Skip to content

Commit

Permalink
Uncrustify
Browse files Browse the repository at this point in the history
Signed-off-by: Patrick Roncagliolo <[email protected]>
  • Loading branch information
roncapat committed Nov 14, 2023
1 parent 0aa4cd5 commit 68bfcb4
Show file tree
Hide file tree
Showing 6 changed files with 38 additions and 30 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,10 @@ PlayOptions get_play_options_from_node_params(rclcpp::Node * node)
auto playback_until_timestamp_nsec = node->declare_parameter<int32_t>(
"playback_until_timestamp.nsec",
0.0);
play_options.playback_until_timestamp = rclcpp::Duration(playback_until_timestamp_sec, playback_until_timestamp_nsec).nanoseconds();
play_options.playback_until_timestamp = rclcpp::Duration(
playback_until_timestamp_sec,
playback_until_timestamp_nsec).
nanoseconds();

play_options.start_paused = node->declare_parameter<bool>(
"start_paused",
Expand All @@ -184,7 +187,8 @@ PlayOptions get_play_options_from_node_params(rclcpp::Node * node)
auto wait_acked_timeout_nsec = node->declare_parameter<int32_t>(
"wait_acked_timeout.nsec",
0.0);
play_options.wait_acked_timeout = rclcpp::Duration(wait_acked_timeout_sec, wait_acked_timeout_nsec).nanoseconds();
play_options.wait_acked_timeout =
rclcpp::Duration(wait_acked_timeout_sec, wait_acked_timeout_nsec).nanoseconds();

play_options.disable_loan_message = node->declare_parameter<bool>(
"disable_loan_message",
Expand Down Expand Up @@ -218,7 +222,9 @@ RecordOptions get_record_options_from_node_params(rclcpp::Node * node)
auto topic_polling_interval_nsec = node->declare_parameter<int32_t>(
"topic_polling_interval.nsec",
1000000.0);
record_options.topic_polling_interval = rclcpp::Duration(topic_polling_interval_sec, topic_polling_interval_nsec).to_chrono<std::chrono::milliseconds>();
record_options.topic_polling_interval = rclcpp::Duration(
topic_polling_interval_sec,
topic_polling_interval_nsec).to_chrono<std::chrono::milliseconds>();

record_options.regex = node->declare_parameter<std::string>(
"regex",
Expand Down Expand Up @@ -316,7 +322,8 @@ get_storage_options_from_node_params(rclcpp::Node * node)

storage_options.storage_id = node->declare_parameter<std::string>("storage_id", "");

storage_options.storage_config_uri = node->declare_parameter<std::string>("storage_config_uri", "");
storage_options.storage_config_uri =
node->declare_parameter<std::string>("storage_config_uri", "");

auto desc_mbs = param_utils::int_param_description(
"Max bagfile size (bytes)",
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_transport/src/rosbag2_transport/play_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

namespace YAML
{

Node convert<rosbag2_transport::PlayOptions>::encode(
const rosbag2_transport::PlayOptions & play_options)
{
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1376,4 +1376,4 @@ rosbag2_transport::PlayOptions Player::get_play_options()
// Register the component with class_loader.
// This acts as a sort of entry point, allowing the component to be
// discoverable when its library is being loaded into a running process.
RCLCPP_COMPONENTS_REGISTER_NODE(rosbag2_transport::Player)
RCLCPP_COMPONENTS_REGISTER_NODE(rosbag2_transport::Player)
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ TEST_F(TestComponentManager, test_load_components)
auto request = std::make_shared<composition_interfaces::srv::LoadNode::Request>();
request->package_name = "rosbag2_transport";
request->plugin_name = "rosbag2_transport::Player";
for (auto p: pl){
for (auto p: pl) {
request->parameters.push_back(p.to_parameter_msg());
}

Expand Down Expand Up @@ -91,7 +91,7 @@ TEST_F(TestComponentManager, test_load_components)
auto request = std::make_shared<composition_interfaces::srv::LoadNode::Request>();
request->package_name = "rosbag2_transport";
request->plugin_name = "rosbag2_transport::Recorder";
for (auto p: pl){
for (auto p: pl) {
request->parameters.push_back(p.to_parameter_msg());
}

Expand All @@ -109,4 +109,4 @@ TEST_F(TestComponentManager, test_load_components)
EXPECT_EQ(result->full_node_name, "/rosbag2_recorder");
EXPECT_EQ(result->unique_id, 2u);
}
}
}
20 changes: 10 additions & 10 deletions rosbag2_transport/test/rosbag2_transport/test_play_params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,15 +54,15 @@ TEST_F(RosBag2PlayTestFixture, parse_parameter_from_file) {
auto qos_node = YAML::LoadFile(_SRC_RESOURCES_DIR_PATH "/overrides.yaml");

YAML::Emitter emitter;
emitter
<< YAML::Newline << YAML::Comment("params_player.yaml")
<< param_node << YAML::Newline
<< YAML::Newline << YAML::Comment("overrides.yaml")
<< qos_node << YAML::Newline
<< YAML::Newline << YAML::Comment("node play parameters")
<< yaml_play_opt << YAML::Newline
<< YAML::Newline << YAML::Comment("node storage parameters")
<< yaml_storage_opt << YAML::Newline;
emitter
<< YAML::Newline << YAML::Comment("params_player.yaml")
<< param_node << YAML::Newline
<< YAML::Newline << YAML::Comment("overrides.yaml")
<< qos_node << YAML::Newline
<< YAML::Newline << YAML::Comment("node play parameters")
<< yaml_play_opt << YAML::Newline
<< YAML::Newline << YAML::Comment("node storage parameters")
<< yaml_storage_opt << YAML::Newline;

std::cout << emitter.c_str() << std::endl;

Expand All @@ -73,4 +73,4 @@ TEST_F(RosBag2PlayTestFixture, parse_parameter_from_file) {
TEST_F(RosBag2PlayTestFixture, test_negative_durations) {
// TODO(roncapat): implement
}
*/
*/
23 changes: 12 additions & 11 deletions rosbag2_transport/test/rosbag2_transport/test_record_params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,23 +46,24 @@ TEST_F(RosBag2RecordTestFixture, parse_parameter_from_file) {
auto node = std::make_shared<MockRecorder>("recorder_params_node", opts);
auto record_options = node->retrieve_record_options();
auto storage_options = node->retrieve_storage_options();
YAML::Node yaml_record_opt = YAML::convert<rosbag2_transport::RecordOptions>().encode(record_options);
YAML::Node yaml_record_opt = YAML::convert<rosbag2_transport::RecordOptions>().encode(
record_options);
YAML::Node yaml_storage_opt = YAML::convert<rosbag2_storage::StorageOptions>().encode(
storage_options);

auto param_node = YAML::LoadFile(_SRC_RESOURCES_DIR_PATH "/params_recorder.yaml");
auto qos_node = YAML::LoadFile(_SRC_RESOURCES_DIR_PATH "/overrides.yaml");

YAML::Emitter emitter;
emitter
<< YAML::Newline << YAML::Comment("params.yaml")
<< param_node << YAML::Newline
<< YAML::Newline << YAML::Comment("overrides.yaml")
<< qos_node << YAML::Newline
<< YAML::Newline << YAML::Comment("node record parameters")
<< yaml_record_opt << YAML::Newline
<< YAML::Newline << YAML::Comment("node storage parameters")
<< yaml_storage_opt << YAML::Newline;
emitter
<< YAML::Newline << YAML::Comment("params.yaml")
<< param_node << YAML::Newline
<< YAML::Newline << YAML::Comment("overrides.yaml")
<< qos_node << YAML::Newline
<< YAML::Newline << YAML::Comment("node record parameters")
<< yaml_record_opt << YAML::Newline
<< YAML::Newline << YAML::Comment("node storage parameters")
<< yaml_storage_opt << YAML::Newline;

std::cout << emitter.c_str() << std::endl;

Expand All @@ -73,4 +74,4 @@ TEST_F(RosBag2RecordTestFixture, parse_parameter_from_file) {
TEST_F(RosBag2PlayTestFixture, test_negative_durations) {
// TODO(roncapat): implement
}
*/
*/

0 comments on commit 68bfcb4

Please sign in to comment.