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

Nodelet Callback Not Working

asked 2018-11-12 04:01:30 -0500

Galadriel1233 gravatar image

updated 2018-11-12 04:40:42 -0500

My nodelet code is

PLUGINLIB_EXPORT_CLASS(example_pkg::MyNodeletClass, nodelet::Nodelet)

namespace example_pkg
{
    void MyNodeletClass::messageCb(const std_msgs::UInt8::ConstPtr& msg)
    {
        ROS_INFO("NODE 1 CALLBACK");
    }   
    void MyNodeletClass::onInit()
    {   
        ros::NodeHandle n = getMTPrivateNodeHandle();
        ROS_INFO("NODELET 1 INITIALIZATION");
        n.subscribe("msg_in", 10, &MyNodeletClass::messageCb, this);

    }

}

and my main node code is

int main(int argc, char **argv)
{
  ros::init(argc, argv, "main");
  nodelet::M_string remap(ros::names::getRemappings());
  nodelet::V_string nargv;
  nodelet::Loader nodelet1;
  nodelet1.load("one", "example_pkg/MyNodeletClass", remap, nargv);
  ROS_INFO("I AM HERE");
  ros::spin();
  return 0;
}

After I run the main code, I do rostopic pub msg_in std_msgs/UInt8 1 but the output remains

[ INFO] [1542015803.740819742]: Initializing nodelet with 6 worker threads.
[ INFO] [1542015803.789365470]: INITIALIZATION OF NODE 1 COMPLETE
[ INFO] [1542015803.821358176]: I AM HERE

I have also tried to use a launch file as below

<launch>
<node pkg="nodelet" type="nodelet" name="standalone_nodelet"  args="manager" output="screen"
></node>
<node pkg="nodelet" type="nodelet" name="MyNodeletClass" args="load example_pkg/MyNodeletClass standalone_nodelet" output="screen"></node>
</launch>

and after launching that, I run the same rostopic pub msg_in std_msgs/UInt8 1 command and get the following output

[ INFO] [1542019185.420793556]: Initializing nodelet with 6 worker threads.
[ INFO] [1542019185.440188632]: NODELET 1 INITIALIZATION

Why isn't the nodelet going into callback? I am not supposed to put ros::spin() in the onInit() function of the nodelet right? Thanks in advance.

edit retag flag offensive close merge delete

Comments

Just checking something first: you use getMTPrivateNodeHandle() and advertise a topic on that.

What is the output of rostopic list when everything is running?

Additionally: why are you not using a regular nodelet manager?

gvdhoorn gravatar image gvdhoorn  ( 2018-11-12 04:12:20 -0500 )edit

When I run the rostopic pub command this is the output.

/msg_in /rosout /rosout_agg

I am also trying to use a launch file with a regular nodelet manager. I edited the question. When I do that and run rostopic list I get

/msg_in /rosout /rosout_agg /standalone_nodelet/bond

Thanks @gvdhoorn

Galadriel1233 gravatar image Galadriel1233  ( 2018-11-12 04:42:46 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2018-11-12 10:28:08 -0500

gvdhoorn gravatar image

updated 2018-11-13 02:11:43 -0500

I'm pretty sure the issue is with the code in onInit(), you call n.subscribe(..), but you don't actually store the ros::Subscriber that is returned by that anywhere.

As soon as the object returned goes out of scope (at the end of onInit()), the subscription is destroyed, and the callback not called any longer.

edit flag offensive delete link more

Comments

Thanks that was absolutely the mistake. Solved!

Galadriel1233 gravatar image Galadriel1233  ( 2018-11-12 22:28:56 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-11-12 04:01:30 -0500

Seen: 677 times

Last updated: Nov 13 '18