8
8
9
9
class Watchdog :
10
10
11
- STEERING_DEVIANCE = 2 #deg
11
+ STEERING_DEVIANCE = 4 #deg
12
12
13
13
def __init__ (self , self_name ) -> None :
14
14
self .alarm = 0 #Check this alarm value
@@ -28,17 +28,21 @@ def __init__(self, self_name) -> None:
28
28
self_name + "/buggy/debug/steering_angle" , Float64 , self .check_stepper_steering
29
29
)
30
30
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
32
32
)
33
33
34
34
self .alarm_publisher = rospy .Publisher (self_name + "/debug/sanity_warning" , Int8 , queue_size = 1 )
35
35
self .alarm_publish_rate = rospy .Rate (100 ) #10ms per alarm
36
36
37
37
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 ))
39
39
self .commanded_steering = msg .data
40
40
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" )
42
46
self .inAutonSteer = msg .data
43
47
44
48
def check_stepper_steering (self , msg ):
@@ -47,19 +51,19 @@ def check_stepper_steering(self, msg):
47
51
if abs (stepper_steer - self .commanded_steering ) > Watchdog .STEERING_DEVIANCE :
48
52
self .alarm = 2 # ERROR
49
53
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 )))
51
55
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 )))
53
57
54
58
elif abs (stepper_steer - self .commanded_steering ) > Watchdog .STEERING_DEVIANCE // 2 :
55
59
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 )
57
62
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 )))
59
64
60
65
def loop (self ):
61
66
while True :
62
- print ("HERE" )
63
67
#publish alarm
64
68
ros_alarm = Int8 ()
65
69
ros_alarm .data = self .alarm
@@ -75,7 +79,6 @@ def loop(self):
75
79
args , _ = parser .parse_known_args ()
76
80
self_name = args .self_name
77
81
rospy .init_node ("watchdog" )
78
- print ("INITIALIZED" )
79
82
rospy .loginfo ("INITIALIZED WATCHDOG NODE" )
80
83
watchdog = Watchdog (self_name = self_name )
81
84
watchdog .loop ()
0 commit comments