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

My Subscriber isn't picking up TurtleBot3's scans

asked 2020-04-13 10:40:44 -0500

bluemoon93 gravatar image

updated 2020-04-13 10:41:02 -0500

Using ROS2 Dashing, running on the Dashing Docker environment, and using Tmux to run multiple nodes in the same console. I setup my TurtleBot3 installation and prepared things for simulation.

I can run

ros2 launch turtlebot3_gazebo turtlebot3_world.launch.py

And this command shows messages being published

ros2 topic echo /scan

But after this I built a node in a separate package, which is unable to subscribe to /scan. This is the MVCE:

void topic_callback(const sensor_msgs::msg::LaserScan::ConstSharedPtr msg)
{
  std::cout << "Got something!" << std::endl;
}

int main(int argc, char *argv[]) {
  rclcpp::init(argc, argv);

  auto node = rclcpp::Node::make_shared("whateverName");
  rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr subscription_ = node->create_subscription<sensor_msgs::msg::LaserScan>("/scan", 10, std::bind(&topic_callback, std::placeholders::_1));
  rclcpp::spin(node);
  rclcpp::shutdown();
  return 0;
}

Running this node prints nothing. What am I doing wrong here?

edit retag flag offensive close merge delete

Comments

Check what QoS the scan is published under. You may need to use the sensor data WoS setting.

stevemacenski gravatar image stevemacenski  ( 2020-04-13 12:25:32 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-04-14 05:57:06 -0500

bluemoon93 gravatar image

@stevemacenski had it right. The Subscription had to be made with

rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr subscription_ = 
    node->create_subscription<sensor_msgs::msg::LaserScan>(
      "/scan", 
      rclcpp::QoS(rclcpp::SystemDefaultsQoS()).keep_last(10),
      std::bind(&topic_callback, std::placeholders::_1));

In order to actually receive the messages.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2020-04-13 10:40:44 -0500

Seen: 238 times

Last updated: Apr 14 '20