diff --git a/composition/src/server_component.cpp b/composition/src/server_component.cpp index 052f77708..3ba38e8b0 100644 --- a/composition/src/server_component.cpp +++ b/composition/src/server_component.cpp @@ -33,7 +33,8 @@ Server::Server(const rclcpp::NodeOptions & options) std::shared_ptr response ) -> void { - RCLCPP_INFO(this->get_logger(), "Incoming request: [a: %" PRId64 ", b: %" PRId64 "]", + RCLCPP_INFO( + this->get_logger(), "Incoming request: [a: %" PRId64 ", b: %" PRId64 "]", request->a, request->b); std::flush(std::cout); response->sum = request->a + request->b; diff --git a/demo_nodes_cpp/src/parameters/even_parameters_node.cpp b/demo_nodes_cpp/src/parameters/even_parameters_node.cpp index 054561779..37cd4adbf 100644 --- a/demo_nodes_cpp/src/parameters/even_parameters_node.cpp +++ b/demo_nodes_cpp/src/parameters/even_parameters_node.cpp @@ -42,22 +42,23 @@ class EvenParameterNode : public rclcpp::Node for (auto parameter : parameters) { rclcpp::ParameterType parameter_type = parameter.get_type(); if (rclcpp::ParameterType::PARAMETER_NOT_SET == parameter_type) { - RCLCPP_INFO(this->get_logger(), - "parameter '%s' deleted successfully", + RCLCPP_INFO( + this->get_logger(), "parameter '%s' deleted successfully", parameter.get_name().c_str() ); result.successful &= true; } else if (rclcpp::ParameterType::PARAMETER_INTEGER == parameter_type) { if (parameter.as_int() % 2 != 0) { - RCLCPP_INFO(this->get_logger(), - "Requested value '%d' for parameter '%s' is not an even number:" - " rejecting change...", + RCLCPP_INFO( + this->get_logger(), "Requested value '%d' for parameter '%s' " + "is not an even number: rejecting change...", parameter.as_int(), parameter.get_name().c_str() ); result.successful = false; } else { - RCLCPP_INFO(this->get_logger(), + RCLCPP_INFO( + this->get_logger(), "parameter '%s' has changed and is now: %s", parameter.get_name().c_str(), parameter.value_to_string().c_str() @@ -65,8 +66,8 @@ class EvenParameterNode : public rclcpp::Node result.successful &= true; } } else { - RCLCPP_INFO(this->get_logger(), - "only integer parameters can be set\n" + RCLCPP_INFO( + this->get_logger(), "only integer parameters can be set\n" "requested value for parameter '%s' is not an even number, rejecting change...", parameter.get_name().c_str() ); diff --git a/demo_nodes_cpp/src/parameters/list_parameters.cpp b/demo_nodes_cpp/src/parameters/list_parameters.cpp index ef429544f..2b89fe429 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters.cpp @@ -52,7 +52,8 @@ class ListParameters : public rclcpp::Node RCLCPP_INFO(this->get_logger(), "Setting parameters..."); // Set several different types of parameters. - auto set_parameters_results = parameters_client->set_parameters({ + auto set_parameters_results = parameters_client->set_parameters( + { rclcpp::Parameter("foo", 2), rclcpp::Parameter("bar", "hello"), rclcpp::Parameter("baz", 1.45), diff --git a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp index e8eeb3996..5a566bd55 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp @@ -49,7 +49,8 @@ int main(int argc, char ** argv) RCLCPP_INFO(node->get_logger(), "Setting parameters..."); // Set several differnet types of parameters. - auto results = parameters_client->set_parameters({ + auto results = parameters_client->set_parameters( + { rclcpp::Parameter("foo", 2), rclcpp::Parameter("bar", "hello"), rclcpp::Parameter("baz", 1.45), diff --git a/demo_nodes_cpp/src/parameters/parameter_blackboard.cpp b/demo_nodes_cpp/src/parameters/parameter_blackboard.cpp index 089bbc9b4..9170e9243 100644 --- a/demo_nodes_cpp/src/parameters/parameter_blackboard.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_blackboard.cpp @@ -36,7 +36,8 @@ class ParameterBlackboard : public rclcpp::Node options.allow_undeclared_parameters(true). automatically_declare_parameters_from_overrides(true)) { - RCLCPP_INFO(this->get_logger(), + RCLCPP_INFO( + this->get_logger(), "Parameter blackboard node named '%s' ready, and serving '%zu' parameters already!", this->get_fully_qualified_name(), this->list_parameters( {}, rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE).names.size()); diff --git a/demo_nodes_cpp/src/parameters/parameter_events.cpp b/demo_nodes_cpp/src/parameters/parameter_events.cpp index 437061874..3b7c916e6 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events.cpp @@ -84,7 +84,8 @@ int main(int argc, char ** argv) node->declare_parameter("foobar"); // Set several different types of parameters. - auto set_parameters_results = parameters_client->set_parameters({ + auto set_parameters_results = parameters_client->set_parameters( + { rclcpp::Parameter("foo", 2), rclcpp::Parameter("bar", "hello"), rclcpp::Parameter("baz", 1.45), @@ -92,7 +93,8 @@ int main(int argc, char ** argv) }); // Change the value of some of them. - set_parameters_results = parameters_client->set_parameters({ + set_parameters_results = parameters_client->set_parameters( + { rclcpp::Parameter("foo", 3), rclcpp::Parameter("bar", "world"), }); diff --git a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp index a5a2848e7..eb56879ba 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp @@ -71,10 +71,11 @@ class ParameterEventsAsyncNode : public rclcpp::Node // Queue a `set_parameters` request as soon as `spin` is called on this node. // TODO(dhood): consider adding a "call soon" notion to Node to not require a timer for this. - timer_ = create_wall_timer(200ms, - [this]() { - this->queue_first_set_parameter_request(); - }); + timer_ = create_wall_timer( + 200ms, + [this]() { + this->queue_first_set_parameter_request(); + }); } private: @@ -101,7 +102,8 @@ class ParameterEventsAsyncNode : public rclcpp::Node this->queue_second_set_parameter_request(); }; - parameters_client_->set_parameters({ + parameters_client_->set_parameters( + { rclcpp::Parameter("foo", 2), rclcpp::Parameter("bar", "hello"), rclcpp::Parameter("baz", 1.45), @@ -123,12 +125,14 @@ class ParameterEventsAsyncNode : public rclcpp::Node // TODO(wjwwood): Create and use delete_parameter // Give time for all of the ParameterEvent callbacks to be received. - timer_ = create_wall_timer(100ms, - []() { - rclcpp::shutdown(); - }); + timer_ = create_wall_timer( + 100ms, + []() { + rclcpp::shutdown(); + }); }; - parameters_client_->set_parameters({ + parameters_client_->set_parameters( + { rclcpp::Parameter("foo", 3), rclcpp::Parameter("bar", "world"), }, response_received_callback); diff --git a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp index c46d202c4..48a81beaa 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp @@ -52,7 +52,8 @@ class SetAndGetParameters : public rclcpp::Node } // Set several different types of parameters. - auto set_parameters_results = parameters_client->set_parameters({ + auto set_parameters_results = parameters_client->set_parameters( + { rclcpp::Parameter("foo", 2), rclcpp::Parameter("bar", "hello"), rclcpp::Parameter("baz", 1.45), @@ -69,8 +70,9 @@ class SetAndGetParameters : public rclcpp::Node std::stringstream ss; // Get a few of the parameters just set. - for (auto & parameter : parameters_client->get_parameters({"foo", "baz", - "foobarbaz", "toto"})) + for ( + auto & parameter : parameters_client->get_parameters( + {"foo", "baz", "foobarbaz", "toto"})) { ss << "\nParameter name: " << parameter.get_name(); ss << "\nParameter value (" << parameter.get_type_name() << "): " << diff --git a/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp b/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp index fd30dc202..b7eeaf5a2 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp @@ -48,7 +48,8 @@ int main(int argc, char ** argv) } // Set several different types of parameters. - auto results = parameters_client->set_parameters({ + auto results = parameters_client->set_parameters( + { rclcpp::Parameter("foo", 2), rclcpp::Parameter("bar", "hello"), rclcpp::Parameter("baz", 1.45), diff --git a/demo_nodes_cpp/src/services/add_two_ints_server.cpp b/demo_nodes_cpp/src/services/add_two_ints_server.cpp index 14b4a46d9..db5fafda9 100644 --- a/demo_nodes_cpp/src/services/add_two_ints_server.cpp +++ b/demo_nodes_cpp/src/services/add_two_ints_server.cpp @@ -39,7 +39,8 @@ class ServerNode : public rclcpp::Node std::shared_ptr response) -> void { (void)request_header; - RCLCPP_INFO(this->get_logger(), "Incoming request\na: %" PRId64 " b: %" PRId64, + RCLCPP_INFO( + this->get_logger(), "Incoming request\na: %" PRId64 " b: %" PRId64, request->a, request->b); response->sum = request->a + request->b; }; diff --git a/demo_nodes_cpp/src/timers/one_off_timer.cpp b/demo_nodes_cpp/src/timers/one_off_timer.cpp index deb844712..723fb654a 100644 --- a/demo_nodes_cpp/src/timers/one_off_timer.cpp +++ b/demo_nodes_cpp/src/timers/one_off_timer.cpp @@ -40,10 +40,11 @@ class OneOffTimerNode : public rclcpp::Node RCLCPP_INFO(this->get_logger(), "in periodic_timer callback"); if (this->count++ % 3 == 0) { RCLCPP_INFO(this->get_logger(), " resetting one off timer"); - this->one_off_timer = this->create_wall_timer(1s, [this]() { - RCLCPP_INFO(this->get_logger(), "in one_off_timer callback"); - this->one_off_timer->cancel(); - }); + this->one_off_timer = this->create_wall_timer( + 1s, [this]() { + RCLCPP_INFO(this->get_logger(), "in one_off_timer callback"); + this->one_off_timer->cancel(); + }); } else { RCLCPP_INFO(this->get_logger(), " not resetting one off timer"); } diff --git a/demo_nodes_cpp/src/topics/allocator_tutorial.cpp b/demo_nodes_cpp/src/topics/allocator_tutorial.cpp index 2f2e14a72..56547139f 100644 --- a/demo_nodes_cpp/src/topics/allocator_tutorial.cpp +++ b/demo_nodes_cpp/src/topics/allocator_tutorial.cpp @@ -143,7 +143,8 @@ int main(int argc, char ** argv) std::list keys = {"intra", "intraprocess", "intra-process", "intra_process"}; bool intra_process = false; - printf("This simple demo shows off a custom memory allocator to count all\n" + printf( + "This simple demo shows off a custom memory allocator to count all\n" "instances of new/delete in the program. It can be run in either regular\n" "mode (no arguments), or in intra-process mode (by passing 'intra' as a\n" "command-line argument)'. It will then publish a message to the\n" diff --git a/image_tools/src/burger.cpp b/image_tools/src/burger.cpp index 09c6419b9..f3cc85b67 100644 --- a/image_tools/src/burger.cpp +++ b/image_tools/src/burger.cpp @@ -126,12 +126,14 @@ cv::Mat & Burger::render_burger(size_t width, size_t height) } burger_buf = cv::Scalar(0, 0, 0); for (int b = 0; b < static_cast(x.size()); b++) { - burger_template.copyTo(burger_buf(cv::Rect( - x[b], - y[b], - burger_template.size().height, - burger_template.size().width - )), burger_mask); + burger_template.copyTo( + burger_buf( + cv::Rect( + x[b], + y[b], + burger_template.size().height, + burger_template.size().width + )), burger_mask); x[b] += x_inc[b]; y[b] += y_inc[b]; // bounce as needed diff --git a/lifecycle/src/lifecycle_listener.cpp b/lifecycle/src/lifecycle_listener.cpp index 6c8c07b18..4a2d566f4 100644 --- a/lifecycle/src/lifecycle_listener.cpp +++ b/lifecycle/src/lifecycle_listener.cpp @@ -38,8 +38,9 @@ class LifecycleListener : public rclcpp::Node : Node(node_name) { // Data topic from the lc_talker node - sub_data_ = this->create_subscription("lifecycle_chatter", 10, - std::bind(&LifecycleListener::data_callback, this, std::placeholders::_1)); + sub_data_ = this->create_subscription( + "lifecycle_chatter", 10, + std::bind(&LifecycleListener::data_callback, this, std::placeholders::_1)); // Notification event topic. All state changes // are published here as TransitionEvents with @@ -57,7 +58,8 @@ class LifecycleListener : public rclcpp::Node void notification_callback(const lifecycle_msgs::msg::TransitionEvent::SharedPtr msg) { - RCLCPP_INFO(get_logger(), "notify callback: Transition from state %s to %s", + RCLCPP_INFO( + get_logger(), "notify callback: Transition from state %s to %s", msg->start_state.label.c_str(), msg->goal_state.label.c_str()); } diff --git a/lifecycle/src/lifecycle_service_client.cpp b/lifecycle/src/lifecycle_service_client.cpp index a1510700d..f3e8acee7 100644 --- a/lifecycle/src/lifecycle_service_client.cpp +++ b/lifecycle/src/lifecycle_service_client.cpp @@ -120,7 +120,8 @@ class LifecycleServiceClient : public rclcpp::Node // We have an succesful answer. So let's print the current state. if (future_result.get()) { - RCLCPP_INFO(get_logger(), "Node %s has current state %s.", + RCLCPP_INFO( + get_logger(), "Node %s has current state %s.", lifecycle_node, future_result.get()->current_state.label.c_str()); return future_result.get()->current_state.id; } else { @@ -317,8 +318,9 @@ int main(int argc, char ** argv) rclcpp::executors::SingleThreadedExecutor exe; exe.add_node(lc_client); - std::shared_future script = std::async(std::launch::async, - std::bind(callee_script, lc_client)); + std::shared_future script = std::async( + std::launch::async, + std::bind(callee_script, lc_client)); exe.spin_until_future_complete(script); rclcpp::shutdown(); diff --git a/pendulum_control/include/pendulum_control/pendulum_motor.hpp b/pendulum_control/include/pendulum_control/pendulum_motor.hpp index 71656fc1c..886b4e344 100644 --- a/pendulum_control/include/pendulum_control/pendulum_motor.hpp +++ b/pendulum_control/include/pendulum_control/pendulum_motor.hpp @@ -82,7 +82,8 @@ class PendulumMotor thread_param.sched_priority = 90; pthread_attr_setschedparam(&thread_attr_, &thread_param); pthread_attr_setschedpolicy(&thread_attr_, SCHED_RR); - pthread_create(&physics_update_thread_, &thread_attr_, + pthread_create( + &physics_update_thread_, &thread_attr_, &pendulum_control::PendulumMotor::physics_update_wrapper, this); } diff --git a/pendulum_control/src/pendulum_teleop.cpp b/pendulum_control/src/pendulum_teleop.cpp index 5e99949da..2c1b1dda5 100644 --- a/pendulum_control/src/pendulum_teleop.cpp +++ b/pendulum_control/src/pendulum_teleop.cpp @@ -34,7 +34,8 @@ int main(int argc, char * argv[]) double command = M_PI / 2; if (argc < 2) { - fprintf(stderr, + fprintf( + stderr, "Command argument not specified. Setting command to 90 degrees (PI/2 radians).\n"); } else { command = atof(argv[1]); diff --git a/quality_of_service_demo/rclcpp/src/deadline.cpp b/quality_of_service_demo/rclcpp/src/deadline.cpp index 52edd3f84..06e2fc8cd 100644 --- a/quality_of_service_demo/rclcpp/src/deadline.cpp +++ b/quality_of_service_demo/rclcpp/src/deadline.cpp @@ -34,7 +34,8 @@ static const size_t DEFAULT_PAUSE_FOR = 1000; void print_usage() { printf("Usage for deadline:\n"); - printf("deadline " + printf( + "deadline " "deadline_duration " "[%s publish_for] " "[%s pause_for] " @@ -42,15 +43,18 @@ void print_usage() OPTION_PUBLISH_FOR, OPTION_PAUSE_FOR); printf("required arguments:\n"); - printf("deadline_duration: " + printf( + "deadline_duration: " "Duration in positive integer milliseconds of the Deadline QoS setting.\n"); printf("optional arguments:\n"); printf("-h : Print this help message.\n"); - printf("%s publish_for : " + printf( + "%s publish_for : " "Duration to publish (in positive integer milliseconds) until pausing the talker. " "Defaults to %zu.\n", OPTION_PUBLISH_FOR, DEFAULT_PUBLISH_FOR); - printf("%s pause_for : " + printf( + "%s pause_for : " "Duration to pause (in positive integer milliseconds) before starting to publish again. " "Defaults to %zu.\n", OPTION_PAUSE_FOR, DEFAULT_PAUSE_FOR); @@ -94,8 +98,8 @@ int main(int argc, char * argv[]) talker->get_options().event_callbacks.deadline_callback = [node = talker.get()](rclcpp::QOSDeadlineOfferedInfo & event) -> void { - RCLCPP_INFO(node->get_logger(), - "Offered deadline missed - total %d delta %d", + RCLCPP_INFO( + node->get_logger(), "Offered deadline missed - total %d delta %d", event.total_count, event.total_count_change); }; @@ -103,8 +107,8 @@ int main(int argc, char * argv[]) listener->get_options().event_callbacks.deadline_callback = [node = listener.get()](rclcpp::QOSDeadlineRequestedInfo & event) -> void { - RCLCPP_INFO(node->get_logger(), - "Requested deadline missed - total %d delta %d", + RCLCPP_INFO( + node->get_logger(), "Requested deadline missed - total %d delta %d", event.total_count, event.total_count_change); }; diff --git a/quality_of_service_demo/rclcpp/src/interactive_publisher.cpp b/quality_of_service_demo/rclcpp/src/interactive_publisher.cpp index ee335b0af..da2787524 100644 --- a/quality_of_service_demo/rclcpp/src/interactive_publisher.cpp +++ b/quality_of_service_demo/rclcpp/src/interactive_publisher.cpp @@ -115,12 +115,14 @@ int main(int argc, char * argv[]) return 0; } if (rcutils_cli_option_exist(argv, argv + argc, OPTION_PUBLISH_DELAY)) { - publish_delay = std::chrono::milliseconds(static_cast(1000 * - std::stof(rcutils_cli_get_option(argv, argv + argc, OPTION_PUBLISH_DELAY)))); + publish_delay = std::chrono::milliseconds( + static_cast(1000 * + std::stof(rcutils_cli_get_option(argv, argv + argc, OPTION_PUBLISH_DELAY)))); } if (rcutils_cli_option_exist(argv, argv + argc, OPTION_DEADLINE_PERIOD)) { - auto period = std::chrono::milliseconds(static_cast(1000 * - std::stof(rcutils_cli_get_option(argv, argv + argc, OPTION_DEADLINE_PERIOD)))); + auto period = std::chrono::milliseconds( + static_cast(1000 * + std::stof(rcutils_cli_get_option(argv, argv + argc, OPTION_DEADLINE_PERIOD)))); qos_settings.deadline(period); } if (rcutils_cli_option_exist(argv, argv + argc, OPTION_LIVELINESS_KIND)) { @@ -138,20 +140,23 @@ int main(int argc, char * argv[]) } } if (rcutils_cli_option_exist(argv, argv + argc, OPTION_LEASE_DURATION)) { - auto duration = std::chrono::milliseconds(static_cast(1000 * - std::stof(rcutils_cli_get_option(argv, argv + argc, OPTION_LEASE_DURATION)))); + auto duration = std::chrono::milliseconds( + static_cast(1000 * + std::stof(rcutils_cli_get_option(argv, argv + argc, OPTION_LEASE_DURATION)))); qos_settings.liveliness_lease_duration(duration); } auto talker = std::make_shared(qos_settings, DEFAULT_TOPIC_NAME, 0, publish_delay); talker->get_options().event_callbacks.deadline_callback = [node = talker.get()](rclcpp::QOSDeadlineOfferedInfo & event) { - RCLCPP_INFO(node->get_logger(), "Deadline missed - total %d (delta %d)", + RCLCPP_INFO( + node->get_logger(), "Deadline missed - total %d (delta %d)", event.total_count, event.total_count_change); }; talker->get_options().event_callbacks.liveliness_callback = [node = talker.get()](rclcpp::QOSLivelinessLostInfo & event) { - RCLCPP_INFO(node->get_logger(), "Liveliness lost - total %d (delta %d)", + RCLCPP_INFO( + node->get_logger(), "Liveliness lost - total %d (delta %d)", event.total_count, event.total_count_change); }; diff --git a/quality_of_service_demo/rclcpp/src/interactive_subscriber.cpp b/quality_of_service_demo/rclcpp/src/interactive_subscriber.cpp index a3fbf8991..8bbf5bb2d 100644 --- a/quality_of_service_demo/rclcpp/src/interactive_subscriber.cpp +++ b/quality_of_service_demo/rclcpp/src/interactive_subscriber.cpp @@ -96,8 +96,9 @@ int main(int argc, char * argv[]) return 0; } if (rcutils_cli_option_exist(argv, argv + argc, OPTION_DEADLINE_PERIOD)) { - auto period = std::chrono::milliseconds(static_cast(1000 * - std::stof(rcutils_cli_get_option(argv, argv + argc, OPTION_DEADLINE_PERIOD)))); + auto period = std::chrono::milliseconds( + static_cast(1000 * + std::stof(rcutils_cli_get_option(argv, argv + argc, OPTION_DEADLINE_PERIOD)))); qos_settings.deadline(period); } if (rcutils_cli_option_exist(argv, argv + argc, OPTION_LIVELINESS_KIND)) { @@ -115,20 +116,23 @@ int main(int argc, char * argv[]) } } if (rcutils_cli_option_exist(argv, argv + argc, OPTION_LEASE_DURATION)) { - auto duration = std::chrono::milliseconds(static_cast(1000 * - std::stof(rcutils_cli_get_option(argv, argv + argc, OPTION_LEASE_DURATION)))); + auto duration = std::chrono::milliseconds( + static_cast(1000 * + std::stof(rcutils_cli_get_option(argv, argv + argc, OPTION_LEASE_DURATION)))); qos_settings.liveliness_lease_duration(duration); } auto listener = std::make_shared(qos_settings); listener->get_options().event_callbacks.deadline_callback = [node = listener.get()](rclcpp::QOSDeadlineRequestedInfo & event) { - RCLCPP_INFO(node->get_logger(), "Deadline missed - total %d (delta %d)", + RCLCPP_INFO( + node->get_logger(), "Deadline missed - total %d (delta %d)", event.total_count, event.total_count_change); }; listener->get_options().event_callbacks.liveliness_callback = [node = listener.get()](rclcpp::QOSLivelinessChangedInfo & event) { - RCLCPP_INFO(node->get_logger(), "Liveliness changed - alive %d (delta %d)," + RCLCPP_INFO( + node->get_logger(), "Liveliness changed - alive %d (delta %d)," " not alive %d (delta %d)", event.alive_count, event.alive_count_change, event.not_alive_count, event.not_alive_count_change); }; diff --git a/quality_of_service_demo/rclcpp/src/lifespan.cpp b/quality_of_service_demo/rclcpp/src/lifespan.cpp index d1d59f848..f33c21b0c 100644 --- a/quality_of_service_demo/rclcpp/src/lifespan.cpp +++ b/quality_of_service_demo/rclcpp/src/lifespan.cpp @@ -34,7 +34,8 @@ static const size_t DEFAULT_SUBSCRIBE_AFTER = 5000; void print_usage() { printf("Usage for lifespan:\n"); - printf("lifespan " + printf( + "lifespan " "lifespan_duration " "[%s history_depth] " "[%s publish_count] " @@ -44,20 +45,24 @@ void print_usage() OPTION_PUBLISH_COUNT, OPTION_SUBSCRIBE_AFTER); printf("required arguments:\n"); - printf("lifespan duration: " + printf( + "lifespan duration: " "Duration in positive integer milliseconds of the Lifespan QoS setting.\n"); printf("optional arguments:\n"); printf("-h : Print this help message.\n"); - printf("%s history : " + printf( + "%s history : " "The depth of the Publisher's history queue - " "the maximum number of messages it will store for late-joining subscriptions. " "Defaults to %zu\n", OPTION_HISTORY, DEFAULT_HISTORY); - printf("%s publish_n_messages : " + printf( + "%s publish_n_messages : " "How many messages to publish before stopping. " "Defaults to %zu\n", OPTION_PUBLISH_COUNT, DEFAULT_PUBLISH_COUNT); - printf("%s subscribe_after_duration : " + printf( + "%s subscribe_after_duration : " "The Subscriber will be created this long in positive integer milliseconds after " "application startup. Defaults to %zu\n", OPTION_SUBSCRIBE_AFTER, DEFAULT_SUBSCRIBE_AFTER); diff --git a/quality_of_service_demo/rclcpp/src/liveliness.cpp b/quality_of_service_demo/rclcpp/src/liveliness.cpp index e7a2ac1a7..445db97ae 100644 --- a/quality_of_service_demo/rclcpp/src/liveliness.cpp +++ b/quality_of_service_demo/rclcpp/src/liveliness.cpp @@ -35,7 +35,8 @@ static const size_t DEFAULT_KILL_PUBLISHER_AFTER = 3000; void print_usage() { printf("Usage for liveliness:\n"); - printf("liveliness " + printf( + "liveliness " "lease_duration " "[%s liveliness_policy] " "[%s node_assert_liveliness_period] " @@ -45,26 +46,31 @@ void print_usage() OPTION_NODE_ASSERT_PERIOD, OPTION_TOPIC_ASSERT_PERIOD); printf("required arguments:\n"); - printf("lease_duration: " + printf( + "lease_duration: " "Duration in positive integer milliseconds after which an inactive Publisher is considered " "not-alive. 0 means never.\n"); printf("optional arguments:\n"); printf("-h : Print this help message.\n"); - printf("%s liveliness_policy : " + printf( + "%s liveliness_policy : " "You may specify AUTOMATIC, MANUAL_BY_NODE, or MANUAL_BY_TOPIC. " "Defaults to %s\n", OPTION_POLICY, DEFAULT_POLICY); - printf("%s node_assert_period : " + printf( + "%s node_assert_period : " "How often the Publisher will assert the liveliness of its Node, in positive integer " "milliseconds. " "Defaults to 0 (never)\n", OPTION_NODE_ASSERT_PERIOD); - printf("%s topic_assert_period : " + printf( + "%s topic_assert_period : " "How often the Publisher will assert the liveliness of its Publisher " ", in positive integer milliseconds. " "Defaults to 0 (never)\n", OPTION_TOPIC_ASSERT_PERIOD); - printf("%s kill_publisher_after : " + printf( + "%s kill_publisher_after : " "Kill the publisher after this amount of time (in uint milliseconds). " "In AUTOMATIC - destroy the whole node. " "In MANUAL_BY_NODE, stop node liveliness assertion. "