brake_thrash.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2018, Dataspeed Inc.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without modification,
00009 # are permitted provided that the following conditions are met:
00010 # 
00011 #     * Redistributions of source code must retain the above copyright notice,
00012 #       this list of conditions and the following disclaimer.
00013 #     * Redistributions in binary form must reproduce the above copyright notice,
00014 #       this list of conditions and the following disclaimer in the documentation
00015 #       and/or other materials provided with the distribution.
00016 #     * Neither the name of Dataspeed Inc. nor the names of its
00017 #       contributors may be used to endorse or promote products derived from this
00018 #       software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00021 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00022 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00023 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00024 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00025 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00026 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00027 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00028 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00029 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00030 
00031 import rospy
00032 from std_msgs.msg import Bool
00033 from dbw_fca_msgs.msg import BrakeCmd
00034 from dbw_fca_msgs.msg import GearReport, SteeringReport
00035 
00036 class BrakeThrash:
00037     def __init__(self):
00038         rospy.init_node('brake_thrash')
00039 
00040         # Shutdown
00041         self.shutdown = False
00042 
00043         # Received messages
00044         self.dbw_enabled = False
00045         self.msg_steering_report_ready = False
00046         self.msg_gear_report = GearReport()
00047         self.msg_gear_report_ready = False
00048         self.msg_steering_report = SteeringReport()
00049         self.msg_steering_report_ready = False
00050 
00051         # Parameters
00052         self.started = False
00053         rospy.loginfo('Preparing to thrash the brake pedal command to try and induce a fault...')
00054         rospy.loginfo('Validating that vehicle is parked...')
00055         
00056         # Publishers and subscribers
00057         self.pub = rospy.Publisher('/vehicle/brake_cmd', BrakeCmd, queue_size=10)
00058         rospy.Subscriber('/vehicle/dbw_enabled', Bool, self.recv_enabled)
00059         rospy.Subscriber('/vehicle/gear_report', GearReport, self.recv_gear)
00060         rospy.Subscriber('/vehicle/steering_report', SteeringReport, self.recv_steering)
00061         rospy.Timer(rospy.Duration(0.2), self.timer_process)
00062 
00063     def timer_process(self, event):
00064         # Check for safe conditions
00065         if not self.msg_steering_report_ready:
00066             self.shutdown = True
00067             rospy.logerr('Speed check failed. No messages on topic \'/vehicle/steering_report\'')
00068         elif not self.msg_steering_report.speed == 0.0:
00069             self.shutdown = True
00070             rospy.logerr('Speed check failed. Vehicle speed is not zero.')
00071         if not self.msg_gear_report_ready:
00072             self.shutdown = True
00073             rospy.logerr('Gear check failed. No messages on topic \'/vehicle/gear_report\'')
00074         elif not self.msg_gear_report.state.gear == self.msg_gear_report.state.PARK:
00075             self.shutdown = True
00076             rospy.logerr('Gear check failed. Vehicle not in park.')
00077 
00078         # Check if enabled
00079         if self.shutdown:
00080             rospy.signal_shutdown('')
00081             return
00082 
00083         # Check if enabled
00084         if not self.dbw_enabled:
00085             rospy.logwarn('Drive-by-wire not enabled!')
00086 
00087         # Start command timers
00088         if not self.started:
00089             self.started = True
00090             rospy.Timer(rospy.Duration(0.01000), self.timer_cmd_0)
00091             rospy.Timer(rospy.Duration(0.01001), self.timer_cmd_1)
00092             rospy.loginfo('Started thrashing the brake pedal command to try and induce a fault.')
00093         
00094         # Prepare for next iteration
00095         self.msg_gear_report_ready = False
00096         self.msg_steering_report_ready = False
00097 
00098     def timer_cmd_0(self, event):
00099         if not self.shutdown:
00100             msg = BrakeCmd()
00101             msg.enable = True
00102             msg.pedal_cmd_type = BrakeCmd.CMD_PEDAL
00103             msg.pedal_cmd = 0.0
00104             self.pub.publish(msg)
00105 
00106     def timer_cmd_1(self, event):
00107         if not self.shutdown:
00108             msg = BrakeCmd()
00109             msg.enable = True
00110             msg.pedal_cmd_type = BrakeCmd.CMD_PEDAL
00111             msg.pedal_cmd = 1.0
00112             self.pub.publish(msg)
00113 
00114     def recv_enabled(self, msg):
00115         self.dbw_enabled = msg.data
00116 
00117     def recv_gear(self, msg):
00118         self.msg_gear_report = msg
00119         self.msg_gear_report_ready = True
00120 
00121     def recv_steering(self, msg):
00122         self.msg_steering_report = msg
00123         self.msg_steering_report_ready = True
00124 
00125     def shutdown_handler(self):
00126         pass
00127 
00128 if __name__ == '__main__':
00129     try:
00130         node = BrakeThrash()
00131         rospy.on_shutdown(node.shutdown_handler)
00132         rospy.spin()
00133     except rospy.ROSInterruptException:
00134         pass


dbw_fca_can
Author(s): Kevin Hallenbeck
autogenerated on Sat May 4 2019 02:40:31