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

Problem with subscriber ROS2

asked 2022-05-18 00:36:45 -0500

Peanpepu gravatar image

updated 2022-05-18 01:16:08 -0500

Im creating a publisher node (only publish) and a manager node (publish and subscribe) to communicate with turtlesim in ROS2. The problem i have is when i try to subscribe to a topic. I have seen many examples of subscribers with minor changes in syntax and i have tried everything but i still have this problem:

error: forming pointer to reference type ‘const std::shared_ptr<std_msgs::msg::String_<std::allocator<void> > >&’
  399 |       using pointer = _Tp*;
      |             ^~~~~~~
/usr/include/c++/9/bits/alloc_traits.h:402:13: error: forming pointer to reference type ‘const std::shared_ptr<std_msgs::msg::String_<std::allocator<void> > >&’
  402 |       using const_pointer = const _Tp*;
      |             ^~~~~~~~~~~~~

I know the problem is on subscriber on this line this->subdir = this->create_subscription<std_msgs::msg::String>("cmd_dir", 1000, std::bind(&Manager_class::cmd_dirCallback, this, std::placeholders::_1)); because if i comment it the code compile correctly. Then i show my manager_class.hpp where i declare the subscriber:

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include <geometry_msgs/msg/twist.hpp>

class Manager_class : public rclcpp::Node
{
public:
  // Constructor
  Manager_class();

  // Methods
  /**
   * @brief Function that subscriber needs to received new messages
   * @param msg 
   */
  void cmd_dirCallback(const std_msgs::msg::String::SharedPtr &msg);
  void publish_vel();

  // Attributes
  double linear, angular; // linear and angular speed
  int mode;  // mode for choosing the robot direction
  geometry_msgs::msg::Twist vel_msg;
  bool nuevo;
  unsigned dir;


private:
  // Attributes
  rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr pub; // Publisher object
  rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subdir; // Subscriber direction object

};

Now i show my manager_class.cpp:

#include "navigation/manager_class.hpp"

Manager_class::Manager_class() : Node("ManagerClass")
{
  this->linear = 0; 
  this->angular = 0;
  this->mode = 1;
  this->nuevo = true;
  this->dir = 0;


  this->subdir = this->create_subscription<std_msgs::msg::String>("cmd_dir", 1000, std::bind(&Manager_class::cmd_dirCallback, this, std::placeholders::_1)); 

  // Call the node handle to publish a geometry_msgs data on the topic "turtle1/cmd_vel"
  pub = this->create_publisher<geometry_msgs::msg::Twist>("turtle1/cmd_vel",1000);

void Manager_class::cmd_dirCallback(const std_msgs::msg::String::SharedPtr &msg)
{
  if(this->mode == 1)
  {
    RCLCPP_INFO(this->get_logger(), "[Object Manager] Received the direction [%s]\n", msg->data.c_str());

    if(msg->data == "stop")               {this->linear = 0;  this->angular = 0;}
    else if(msg->data == "fordwards")     {this->linear = 1;  this->angular = 0;}
    else if(msg->data == "backwards")     {this->linear = -1; this->angular = 0;}
    else if(msg->data == "left")          {this->linear = 0;  this->angular = 1;}
    else if(msg->data == "right")         {this->linear = 0;  this->angular = -1;}

    this->vel_msg.linear.x = this->linear;
    this->vel_msg.angular.z = this->angular;

    this->publish_vel();
  }
}

void Manager_class::publish_vel()
{
  RCLCPP_INFO(this->get_logger(), "Value: %d %d", this->vel_msg.linear.x, this->vel_msg.angular.z);
  this->pub->publish(this->vel_msg);
}

My main_manager.cpp is the following:

#include "navigation/manager_class.hpp"

int main(int argc, char** argv)
{
  // Initialize ROS
  rclcpp::init(argc, argv);
  auto node = std::make_shared<Manager_class>();
  Manager_class manager;
  rclcpp::Rate loop(10);

  while(rclcpp::ok())
  {
    rclcpp::spin_some(manager.node);
    if(manager.mode == 2)
    {
      manager.publish_vel();
    }
    loop.sleep();
  }

  rclcpp::spin(node);
  rclcpp::shutdown();

  return 0;

}

I would appreciate any help. Thanks in advance

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
2

answered 2022-05-18 01:31:36 -0500

aprotyas gravatar image

The problem is with your subscription callback signature. In Foxy, std::function<void (const std::shared_ptr<const MessageT> &)> (what you have) is not a supported signature for a subscription callback.

The list of supported subscription callbacks in Foxy is (reference: https://docs.ros2.org/foxy/api/rclcpp...)

  • std::function<void (std::unique_ptr<MessageT, MessageDeleter>)>
  • std::function<void (std::unique_ptr<MessageT, MessageDeleter>, const rclcpp::MessageInfo &)>
  • std::function<void (const std::shared_ptr<const MessageT>)>
  • std::function<void (const std::shared_ptr<const MessageT>, const rclcpp::MessageInfo &)>
  • std::function<void (std::shared_ptr<MessageT>)>
  • std::function<void (std::shared_ptr<MessageT>, const rclcpp::MessageInfo &)>

The quick fix here would be to drop the reference to the message's constant shared_ptr, instead opting to just receive a constant shared_ptr in your subscription callback as such:

void cmd_dirCallback(const std_msgs::msg::String::SharedPtr msg);

edit flag offensive delete link more

Comments

Thank you very much it does work, but i dont understand very well why if the paramether is a pointer it doesnt need the reference before its name declaration. If that was a normal pointer it would be different?

Peanpepu gravatar image Peanpepu  ( 2022-05-18 03:05:26 -0500 )edit

I don't know if I'm interpreting your question correctly, but do you mean to say why are we not passing a reference to the pointer? There's no benefit in doing so and doesn't make much sense. I can see why you might want to pass references to smart pointers, but we usually just pass all pointer types by value (the pointer performs the same purpose as a pass-by-reference argument, if you know what I mean).

Anyways, in a newer ROS distribution, the callback signature you're thinking of (const reference to a shared pointer) is supported. Please refer to this big PR for extended discussion around this topic

aprotyas gravatar image aprotyas  ( 2022-05-18 19:33:16 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2022-05-18 00:36:45 -0500

Seen: 1,531 times

Last updated: May 18 '22