Skip to content

Commit

Permalink
initial watchdog node commit
Browse files Browse the repository at this point in the history
  • Loading branch information
mehulgoel873 committed Oct 24, 2024
1 parent 7ebbd5c commit f009cce
Show file tree
Hide file tree
Showing 3 changed files with 50 additions and 1 deletion.
44 changes: 44 additions & 0 deletions rb_ws/src/buggy/buggy/watchdog/watchdog_node.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
import rclpy
from rclpy.node import Node

from std_msgs.msg import Bool

class Watchdog(Node):

def __init__(self):
"""
Constructor for Watchdog class.
Creates a ROS node with a publisher that periodically sends a message
indicating whether the node is still alive.
"""
super().__init__('watchdog')
self.heartbeat_publisher = self.create_publisher(Bool, 'self/debug/heartbeat', 1)
timer_period = 0.01 # seconds (10 Hz)
self.timer = self.create_timer(timer_period, self.loop)
self.i = 0 # Loop Counter

def loop(self):
# Loop for the code that operates at 0.1 Hz
msg = Bool()
msg.data = True
self.heartbeat_publisher.publish(msg)


def main(args=None):
rclpy.init(args=args)

minimal_publisher = Watchdog()

rclpy.spin(minimal_publisher)

# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
minimal_publisher.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()
4 changes: 4 additions & 0 deletions rb_ws/src/buggy/launch/watchdog.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<launch>
<node pkg="foxglove_bridge" exec="foxglove_bridge" name="foxglove" namespace="SC"/>
<node pkg="buggy" exec="watchdog" name="SC_watchdog" namespace="SC"/>
</launch>
3 changes: 2 additions & 1 deletion rb_ws/src/buggy/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,8 @@
tests_require=['pytest'],
entry_points={
'console_scripts': [
'hello_world = buggy.hello_world:main'
'hello_world = buggy.hello_world:main',
'watchdog = buggy.watchdog.watchdog_node:main'
],
},
)

0 comments on commit f009cce

Please sign in to comment.