Skip to content

Commit

Permalink
add rcl_action_client_options when creating action client. (#1133)
Browse files Browse the repository at this point in the history
* add rcl_action_client_options for create_client.

Signed-off-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>

* Capitalize comments and keep the default rcl_action_client_options.

Signed-off-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>

* delete unnecessary default rcl_action_client_options_t.

Signed-off-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya committed Jun 16, 2020
1 parent 74daff0 commit 696d9ed
Show file tree
Hide file tree
Showing 8 changed files with 20 additions and 12 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 Optional pointer to a topic statistics subcription.
* \throws std::invalid_argument if the QoS is uncompatible with intra-process (if one
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/subscription_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
* \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
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_action/include/rclcpp_action/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 = rcl_action_client_get_default_options()
const rcl_action_client_options_t & client_options = rcl_action_client_get_default_options()
)
: ClientBase(
node_base, node_graph, node_logging, action_name,
Expand Down
14 changes: 10 additions & 4 deletions rclcpp_action/include/rclcpp_action/create_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +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`.
*/
template<typename ActionT>
typename Client<ActionT>::SharedPtr
Expand All @@ -46,7 +47,8 @@ create_client(
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface,
const std::string & name,
rclcpp::CallbackGroup::SharedPtr group = nullptr)
rclcpp::CallbackGroup::SharedPtr group = nullptr,
const rcl_action_client_options_t & options = rcl_action_client_get_default_options())
{
std::weak_ptr<rclcpp::node_interfaces::NodeWaitablesInterface> weak_node =
node_waitables_interface;
Expand Down Expand Up @@ -82,7 +84,8 @@ create_client(
node_base_interface,
node_graph_interface,
node_logging_interface,
name),
name,
options),
deleter);

node_waitables_interface->add_waitable(action_client, group);
Expand All @@ -95,21 +98,24 @@ 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`.
*/
template<typename ActionT, typename NodeT>
typename Client<ActionT>::SharedPtr
create_client(
NodeT node,
const std::string & name,
rclcpp::CallbackGroup::SharedPtr group = nullptr)
rclcpp::CallbackGroup::SharedPtr group = nullptr,
const rcl_action_client_options_t & options = rcl_action_client_get_default_options())
{
return rclcpp_action::create_client<ActionT>(
node->get_node_base_interface(),
node->get_node_graph_interface(),
node->get_node_logging_interface(),
node->get_node_waitables_interface(),
name,
group);
group,
options);
}
} // namespace rclcpp_action

Expand Down
4 changes: 2 additions & 2 deletions rclcpp_action/include/rclcpp_action/create_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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[in] group The action server will be added to this callback group.
* If `nullptr`, then the action server is added to the default callback group.
*/
Expand Down Expand Up @@ -123,7 +123,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[in] group The action server will be added to this callback group.
* If `nullptr`, then the action server is added to the default callback group.
*/
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_action/include/rclcpp_action/server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -296,7 +296,7 @@ class Server : public ServerBase, public std::enable_shared_from_this<Server<Act
* \param[in] name the name of an action.
* The same name and type must be used by both the action client and action server to
* communicate.
* \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[in] handle_goal a callback that decides if a goal should be accepted or rejected.
* \param[in] handle_cancel a callback that decides if a goal should be attemted to be canceled.
* The return from this callback only indicates if the server will try to cancel a goal.
Expand Down
4 changes: 3 additions & 1 deletion rclcpp_action/test/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -313,14 +313,16 @@ TEST_F(TestClient, construction_and_destruction_callback_group)
{
auto group = client_node->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive);
const rcl_action_client_options_t & options = rcl_action_client_get_default_options();
ASSERT_NO_THROW(
rclcpp_action::create_client<ActionType>(
client_node->get_node_base_interface(),
client_node->get_node_graph_interface(),
client_node->get_node_logging_interface(),
client_node->get_node_waitables_interface(),
action_name,
group
group,
options
).reset());
}

Expand Down

0 comments on commit 696d9ed

Please sign in to comment.