32 from std_msgs.msg 
import Bool
 
   33 from dbw_mkz_msgs.msg 
import BrakeCmd
 
   34 from dbw_mkz_msgs.msg 
import GearReport, SteeringReport
 
   38         rospy.init_node(
'brake_thrash')
 
   53         rospy.loginfo(
'Preparing to thrash the brake pedal command to try and induce a fault...')
 
   54         rospy.loginfo(
'Validating that vehicle is parked...')
 
   57         self.
pub = rospy.Publisher(
'/vehicle/brake_cmd', BrakeCmd, queue_size=10)
 
   58         rospy.Subscriber(
'/vehicle/dbw_enabled', Bool, self.
recv_enabled)
 
   59         rospy.Subscriber(
'/vehicle/gear_report', GearReport, self.
recv_gear)
 
   60         rospy.Subscriber(
'/vehicle/steering_report', SteeringReport, self.
recv_steering)
 
   67             rospy.logerr(
'Speed check failed. No messages on topic \'/vehicle/steering_report\'')
 
   70             rospy.logerr(
'Speed check failed. Vehicle speed is not zero.')
 
   73             rospy.logerr(
'Gear check failed. No messages on topic \'/vehicle/gear_report\'')
 
   76             rospy.logerr(
'Gear check failed. Vehicle not in park.')
 
   80             rospy.signal_shutdown(
'')
 
   85             rospy.logwarn(
'Drive-by-wire not enabled!')
 
   90             rospy.Timer(rospy.Duration(0.01000), self.
timer_cmd_0)
 
   91             rospy.Timer(rospy.Duration(0.01001), self.
timer_cmd_1)
 
   92             rospy.loginfo(
'Started thrashing the brake pedal command to try and induce a fault.')
 
  102             msg.pedal_cmd_type = BrakeCmd.CMD_PEDAL
 
  104             self.
pub.publish(msg)
 
  110             msg.pedal_cmd_type = BrakeCmd.CMD_PEDAL
 
  112             self.
pub.publish(msg)
 
  128 if __name__ == 
'__main__':
 
  131         rospy.on_shutdown(node.shutdown_handler)
 
  133     except rospy.ROSInterruptException: