Skip to content

Commit 40336b9

Browse files
committed
fixed up watchdog and added to launch files
1 parent f6659b7 commit 40336b9

File tree

4 files changed

+16
-12
lines changed

4 files changed

+16
-12
lines changed

rb_ws/src/buggy/launch/nand-system.launch

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,4 +6,5 @@
66

77
<node name="foxglove" pkg="foxglove_bridge" type="foxglove_bridge" />
88
<node name="telematics" pkg="buggy" type="telematics.py" />
9+
<node name="watchdog" pkg="buggy" type="watchdog.py" args = "--self_name NAND" output="screen"/>
910
</launch>

rb_ws/src/buggy/launch/sc-system.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,5 +14,5 @@
1414

1515
<node name="foxglove" pkg="foxglove_bridge" type="foxglove_bridge" />
1616
<node name="telematics" pkg="buggy" type="telematics.py" />
17-
<node name="watchdog" pkg="buggy" type="watchdog.py" args = "--self_name SC" />
17+
<node name="watchdog" pkg="buggy" type="watchdog.py" args = "--self_name SC" output="screen"/>
1818
</launch>

rb_ws/src/buggy/launch/watchdog.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,5 +2,5 @@
22

33
<launch>
44
<node name="foxglove" pkg="foxglove_bridge" type="foxglove_bridge" />
5-
<node name="watchdog" pkg="buggy" type="watchdog.py" args = "--self_name SC" />
5+
<node name="watchdog" pkg="buggy" type="watchdog.py" args = "--self_name SC" output="screen"/>
66
</launch>

rb_ws/src/buggy/scripts/watchdog/watchdog.py

Lines changed: 13 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88

99
class Watchdog:
1010

11-
STEERING_DEVIANCE = 2 #deg
11+
STEERING_DEVIANCE = 4 #deg
1212

1313
def __init__(self, self_name) -> None:
1414
self.alarm = 0 #Check this alarm value
@@ -28,17 +28,21 @@ def __init__(self, self_name) -> None:
2828
self_name + "/buggy/debug/steering_angle", Float64, self.check_stepper_steering
2929
)
3030
rospy.Subscriber(
31-
self_name + "/buggy/debug/use_auton_steer", Bool, self.check_stepper_steering
31+
self_name + "/buggy/debug/use_auton_steer", Bool, self.set_auton_steer
3232
)
3333

3434
self.alarm_publisher = rospy.Publisher(self_name + "/debug/sanity_warning", Int8, queue_size=1)
3535
self.alarm_publish_rate = rospy.Rate(100) #10ms per alarm
3636

3737
def set_input_steering(self, msg):
38-
rospy.loginfo("Got input steering of, " + str(msg.data))
38+
rospy.logdebug("Got input steering of: " + str(msg.data))
3939
self.commanded_steering = msg.data
4040

41-
def set_auton_steer(self, msg):
41+
def set_auton_steer(self, msg):
42+
if (msg.data and not self.inAutonSteer):
43+
rospy.loginfo("ENTERED AUTON")
44+
if (not msg.data and self.inAutonSteer):
45+
rospy.logwarn("EXITED AUTON")
4246
self.inAutonSteer = msg.data
4347

4448
def check_stepper_steering(self, msg):
@@ -47,19 +51,19 @@ def check_stepper_steering(self, msg):
4751
if abs(stepper_steer - self.commanded_steering) > Watchdog.STEERING_DEVIANCE:
4852
self.alarm = 2 # ERROR
4953
if self.inAutonSteer:
50-
rospy.logerror("STEPPER DEVIANCE of " + str(abs(stepper_steer - self.commanded_steering)))
54+
rospy.logerr("STEPPER DEVIANCE (DEGREES OFF): " + str(abs(stepper_steer - self.commanded_steering)))
5155
else:
52-
rospy.logdebug("Stepper Deviance of " + str((stepper_steer - self.commanded_steering)) + " but not in auton steer")
56+
rospy.logdebug("(Non Auton) Stepper Deviance of: " + str(abs(stepper_steer - self.commanded_steering)))
5357

5458
elif abs(stepper_steer - self.commanded_steering) > Watchdog.STEERING_DEVIANCE//2:
5559
if self.inAutonSteer:
56-
rospy.logwarn("STEPPER POSSIBILY DEVIATING: " + str(abs(stepper_steer - self.commanded_steering)))
60+
rospy.logwarn("STEPPER POSSIBILY DEVIATING (DEGREES OFF): " + str(abs(stepper_steer - self.commanded_steering)))
61+
self.alarm = max(self.alarm, 1)
5762
else:
58-
rospy.logdebug("Not in auton, but stepper possibly deviating " + str(abs(stepper_steer - self.commanded_steering)))
63+
rospy.logdebug("(Non Auton) Stepper possibly deviating: " + str(abs(stepper_steer - self.commanded_steering)))
5964

6065
def loop(self):
6166
while True:
62-
print("HERE")
6367
#publish alarm
6468
ros_alarm = Int8()
6569
ros_alarm.data = self.alarm
@@ -75,7 +79,6 @@ def loop(self):
7579
args, _ = parser.parse_known_args()
7680
self_name = args.self_name
7781
rospy.init_node("watchdog")
78-
print("INITIALIZED")
7982
rospy.loginfo("INITIALIZED WATCHDOG NODE")
8083
watchdog = Watchdog(self_name=self_name)
8184
watchdog.loop()

0 commit comments

Comments
 (0)