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

NodeHandle::subscribe fail to subscribe topic

asked 2018-10-25 09:52:23 -0500

Xmice gravatar image

updated 2018-10-25 20:23:09 -0500

Hi, I'm new to ROS and C++ and doing Programming for Robotics ( http://www.rsl.ethz.ch/education-stud... ). My problem is "Create a subscriber to the /scan topic" in exercise2. Here is my code:

HuskyHighlevelController.Cpp File:

#include "husky_highlevel_controller/HuskyHighlevelController.hpp"
#include <std_msgs/String.h>
#include <ros/ros.h>
#include <sensor_msgs/LaserScan.h>

namespace husky_highlevel_controller {

HuskyHighlevelController::HuskyHighlevelController(ros::NodeHandle& nodeHandle) :
  nodeHandle_(nodeHandle)
{
  ros::Subscriber subscriber =
  nodeHandle_.subscribe("scan",1000,&HuskyHighlevelController::ScanCallback,this);
  ROS_INFO("Successfully launched node.");
}

HuskyHighlevelController::~HuskyHighlevelController()
{
}

void HuskyHighlevelController::ScanCallback(const sensor_msgs::LaserScan& msg)
{
ROS_INFO("Received");
}

}

husky_highlevel_controller_node.Cpp File:

#include <ros/ros.h>
#include "husky_highlevel_controller/HuskyHighlevelController.hpp"

int main(int argc, char** argv)
{
  ros::init(argc, argv, "husky_highlevel_controller");
  ros::NodeHandle nodeHandle("~");

  husky_highlevel_controller::HuskyHighlevelController huskyHighlevelController(nodeHandle);

  ros::spin();
  return 0;
}

No problem with build but I launched husky_world.launch first then I ran this node (husky_highlevel_controller_node) and I checked the info of husky_highlevel_controller node and scan topic. Found No relationship between them (also rqt_console to check info message but receive nothing). I'm confused with

ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_object);

and

ros::Subscriber sub = handle.subscribe("my_topic", 1, callback);

From the ROS/Tutorials/WritingPublisherSubscriber(c++), I think my_topic should be the topic found in rostopic list but didn't work for subscribing scan topic. Thanks.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-10-25 15:33:14 -0500

NEngelhard gravatar image

As it's your homework: What is the scope of your subscriber and how long will it live?

edit flag offensive delete link more

Comments

Thanks for the hint.

  ros::Subscriber subscriber =  nodeHandle_.subscribe("scan",1000,&HuskyHighlevelController::ScanCallback,this);

was the reason. I replace it by

subscriber_ =
nodeHandle_.subscribe("/scan",1000,&HuskyHighlevelController::ScanCallback,this);

Worked as expectedly.

Xmice gravatar image Xmice  ( 2018-10-25 21:22:03 -0500 )edit

@Xmice: please mark the answer by @NEngelhard as correct by ticking the checkmark to the left of the answer. It will turn green.

gvdhoorn gravatar image gvdhoorn  ( 2018-10-26 04:46:53 -0500 )edit
1

@gvdhoorn: Done. I'll get familiar with the forum and thanks for the reminding.

Xmice gravatar image Xmice  ( 2018-10-26 05:27:49 -0500 )edit

Thanks a lot I had the same problem and this solved it for me. I am not sure though what exactly is the difference between the two versions. Why is the scope different?

dimitri gravatar image dimitri  ( 2020-04-20 08:03:28 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-10-25 09:52:23 -0500

Seen: 799 times

Last updated: Oct 25 '18