A quite general version of this problem I came up with is attached:
#! /usr/bin/env python
import rospy
from geometry_msgs.msg import Twist
from ackermann_msgs.msg import AckermannDriveStamped
class SendEmptyWatchdog(object):
def __init__(self, datatype, topic, timeout=0.15, send_value=None):
self.timeout = timeout
self.datatype = datatype
if send_value is None:
self.send_value = datatype()
else:
self.send_value = send_value
self.twist_subscriber = rospy.Subscriber(topic, self.datatype, self.message_callback, queue_size=1)
self.twist_publisher = rospy.Publisher(topic, self.datatype, queue_size=1)
self.timer = rospy.Timer(rospy.Duration(self.timeout), self.timer_callback, oneshot=True)
self.timeout_triggered = False
def message_callback(self, msg):
rospy.logdebug("SendEmptyWatchdog{}: Message Callback".format(self.datatype))
if self.timeout_triggered:
self.timeout_triggered = False
else:
self.timer.shutdown()
self.timer = rospy.Timer(rospy.Duration(self.timeout), self.timer_callback, oneshot=True)
def timer_callback(self, event):
rospy.logwarn("SendEmptyWatchdog{}: Timeout Triggered. Received no message for {} seconds".format(self.datatype, self.timeout))
self.timeout_triggered = True
self.twist_publisher.publish(self.send_value)
if __name__ == '__main__':
rospy.init_node("command_watchdog")
twist_watchdog = SendEmptyWatchdog(Twist, "cmd_vel")
ackermann_watchdog = SendEmptyWatchdog(AckermannDriveStamped, "cmd_ackermann")
rospy.spin()
What it does is to subscribe to the topic "cmd_vel" and reset a oneshot timer to send a "zero twist" message once the time is expired. The timer.shutdown() and reinitializing is to stop the previously generated timer from firing and spamming "zero twist" messages self.timeout
seconds after each received message on "cmd_vel".
To avoid the reset of the timer with a published "zero twist" message, no timer is started for the first message after a timeout wast triggered.
The snippet works with Twists and basically any other datatype (Example with "AckermannDriveStamped" in the code).
Since by default all numeric fields of a newly created message are set to 0 stopping the robot in case of a timeout doesn't need a "send_value" specified. However you can do so, if e.g. a frame has to be specified.
@abdelkrim: take a look at how (fi)
diff_drive_controller
does this: here.@gvdhoorn yeah exactly what i am looking for thank you ... but i still have question how i can implement that in my node i am coding with python and in this example it's not very clear how he used timeout