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

Check when a topic is not published with a callback in C++

asked 2022-07-28 12:22:09 -0500

Marcus Barnet gravatar image

updated 2022-07-28 12:22:56 -0500

hi to all,

I have a callback function in my ROS Node that is used to set the velocity on the motors. I noticed that if I stop publishing the velocity topic, the callback function continues to make the motors spin at the previous velocity until I publish again the topic by setting speed to 0.

What is the best solution to check when the topic is not published anymore and automatically set 0 inside the callback?

This is my callback:

 void velocity_callback(const roboclaw::RoboclawMotorVelocity &msg) {

 int mot1_vel1_sps =  msg.mot1_vel1_sps;
 int mot2_vel1_sps =  msg.mot2_vel1_sps;
 int mot1_vel2_sps =  msg.mot1_vel2_sps;
 int mot2_vel2_sps =  msg.mot2_vel2_sps;

    if(roboclaw_duty_m1m2(rc, address_2, mot1_vel2_sps, mot2_vel2_sps) != ROBOCLAW_OK )
    {
        fprintf(stderr, "problem communicating with roboclaw, terminating\n");

    }   
    if(roboclaw_duty_m1m2(rc, address, mot1_vel1_sps, mot2_vel1_sps) != ROBOCLAW_OK )
    {
        fprintf(stderr, "problem communicating with roboclaw, terminating\n");

    }   
}

This is how I publish the topic for testing:

rostopic pub -r 5 /cmd_vel_steering roboclaw/RoboclawMotorVelocity "{index0: 0, t1_vel1_sps: 0, mot2_vel1_sps: 20}"

This is how I call the callback in my main():

  ros::Subscriber velocity_sub = n.subscribe(std::string("cmd_vel_steering"), 1, &velocity_callback);

If I stop using rostopic, then velocity_callback() continues to make the motors spin with the previous received velocity.

Thank you!

edit retag flag offensive close merge delete

Comments

if I stop publishing the velocity topic, the callback function continues to make the motors spin at the previous velocity until I publish again the topic

That is by design.

check when the topic is not published anymore and automatically set 0 inside the callback

The callback gets triggered when the subscriber receives a message. Meaning if the topic is not being published on, then the callback will not get triggered.

abhishek47 gravatar image abhishek47  ( 2022-07-30 13:45:52 -0500 )edit

I was already aware about this behavior. The problem is: how can I modify my code in order to be able to set velocity=0 when the callback is not triggered anymore?

Marcus Barnet gravatar image Marcus Barnet  ( 2022-07-31 03:00:27 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2022-08-01 11:16:43 -0500

gvdhoorn gravatar image

updated 2022-08-01 11:18:53 -0500

how can I modify my code in order to be able to set velocity=0 when the callback is not triggered anymore?

this is typically done using a watchdog.

You can implement this in a ROS node which accepts incoming command messages using a timer:

  • create a timer but initially don't start it
  • configure it with the timeout you'd like on your "velocity commands"
  • in the timer callback function, set velocity=0, log a message (always nice to know when your watchdog got triggered) and disable the timer
  • upon reception of a message: start (if not started) or restart it (if it was already started)

with this in place, a single message received will do whatever you normally do with a message, but also start the timer.

With no follow-up messages, the timer will fire the callback, causing set velocity=0 to be executed.

The timer will also be disabled, so it will only do this once.

Any subsequent message will restart the timer.

Subsequent messages within the timeout will just reset the timeout, so set velocity=0 will not be executed.

Note:

I noticed that if I stop publishing the velocity topic, the callback function continues to make the motors spin at the previous velocity until I publish again the topic by setting speed to 0.

no, that's not how it works.

As @abhishek47 already states, callbacks are only called when there are messages. If there are no messages -> no callback called.

What you observe is caused by a lack of messages combined with a persistent state (ie: the last velocity setting is retained by your motor controller).

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-07-28 12:22:09 -0500

Seen: 158 times

Last updated: Aug 01 '22