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

[ROS2][rclcpp][services] Service not being created [closed]

asked 2020-12-21 09:57:09 -0500

vinny gravatar image

updated 2020-12-22 11:53:32 -0500

I am attempting to write a ROS2 SetBool Service.

I am getting no compile-time errors, and I am getting to a logger message that is placed after I call the create_service method.

Even after this, the service is not advertised when I call ros2 service list.

  • I am on Ubuntu 20.04, Foxy, x86 (don't think that is relevant).

The constructor / destructor:

// Minimal Example

#include <memory.h>

#include "my_test_robot/main.hpp"

#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/set_bool.hpp"


MinimalExampleNode::MinimalExampleNode()
: Node("minimal_example_node")
{
  rclcpp::Service<std_srvs::srv::SetBool>::SharedPtr set_bool_service_ =
    this->create_service<std_srvs::srv::SetBool>(
      "set_bool",
      std::bind(&MinimalExampleNode::setBoolServiceCallback,
      this,
      std::placeholders::_1,
      std::placeholders::_2,
      std::placeholders::_3));
    RCLCPP_INFO(this->get_logger(), "Service ready");
}

MinimalExampleNode::~MinimalExampleNode() {}

The Callback., This is not even entered as the service does not appear to be advertised.

void MinimalExampleNode::setBoolServiceCallback(
  const std::shared_ptr<rmw_request_id_t> request_header,
  const std::shared_ptr<std_srvs::srv::SetBool::Request> request,
  const std::shared_ptr<std_srvs::srv::SetBool::Response> response)
{
  (void)request_header;
  bool ready_state = request->data;
  bool success = false;
  if (ready_state) {
    RCLCPP_INFO(this->get_logger(), "Ready recieved");
    success = true;
  } else {
    RCLCPP_INFO(this->get_logger(), "Not Ready recieved");
      }
      response->success = success;
    }

The main function. This is the only part in my head that is slightly different than the example tutorial.

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalExampleNode>());
  rclcpp::shutdown();
  return 0;
}

I am not sure what is going wrong, as even my minimal example is exhibiting this behavior. Does it have something to do with the way I am spinning the node?

Update

I think this might be a DDS issue? The above was on FastRTPS ... but when I switch to CycloneDDS export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp the issue goes away? Not sure if that is a bandaid or the proper solution.

Update 2 Switching to cycloneDDS only helped solve service discovery. Calling the service was still not possible using a minmal service client, nor ros2 service call.

When the service is created in main, then the service is both discoverable and callable. Is it something about creating the service in the constructor that I am doing incorrectly?

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by vinny
close date 2020-12-23 09:27:20.134671

1 Answer

Sort by ยป oldest newest most voted
3

answered 2020-12-23 00:05:46 -0500

jdlangs gravatar image

The problem is you're saving the output of create_service in a local variable only. When the constructor ends, the local variable is destroyed along with the service. It should work if you instead store it in a member variable of MinimalExampleNode.

edit flag offensive delete link more

Comments

good point. that was the issue. what a learning opportunity for me. Thanks for the catch!

vinny gravatar image vinny  ( 2020-12-23 09:02:42 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-12-21 09:57:09 -0500

Seen: 1,509 times

Last updated: Dec 23 '20