Skip to content

Commit

Permalink
Address reivew comments
Browse files Browse the repository at this point in the history
Signed-off-by: Barry Xu <[email protected]>
  • Loading branch information
Barry-Xu-2018 committed Sep 12, 2023
1 parent 3705273 commit 67678ff
Show file tree
Hide file tree
Showing 15 changed files with 107 additions and 55 deletions.
2 changes: 1 addition & 1 deletion docs/message_definition_encoding.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ This set of definitions with all field types recursively included can be called

## `ros2msg` encoding

This encoding consists of definitions in [.msg](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html#message-description-specification) and [.srv](https://docs.ros.org/en/rolling/Concepts/Basic/About-Interfaces.html#services) format, concatenated together in human-readable form with
This encoding consists of definitions in [.msg](https://docs.ros.org/en/rolling/Concepts/Basic/About-Interfaces.html#messages) and [.srv](https://docs.ros.org/en/rolling/Concepts/Basic/About-Interfaces.html#services) format, concatenated together in human-readable form with
a delimiter.

The top-level message definition is present first, with no delimiter. All dependent .msg definitions are preceded by a two-line delimiter:
Expand Down
23 changes: 22 additions & 1 deletion ros2bag/ros2bag/api/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,15 @@ def _split_lines(self, text, width):


def print_error(string: str) -> str:
return '[ERROR] [ros2bag]: {}'.format(string)
return _print_base('ERROR', string)


def print_warn(string: str) -> str:
return _print_base('WARN', string)


def _print_base(print_type: str, string: str) -> str:
return '[{}] [ros2bag]: {}'.format(print_type, string)


def dict_to_duration(time_dict: Optional[Dict[str, int]]) -> Duration:
Expand Down Expand Up @@ -200,3 +208,16 @@ def add_writer_storage_plugin_extensions(parser: ArgumentParser) -> None:
'Settings in this profile can still be overridden by other explicit options '
'and --storage-config-file. Profiles:\n' +
'\n'.join([f'{preset[0]}: {preset[1]}' for preset in preset_profiles]))


def convert_service_to_service_event_topic(services):
services_event_topics = []

if not services:
return services_event_topics

for service in services:
name = '/' + service if service[0] != '/' else service
services_event_topics.append(name + '/_service_event')

return services_event_topics
8 changes: 2 additions & 6 deletions ros2bag/ros2bag/verb/burst.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
from ros2bag.api import add_standard_reader_args
from ros2bag.api import check_not_negative_int
from ros2bag.api import check_positive_float
from ros2bag.api import convert_service_to_service_event_topic
from ros2bag.api import convert_yaml_to_qos_profile
from ros2bag.api import print_error
from ros2bag.verb import VerbExtension
Expand Down Expand Up @@ -95,12 +96,7 @@ def main(self, *, args): # noqa: D102
play_options.rate = 1.0
play_options.topics_to_filter = args.topics
# Convert service name to service event topic name
services = []
if args.services and len(args.services) != 0:
for s in args.services:
name = '/' + s if s[0] != '/' else s
services.append(name + '/_service_event')
play_options.services_to_filter = services
play_options.services_to_filter = convert_service_to_service_event_topic(args.services)
play_options.topic_qos_profile_overrides = qos_profile_overrides
play_options.loop = False
play_options.topic_remapping_options = topic_remapping
Expand Down
31 changes: 22 additions & 9 deletions ros2bag/ros2bag/verb/play.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,10 @@
from ros2bag.api import add_standard_reader_args
from ros2bag.api import check_not_negative_int
from ros2bag.api import check_positive_float
from ros2bag.api import convert_service_to_service_event_topic
from ros2bag.api import convert_yaml_to_qos_profile
from ros2bag.api import print_error
from ros2bag.api import print_warn
from ros2bag.verb import VerbExtension
from ros2cli.node import NODE_NAME_PREFIX
from rosbag2_py import Player
Expand Down Expand Up @@ -54,12 +56,17 @@ def add_arguments(self, parser, cli_name): # noqa: D102
'replayed.')
parser.add_argument(
'--services', type=str, default=[], nargs='+',
help='services to replay, separated by space. At least one service needs to be '
'specified.')
help='services to replay, separated by space. if none specified, all services will '
'be played.')
parser.add_argument(
'-e', '--regex', default='',
help='filter topics by regular expression to replay, separated by space. If none '
'specified, all topics will be replayed.')
parser.add_argument(
'-x', '--exclude', default='',
help='regular expressions to exclude topics from replay, separated by space. If none '
'specified, all topics will be replayed. This argument is deprecated and please '
'use --exclude-topics.')
parser.add_argument(
'--exclude-topics', default='',
help='regular expressions to exclude topics from replay, separated by space. If none '
Expand Down Expand Up @@ -172,6 +179,10 @@ def main(self, *, args): # noqa: D102
except (InvalidQoSProfileException, ValueError) as e:
return print_error(str(e))

if args.exclude and args.exclude_topics:
return print_error(str('-x/--exclude and --exclude_topics cannot be used at the '
'same time.'))

storage_config_file = ''
if args.storage_config_file:
storage_config_file = args.storage_config_file.name
Expand All @@ -193,15 +204,17 @@ def main(self, *, args): # noqa: D102
play_options.topics_to_filter = args.topics

# Convert service name to service event topic name
services = []
if args.services and len(args.services) != 0:
for s in args.services:
name = '/' + s if s[0] != '/' else s
services.append(name + '/_service_event')
play_options.services_to_filter = services
play_options.services_to_filter = convert_service_to_service_event_topic(args.services)

play_options.regex_to_filter = args.regex
play_options.topics_regex_to_exclude = args.exclude_topics

if args.exclude:
print(print_warn(str('-x/--exclude argument is deprecated. Please use '
'--exclude-topics.')))
play_options.topics_regex_to_exclude = args.exclude
else:
play_options.topics_regex_to_exclude = args.exclude_topics

if args.exclude_services:
play_options.services_regex_to_exclude = args.exclude_services + '/_service_event'
else:
Expand Down
16 changes: 9 additions & 7 deletions ros2bag/ros2bag/verb/record.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

from rclpy.qos import InvalidQoSProfileException
from ros2bag.api import add_writer_storage_plugin_extensions
from ros2bag.api import convert_service_to_service_event_topic
from ros2bag.api import convert_yaml_to_qos_profile
from ros2bag.api import print_error
from ros2bag.api import SplitLineFormatter
Expand Down Expand Up @@ -183,11 +184,17 @@ def add_arguments(self, parser, cli_name): # noqa: D102
help='Choose the compression format/algorithm. '
'Has no effect if no compression mode is chosen. Default: %(default)s.')

def main(self, *, args): # noqa: D102
def _check_necessary_argument(self, args):
# One options out of --all, --all-topics, --all-services, --services, topics or --regex
# must be used
if not (args.all or args.all_topics or args.all_services or
args.services or (args.topics and len(args.topics) > 0) or args.regex):
return False
return True

def main(self, *, args): # noqa: D102

if not self._check_necessary_argument(args):
return print_error('Must specify only one option out of --all, --all-topics, '
'--all-services, --services, topics and --regex')

Expand Down Expand Up @@ -286,12 +293,7 @@ def main(self, *, args): # noqa: D102
record_options.all_services = args.all_services or args.all

# Convert service name to service event topic name
services = []
if args.services and len(args.services) != 0:
for s in args.services:
name = '/' + s if s[0] != '/' else s
services.append(name + '/_service_event')
record_options.services = services
record_options.services = convert_service_to_service_event_topic(args.services)

recorder = Recorder()

Expand Down
6 changes: 3 additions & 3 deletions rosbag2_cpp/include/rosbag2_cpp/info.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,14 +26,14 @@
namespace rosbag2_cpp
{

typedef struct
typedef ROSBAG2_CPP_PUBLIC_TYPE struct rosbag2_service_info_t
{
std::string name;
std::string type;
std::string serialization_format;
size_t request_count;
size_t response_count;
} service_info;
} rosbag2_service_info_t;

class ROSBAG2_CPP_PUBLIC Info
{
Expand All @@ -43,7 +43,7 @@ class ROSBAG2_CPP_PUBLIC Info
virtual rosbag2_storage::BagMetadata read_metadata(
const std::string & uri, const std::string & storage_id = "");

virtual std::vector<std::shared_ptr<service_info>> read_service_info(
virtual std::vector<std::shared_ptr<rosbag2_service_info_t>> read_service_info(
const std::string & uri, const std::string & storage_id = "");
};

Expand Down
20 changes: 15 additions & 5 deletions rosbag2_cpp/include/rosbag2_cpp/service_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,25 @@

#include <string>

#include "rosbag2_cpp/visibility_control.hpp"

namespace rosbag2_cpp
{
bool is_service_event_topic(const std::string & topic, const std::string & topic_type);
ROSBAG2_CPP_PUBLIC
bool
is_service_event_topic(const std::string & topic, const std::string & topic_type);

std::string service_event_topic_name_to_service_name(const std::string & topic_name);
ROSBAG2_CPP_PUBLIC
std::string
service_event_topic_name_to_service_name(const std::string & topic_name);

std::string service_event_topic_type_to_service_type(const std::string & topic_type);
ROSBAG2_CPP_PUBLIC
std::string
service_event_topic_type_to_service_type(const std::string & topic_type);

size_t get_serialization_size_for_service_metadata_event();
}
ROSBAG2_CPP_PUBLIC
size_t
get_serialization_size_for_service_metadata_event();
} // namespace rosbag2_cpp

#endif // ROSBAG2_CPP__SERVICE_UTILS_HPP_
12 changes: 6 additions & 6 deletions rosbag2_cpp/src/rosbag2_cpp/info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <map>
#include "rosbag2_cpp/info.hpp"

#include <unordered_map>
#include <unordered_set>
#include <stdexcept>
Expand All @@ -22,7 +23,6 @@
#include "rmw/rmw.h"

#include "rcpputils/filesystem_helper.hpp"
#include "rosbag2_cpp/info.hpp"
#include "rosbag2_cpp/service_utils.hpp"
#include "rosbag2_storage/logging.hpp"
#include "rosbag2_storage/metadata_io.hpp"
Expand Down Expand Up @@ -84,7 +84,7 @@ struct service_req_resp_info
};
} // namespace

std::vector<std::shared_ptr<service_info>> Info::read_service_info(
std::vector<std::shared_ptr<rosbag2_service_info_t>> Info::read_service_info(
const std::string & uri, const std::string & storage_id)
{
rosbag2_storage::StorageFactory factory;
Expand All @@ -96,13 +96,13 @@ std::vector<std::shared_ptr<service_info>> Info::read_service_info(
using service_analysis =
std::unordered_map<std::string, std::shared_ptr<service_req_resp_info>>;

std::unordered_map<std::string, std::shared_ptr<service_info>> all_service_info;
std::unordered_map<std::string, std::shared_ptr<rosbag2_service_info_t>> all_service_info;
service_analysis service_process_info;

auto all_topics_types = storage->get_all_topics_and_types();
for (auto & t : all_topics_types) {
if (is_service_event_topic(t.name, t.type)) {
auto service_info = std::make_shared<rosbag2_cpp::service_info>();
auto service_info = std::make_shared<rosbag2_cpp::rosbag2_service_info_t>();
service_info->name = service_event_topic_name_to_service_name(t.name);
service_info->type = service_event_topic_type_to_service_type(t.type);
service_info->serialization_format = t.serialization_format;
Expand All @@ -111,7 +111,7 @@ std::vector<std::shared_ptr<service_info>> Info::read_service_info(
}
}

std::vector<std::shared_ptr<service_info>> ret_service_info;
std::vector<std::shared_ptr<rosbag2_service_info_t>> ret_service_info;

if (!all_service_info.empty()) {
auto msg = service_msgs::msg::ServiceEventInfo();
Expand Down
12 changes: 8 additions & 4 deletions rosbag2_cpp/src/rosbag2_cpp/service_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,11 +46,15 @@ bool is_service_event_topic(const std::string & topic, const std::string & topic
return false;
}

std::string end_topic_type = topic_type.substr(
topic_type.length() - std::strlen(service_event_topic_type_postfix));
if (topic_type.length() <= std::strlen(service_event_topic_type_postfix)) {
return false;
}

return end_topic_name == RCL_SERVICE_INTROSPECTION_TOPIC_POSTFIX &&
end_topic_type == service_event_topic_type_postfix;
return (topic_type.compare(
topic_type.length() - std::strlen(service_event_topic_type_postfix),
std::strlen(service_event_topic_type_postfix),
service_event_topic_type_postfix) == 0) &&
(end_topic_name == RCL_SERVICE_INTROSPECTION_TOPIC_POSTFIX);
}

std::string service_event_topic_name_to_service_name(const std::string & topic_name)
Expand Down
4 changes: 1 addition & 3 deletions rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,9 +200,7 @@ void SequentialWriter::create_topic(const rosbag2_storage::TopicMetadata & topic
std::string topic_type;
if (is_service_event_topic(topic_with_type.name, topic_with_type.type)) {
// change service event type to service type for next step to get message definition
topic_type = topic_with_type.type.substr(
0,
topic_with_type.type.length() - strlen("_Event"));
topic_type = service_event_topic_type_to_service_type(topic_with_type.type);
} else {
topic_type = topic_with_type.type;
}
Expand Down
7 changes: 4 additions & 3 deletions rosbag2_cpp/test/rosbag2_cpp/test_service_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <gmock/gmock.h>

#include <string>
#include <tuple>
#include <vector>

#include "rosbag2_cpp/service_utils.hpp"
Expand All @@ -26,7 +27,7 @@ class ServiceUtilsTest : public Test

TEST_F(ServiceUtilsTest, check_is_service_event_topic)
{
std::vector<std::pair<std::pair<std::string, std::string>, bool>> all_test_data =
std::vector<std::pair<std::tuple<std::string, std::string>, bool>> all_test_data =
{
{{"/abc/_service_event", "package/srv/xyz_Event"}, true},
{{"/_service_event", "package/srv/xyz_Event"}, false},
Expand All @@ -37,8 +38,8 @@ TEST_F(ServiceUtilsTest, check_is_service_event_topic)

for (const auto & test_data : all_test_data) {
EXPECT_TRUE(
rosbag2_cpp::is_service_event_topic(test_data.first.first, test_data.first.second) ==
test_data.second);
rosbag2_cpp::is_service_event_topic(
std::get<0>(test_data.first), std::get<1>(test_data.first)) == test_data.second);
}
}

Expand Down
2 changes: 1 addition & 1 deletion rosbag2_py/src/rosbag2_py/_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class Info
{
auto metadata_info = read_metadata(uri, storage_id);

std::vector<std::shared_ptr<rosbag2_cpp::service_info>> all_services_info;
std::vector<std::shared_ptr<rosbag2_cpp::rosbag2_service_info_t>> all_services_info;
for (auto & file_info : metadata_info.files) {
auto services_info = info_->read_service_info(
uri + "/" + file_info.path,
Expand Down
5 changes: 3 additions & 2 deletions rosbag2_py/src/rosbag2_py/format_service_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,8 @@
#include "format_service_info.hpp"

std::string
format_service_info(std::vector<std::shared_ptr<rosbag2_cpp::service_info>> & service_info_list)
format_service_info(
std::vector<std::shared_ptr<rosbag2_cpp::rosbag2_service_info_t>> & service_info_list)
{
std::stringstream info_stream;
int indentation_spaces = 21;
Expand All @@ -29,7 +30,7 @@ format_service_info(std::vector<std::shared_ptr<rosbag2_cpp::service_info>> & se
}

auto print_service_info =
[&info_stream](const std::shared_ptr<rosbag2_cpp::service_info> & si) -> void {
[&info_stream](const std::shared_ptr<rosbag2_cpp::rosbag2_service_info_t> & si) -> void {
info_stream << "Service: " << si->name << " | ";
info_stream << "Type: " << si->type << " | ";
info_stream << "Request Count: " << si->request_count << " | ";
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_py/src/rosbag2_py/format_service_info.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,6 @@
#include "rosbag2_cpp/info.hpp"

std::string format_service_info(
std::vector<std::shared_ptr<rosbag2_cpp::service_info>> & service_info);
std::vector<std::shared_ptr<rosbag2_cpp::rosbag2_service_info_t>> & service_info);

#endif // ROSBAG2_PY__FORMAT_SERVICE_INFO_HPP_
Loading

0 comments on commit 67678ff

Please sign in to comment.