From 18252c275cf9f4d622e0f9bab28f5e43452477f0 Mon Sep 17 00:00:00 2001 From: "Tomoya.Fujita" Date: Sat, 23 May 2020 23:24:23 +0900 Subject: [PATCH] Capitalize comments and keep the default rcl_action_client_options. Signed-off-by: Tomoya.Fujita --- rclcpp/include/rclcpp/publisher.hpp | 2 +- rclcpp/include/rclcpp/subscription.hpp | 2 +- rclcpp/include/rclcpp/subscription_base.hpp | 2 +- rclcpp_action/include/rclcpp_action/client.hpp | 4 ++-- rclcpp_action/include/rclcpp_action/create_client.hpp | 4 ++-- rclcpp_action/include/rclcpp_action/create_server.hpp | 4 ++-- rclcpp_action/include/rclcpp_action/server.hpp | 2 +- 7 files changed, 10 insertions(+), 10 deletions(-) diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index ebe349cd99..397aead611 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -68,7 +68,7 @@ class Publisher : public PublisherBase * \param[in] node_base NodeBaseInterface pointer that is used in part of the setup. * \param[in] topic Name of the topic to publish to. * \param[in] qos QoS profile for Subcription. - * \param[in] options options for the subscription. + * \param[in] options Options for the subscription. */ Publisher( rclcpp::node_interfaces::NodeBaseInterface * node_base, diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 97e8714b40..046e2acf62 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -92,7 +92,7 @@ class Subscription : public SubscriptionBase * \param[in] topic_name Name of the topic to subscribe to. * \param[in] qos QoS profile for Subcription. * \param[in] callback User defined callback to call when a message is received. - * \param[in] options options for the subscription. + * \param[in] options Options for the subscription. * \param[in] message_memory_strategy The memory strategy to be used for managing message memory. * \param[in] subscription_topic_statistics pointer to a topic statistics subcription. * \throws std::invalid_argument if the QoS is uncompatible with intra-process (if one diff --git a/rclcpp/include/rclcpp/subscription_base.hpp b/rclcpp/include/rclcpp/subscription_base.hpp index 8156622299..022ac2ee30 100644 --- a/rclcpp/include/rclcpp/subscription_base.hpp +++ b/rclcpp/include/rclcpp/subscription_base.hpp @@ -66,7 +66,7 @@ class SubscriptionBase : public std::enable_shared_from_this * \param[in] node_base NodeBaseInterface pointer used in parts of the setup. * \param[in] type_support_handle rosidl type support struct, for the Message type of the topic. * \param[in] topic_name Name of the topic to subscribe to. - * \param[in] subscription_options options for the subscription. + * \param[in] subscription_options Options for the subscription. * \param[in] is_serialized is true if the message will be delivered still serialized */ RCLCPP_PUBLIC diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 2ce0407ff3..b62ff95e20 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -130,7 +130,7 @@ class ClientBase : public rclcpp::Waitable rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, const std::string & action_name, const rosidl_action_type_support_t * type_support, - const rcl_action_client_options_t & options); + const rcl_action_client_options_t & options = rcl_action_client_get_default_options()); /// Wait for action_server_is_ready() to become true, or until the given timeout is reached. RCLCPP_ACTION_PUBLIC @@ -317,7 +317,7 @@ class Client : public ClientBase rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, const std::string & action_name, - const rcl_action_client_options_t & client_options + const rcl_action_client_options_t & client_options = rcl_action_client_get_default_options() ) : ClientBase( node_base, node_graph, node_logging, action_name, diff --git a/rclcpp_action/include/rclcpp_action/create_client.hpp b/rclcpp_action/include/rclcpp_action/create_client.hpp index 770733d042..2461dd5b68 100644 --- a/rclcpp_action/include/rclcpp_action/create_client.hpp +++ b/rclcpp_action/include/rclcpp_action/create_client.hpp @@ -37,7 +37,7 @@ namespace rclcpp_action * \param[in] name The action name. * \param[in] group The action client will be added to this callback group. * If `nullptr`, then the action client is added to the default callback group. - * \param[in] options options to pass to the underlying `rcl_action_client_t`. + * \param[in] options Options to pass to the underlying `rcl_action_client_t`. */ template typename Client::SharedPtr @@ -99,7 +99,7 @@ create_client( * \param[in] name The action name. * \param[in] group The action client will be added to this callback group. * If `nullptr`, then the action client is added to the default callback group. - * \param[in] options options to pass to the underlying `rcl_action_client_t`. + * \param[in] options Options to pass to the underlying `rcl_action_client_t`. */ template typename Client::SharedPtr diff --git a/rclcpp_action/include/rclcpp_action/create_server.hpp b/rclcpp_action/include/rclcpp_action/create_server.hpp index 2886ee9c97..8245ad8bc2 100644 --- a/rclcpp_action/include/rclcpp_action/create_server.hpp +++ b/rclcpp_action/include/rclcpp_action/create_server.hpp @@ -49,7 +49,7 @@ namespace rclcpp_action * The return from this callback only indicates if the server will try to cancel a goal. * It does not indicate if the goal was actually canceled. * \param[in] handle_accepted A callback that is called to give the user a handle to the goal. - * \param[in] options options to pass to the underlying `rcl_action_server_t`. + * \param[in] options Options to pass to the underlying `rcl_action_server_t`. * \param group[in] The action server will be added to this callback group. * If `nullptr`, then the action server is added to the default callback group. */ @@ -124,7 +124,7 @@ create_server( * The return from this callback only indicates if the server will try to cancel a goal. * It does not indicate if the goal was actually canceled. * \param[in] handle_accepted A callback that is called to give the user a handle to the goal. - * \param[in] options options to pass to the underlying `rcl_action_server_t`. + * \param[in] options Options to pass to the underlying `rcl_action_server_t`. * \param group[in] The action server will be added to this callback group. * If `nullptr`, then the action server is added to the default callback group. */ diff --git a/rclcpp_action/include/rclcpp_action/server.hpp b/rclcpp_action/include/rclcpp_action/server.hpp index 7aede9ae69..c5ff2c1d8c 100644 --- a/rclcpp_action/include/rclcpp_action/server.hpp +++ b/rclcpp_action/include/rclcpp_action/server.hpp @@ -296,7 +296,7 @@ class Server : public ServerBase, public std::enable_shared_from_this