Skip to content

Commit 2d8fd5f

Browse files
authored
Updated node declare_parameter to new syntax (ros2#882)
- also added required defaults for optional parameters (qos set) Signed-off-by: Adam Dabrowski <[email protected]>
1 parent 7cd143e commit 2d8fd5f

File tree

1 file changed

+21
-20
lines changed

1 file changed

+21
-20
lines changed

rosbag2_performance/rosbag2_performance_benchmarking/src/config_utils.cpp

Lines changed: 21 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -28,13 +28,14 @@ void load_qos_configuration(
2828
PublisherGroupConfig & group_config,
2929
const std::string & group_prefix)
3030
{
31+
unsigned int qos_depth = 10;
32+
std::string qos_reliability = "reliable";
33+
std::string qos_durability = "volatile";
3134
auto qos_prefix = group_prefix + ".qos";
32-
node.declare_parameter(qos_prefix + ".qos_depth");
33-
node.declare_parameter(qos_prefix + ".qos_reliability");
34-
node.declare_parameter(qos_prefix + ".qos_durability");
35+
node.declare_parameter<int>(qos_prefix + ".qos_depth", qos_depth);
36+
node.declare_parameter<std::string>(qos_prefix + ".qos_reliability", qos_reliability);
37+
node.declare_parameter<std::string>(qos_prefix + ".qos_durability", qos_durability);
3538

36-
unsigned int qos_depth = 10;
37-
std::string qos_reliability, qos_durability;
3839
node.get_parameter(qos_prefix + ".qos_depth", qos_depth);
3940
node.get_parameter(qos_prefix + ".qos_reliability", qos_reliability);
4041
node.get_parameter(qos_prefix + ".qos_durability", qos_durability);
@@ -50,7 +51,7 @@ void load_qos_configuration(
5051
bool wait_for_subscriptions_from_node_parameters(rclcpp::Node & node)
5152
{
5253
const std::string parameters_ns = "publishers";
53-
node.declare_parameter(parameters_ns + ".wait_for_subscriptions", true);
54+
node.declare_parameter<bool>(parameters_ns + ".wait_for_subscriptions", true);
5455
bool wait_for_subscriptions;
5556
node.get_parameter(parameters_ns + ".wait_for_subscriptions", wait_for_subscriptions);
5657
return wait_for_subscriptions;
@@ -62,15 +63,15 @@ std::vector<PublisherGroupConfig> publisher_groups_from_node_parameters(
6263
std::vector<PublisherGroupConfig> configurations;
6364
std::vector<std::string> publisher_groups;
6465
const std::string parameters_ns = "publishers";
65-
node.declare_parameter(parameters_ns + ".publisher_groups");
66+
node.declare_parameter<std::vector<std::string>>(parameters_ns + ".publisher_groups");
6667
node.get_parameter(parameters_ns + ".publisher_groups", publisher_groups);
6768
for (const auto & group_name : publisher_groups) {
6869
auto group_prefix = parameters_ns + "." + group_name;
69-
node.declare_parameter(group_prefix + ".publishers_count");
70-
node.declare_parameter(group_prefix + ".topic_root");
71-
node.declare_parameter(group_prefix + ".msg_size_bytes");
72-
node.declare_parameter(group_prefix + ".msg_count_each");
73-
node.declare_parameter(group_prefix + ".rate_hz");
70+
node.declare_parameter<int>(group_prefix + ".publishers_count");
71+
node.declare_parameter<std::string>(group_prefix + ".topic_root");
72+
node.declare_parameter<int>(group_prefix + ".msg_size_bytes");
73+
node.declare_parameter<int>(group_prefix + ".msg_count_each");
74+
node.declare_parameter<int>(group_prefix + ".rate_hz");
7475

7576
PublisherGroupConfig group_config;
7677
node.get_parameter(
@@ -108,14 +109,14 @@ BagConfig bag_config_from_node_parameters(
108109
const std::string default_bag_folder("/tmp/rosbag2_test");
109110
BagConfig bag_config;
110111

111-
node.declare_parameter("storage_id", "sqlite3");
112-
node.declare_parameter("max_cache_size", 10000000);
113-
node.declare_parameter("max_bag_size", 0);
114-
node.declare_parameter("db_folder", default_bag_folder);
115-
node.declare_parameter("storage_config_file", "");
116-
node.declare_parameter("compression_format", "");
117-
node.declare_parameter("compression_queue_size", 1);
118-
node.declare_parameter("compression_threads", 0);
112+
node.declare_parameter<std::string>("storage_id", "sqlite3");
113+
node.declare_parameter<int>("max_cache_size", 10000000);
114+
node.declare_parameter<int>("max_bag_size", 0);
115+
node.declare_parameter<std::string>("db_folder", default_bag_folder);
116+
node.declare_parameter<std::string>("storage_config_file", "");
117+
node.declare_parameter<std::string>("compression_format", "");
118+
node.declare_parameter<int>("compression_queue_size", 1);
119+
node.declare_parameter<int>("compression_threads", 0);
119120

120121
node.get_parameter("storage_id", bag_config.storage_options.storage_id);
121122
node.get_parameter("max_cache_size", bag_config.storage_options.max_cache_size);

0 commit comments

Comments
 (0)