ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I was stuck on this for whole day, so I'm adding my solution in case anyone else runs into a similar problem. The previously mentioned solutions are on the right track, but they are incomplete. There is an official solution in the ros docs, which I am pasting here just in case the link breaks.
Note that this problem is not unique to calling a service client from within a subscriber callback. This problem occurs whenever you have to call a callback from within a callback. Therefore the example of calling a service from within the timer callback is effectively the same as calling a service from within a subscription callback, or calling a service from within a service callback.
The solution is to put your nested callbacks in different callback groups (see the link above) and to use std::future::wait_for()
instead of rclcpp::spin_until_future_complete()
.
#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/empty.hpp"
using namespace std::chrono_literals;
namespace cb_group_demo
{
class DemoNode : public rclcpp::Node
{
public:
DemoNode() : Node("client_node")
{
client_cb_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
timer_cb_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
client_ptr_ = this->create_client<std_srvs::srv::Empty>("test_service", rmw_qos_profile_services_default,
client_cb_group_);
timer_ptr_ = this->create_wall_timer(1s, std::bind(&DemoNode::timer_callback, this),
timer_cb_group_);
}
private:
rclcpp::CallbackGroup::SharedPtr client_cb_group_;
rclcpp::CallbackGroup::SharedPtr timer_cb_group_;
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_ptr_;
rclcpp::TimerBase::SharedPtr timer_ptr_;
void timer_callback()
{
RCLCPP_INFO(this->get_logger(), "Sending request");
auto request = std::make_shared<std_srvs::srv::Empty::Request>();
auto result_future = client_ptr_->async_send_request(request);
// Do this instead of rclcpp::spin_until_future_complete()
std::future_status status = result_future.wait_for(10s); // timeout to guarantee a graceful finish
if (status == std::future_status::ready) {
RCLCPP_INFO(this->get_logger(), "Received response");
std::shared_ptr<ServiceT::Response> response = result_future.get();
// Do something with response
}
}
}; // class DemoNode
} // namespace cb_group_demo
int main(int argc, char* argv[])
{
rclcpp::init(argc, argv);
auto client_node = std::make_shared<cb_group_demo::DemoNode>();
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(client_node);
RCLCPP_INFO(client_node->get_logger(), "Starting client node, shut down with CTRL-C");
executor.spin();
RCLCPP_INFO(client_node->get_logger(), "Keyboard interrupt, shutting down.\n");
rclcpp::shutdown();
return 0;
}