ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

I feel your pain, the fact that there isn't a simpler wrapper for actions and services for "synchronous" use-cases I think will be a challenge for many users. Luckily, in Nav2 we've been working on some simple wrappers for our own internal use that can be leveraged in other packages.

https://github.com/ros-planning/navigation2/blob/main/nav2_util/include/nav2_util/service_client.hpp

This gives you a much more Simple Service Client interface (rather than dealing with nasty futures and such). Just create the object and call invoke with your request and returns the response. There's also a wait function to make sure its online, but otherwise handles the rest for you.

We unfortunately don't have a Simple Action Client at the moment, but I'd be more than happy to merge in one in the nav2_utils package that could be used by yourself and others in the future to help fill that niche. One way to get a "simpler" call though rather than spinning is to leverage the SendGoalOptions class:

  auto send_goal_options = rclcpp_action::Client<ClientT>::SendGoalOptions();
  send_goal_options.result_callback =
    std::bind(&WaypointFollower::resultCallback, this, std::placeholders::_1);
  send_goal_options.goal_response_callback =
    std::bind(&WaypointFollower::goalResponseCallback, this, std::placeholders::_1);
  future_goal_handle_ =
    nav_to_pose_client_->async_send_goal(client_goal, send_goal_options);

Whereas you can set callbacks for completion / goal acceptance / feedback rather than spinning until future complete. If the node you used to create the action client is just free spinning (or spin_some in some loop), then you don't need to worry too much about the async-ness, just wait for a callback result. Its still not as ideal as "send goal -> wait -> get result" blocking in the code, but its also probably not the best way to structure your software for an action (though I won't pretend I haven't done that myself).

I feel your pain, the fact that there isn't a simpler wrapper for actions and services for "synchronous" use-cases I think will be a challenge for many users. Luckily, in Nav2 we've been working on some simple wrappers for our own internal use that can be leveraged in other packages.

https://github.com/ros-planning/navigation2/blob/main/nav2_util/include/nav2_util/service_client.hpp

This gives you a much more Simple Service Client interface (rather than dealing with nasty futures and such). Just create the object and call invoke with your request and returns the response. There's also a wait function to make sure its online, but otherwise handles the rest for you.

We unfortunately don't have a Simple Action Client at the moment, but I'd be more than happy to merge in one in the nav2_utils package that could be used by yourself and others in the future to help fill that niche. One way to get a "simpler" call though rather than spinning is to leverage the SendGoalOptions class:

  auto send_goal_options = rclcpp_action::Client<ClientT>::SendGoalOptions();
  send_goal_options.result_callback =
    std::bind(&WaypointFollower::resultCallback, this, std::placeholders::_1);
  send_goal_options.goal_response_callback =
    std::bind(&WaypointFollower::goalResponseCallback, this, std::placeholders::_1);
  future_goal_handle_ =
    nav_to_pose_client_->async_send_goal(client_goal, send_goal_options);

Whereas you can set callbacks for completion / goal acceptance / feedback rather than spinning until future complete. If the node you used to create the action client is just free spinning (or spin_some in some loop), then you don't need to worry too much about the async-ness, just wait for a callback result. Its still not as ideal as "send goal -> wait -> get result" blocking in the code, but its also probably not the best way to structure your software for an action (though I won't pretend I haven't done that myself).

Down the line, if there's interest, I'd be more than happy to move the Simple clients over to ROS2 client libraries directly. They really only live in Nav2 because we needed them so we built them.