Skip to content

Commit 8332f70

Browse files
committed
Record option declaration
Dependency fixes Fix Cpplint Fix
1 parent 7f467a9 commit 8332f70

File tree

4 files changed

+133
-1
lines changed

4 files changed

+133
-1
lines changed

rosbag2_storage/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,8 @@ endif()
2323

2424
find_package(ament_cmake REQUIRED)
2525
find_package(pluginlib REQUIRED)
26+
find_package(rcl_interfaces REQUIRED)
27+
find_package(rclcpp REQUIRED)
2628
find_package(rcpputils REQUIRED)
2729
find_package(rcutils REQUIRED)
2830
find_package(yaml_cpp_vendor REQUIRED)
@@ -45,6 +47,8 @@ target_link_libraries(${PROJECT_NAME}
4547
pluginlib::pluginlib
4648
rcpputils::rcpputils
4749
rcutils::rcutils
50+
rclcpp::rclcpp
51+
${rcl_interfaces_TARGETS}
4852
yaml-cpp
4953
)
5054

rosbag2_storage/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@
1414

1515
<depend>pluginlib</depend>
1616
<depend>rcpputils</depend>
17+
<depend>rcl_interfaces</depend>
18+
<depend>rclcpp</depend>
1719
<depend>rcutils</depend>
1820
<depend>yaml_cpp_vendor</depend>
1921

rosbag2_transport/include/rosbag2_transport/play_options.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,8 @@ void declare_play_options_rw_params(std::shared_ptr<rclcpp::Node> nh, PlayOption
183183

184184
// TODO(roncapat): but I think it's worth to use classic CLI/launchfile remap instead
185185
// po.topic_remapping_options =
186-
// nh->declare_parameter<std::vector<std::string>>("play.topic_remapping_options", empty_str_list);
186+
// nh->declare_parameter<std::vector<std::string>>(
187+
// "play.topic_remapping_options", empty_str_list);
187188

188189
po.clock_publish_frequency = nh->declare_parameter<double>(
189190
"play.clock_publish_frequency",

rosbag2_transport/include/rosbag2_transport/record_options.hpp

Lines changed: 125 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@
1616
#define ROSBAG2_TRANSPORT__RECORD_OPTIONS_HPP_
1717

1818
#include <chrono>
19+
#include <memory>
20+
#include <limits>
1921
#include <string>
2022
#include <unordered_map>
2123
#include <vector>
@@ -50,6 +52,129 @@ struct RecordOptions
5052
bool use_sim_time = false;
5153
};
5254

55+
namespace
56+
{
57+
rcl_interfaces::msg::ParameterDescriptor int_param_description(
58+
std::string description, int64_t min,
59+
int64_t max)
60+
{
61+
rcl_interfaces::msg::ParameterDescriptor d{};
62+
rcl_interfaces::msg::IntegerRange r{};
63+
d.description = description;
64+
r.from_value = min;
65+
r.to_value = max;
66+
d.integer_range.push_back(r);
67+
return d;
68+
}
69+
70+
rcl_interfaces::msg::ParameterDescriptor float_param_description(
71+
std::string description, float min,
72+
float max)
73+
{
74+
rcl_interfaces::msg::ParameterDescriptor d{};
75+
rcl_interfaces::msg::FloatingPointRange r{};
76+
d.description = description;
77+
r.from_value = min;
78+
r.to_value = max;
79+
d.floating_point_range.push_back(r);
80+
return d;
81+
}
82+
} // namespace
83+
84+
void declare_record_options_rw_params(std::shared_ptr<rclcpp::Node> nh, RecordOptions & ro)
85+
{
86+
static const std::vector<std::string> empty_str_list;
87+
88+
ro.all = nh->declare_parameter<bool>(
89+
"record.all",
90+
false);
91+
92+
ro.is_discovery_disabled = nh->declare_parameter<bool>(
93+
"record.is_discovery_disabled",
94+
false);
95+
96+
ro.topics = nh->declare_parameter<std::vector<std::string>>(
97+
"record.topics",
98+
empty_str_list);
99+
100+
ro.rmw_serialization_format = nh->declare_parameter<std::string>(
101+
"record.rmw_serialization_format",
102+
"");
103+
104+
auto desc_tpi = int_param_description(
105+
"Topic polling interval (ms)",
106+
1,
107+
std::numeric_limits<int64_t>::max());
108+
auto topic_polling_interval_ = nh->declare_parameter<int64_t>(
109+
"record.topic_polling_interval",
110+
100,
111+
desc_tpi);
112+
ro.topic_polling_interval = std::chrono::milliseconds{topic_polling_interval_};
113+
114+
ro.regex = nh->declare_parameter<std::string>(
115+
"record.regex",
116+
"");
117+
118+
ro.exclude = nh->declare_parameter<std::string>(
119+
"record.exclude",
120+
"");
121+
122+
ro.node_prefix = nh->declare_parameter<std::string>(
123+
"record.node_prefix",
124+
"");
125+
126+
ro.compression_mode = nh->declare_parameter<std::string>(
127+
"record.compression_mode",
128+
"");
129+
130+
ro.compression_format = nh->declare_parameter<std::string>(
131+
"record.compression_format",
132+
"");
133+
134+
auto desc_cqs = int_param_description(
135+
"Compression queue size (messages)",
136+
1,
137+
std::numeric_limits<int64_t>::max());
138+
auto compression_queue_size_ = nh->declare_parameter<int64_t>(
139+
"record.compression_queue_size",
140+
1,
141+
desc_cqs);
142+
ro.compression_queue_size = std::static_cast<uint64_t>(compression_queue_size_);
143+
144+
auto desc_cts = int_param_description(
145+
"Compression threads",
146+
0,
147+
std::numeric_limits<int64_t>::max());
148+
auto compression_threads_ = nh->declare_parameter<int64_t>(
149+
"record.compression_threads",
150+
0,
151+
desc_cts);
152+
ro.compression_threads = std::static_cast<uint64_t>(compression_threads_);
153+
154+
// TODO(roncapat)
155+
// std::unordered_map<std::string, rclcpp::QoS> topic_qos_profile_overrides{};
156+
157+
ro.include_hidden_topics = nh->declare_parameter<bool>(
158+
"record.include_hidden_topics",
159+
false);
160+
161+
ro.include_unpublished_topics = nh->declare_parameter<bool>(
162+
"record.include_unpublished_topics",
163+
false);
164+
165+
ro.ignore_leaf_topics = nh->declare_parameter<bool>(
166+
"record.ignore_leaf_topics",
167+
false);
168+
169+
ro.start_paused = nh->declare_parameter<bool>(
170+
"record.start_paused",
171+
false);
172+
173+
ro.use_sim_time = nh->declare_parameter<bool>(
174+
"record.use_sim_time",
175+
false);
176+
}
177+
53178
} // namespace rosbag2_transport
54179

55180
namespace YAML

0 commit comments

Comments
 (0)