throttle_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 ThrottleCmd
00034 from dbw_fca_msgs.msg import GearReport, SteeringReport
00035 
00036 class ThrottleThrash:
00037     def __init__(self):
00038         rospy.init_node('throttle_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 throttle pedal command to try and induce a fault...')
00054         rospy.loginfo('Validating that vehicle is parked...')
00055 
00056         # Command state
00057         self.cmd_state = False
00058         
00059         # Publishers and subscribers
00060         self.pub = rospy.Publisher('/vehicle/throttle_cmd', ThrottleCmd, queue_size=10)
00061         rospy.Subscriber('/vehicle/dbw_enabled', Bool, self.recv_enabled)
00062         rospy.Subscriber('/vehicle/gear_report', GearReport, self.recv_gear)
00063         rospy.Subscriber('/vehicle/steering_report', SteeringReport, self.recv_steering)
00064         rospy.Timer(rospy.Duration(0.2), self.timer_process)
00065 
00066     def timer_process(self, event):
00067         # Check for safe conditions
00068         if not self.msg_steering_report_ready:
00069             self.shutdown = True
00070             rospy.logerr('Speed check failed. No messages on topic \'/vehicle/steering_report\'')
00071         elif not self.msg_steering_report.speed == 0.0:
00072             self.shutdown = True
00073             rospy.logerr('Speed check failed. Vehicle speed is not zero.')
00074         if not self.msg_gear_report_ready:
00075             self.shutdown = True
00076             rospy.logerr('Gear check failed. No messages on topic \'/vehicle/gear_report\'')
00077         elif not self.msg_gear_report.state.gear == self.msg_gear_report.state.PARK:
00078             self.shutdown = True
00079             rospy.logerr('Gear check failed. Vehicle not in park.')
00080 
00081         # Check if enabled
00082         if self.shutdown:
00083             rospy.signal_shutdown('')
00084             return
00085 
00086         # Check if enabled
00087         if not self.dbw_enabled:
00088             rospy.logwarn('Drive-by-wire not enabled!')
00089 
00090         # Start command timers
00091         if not self.started:
00092             self.started = True
00093             rospy.Timer(rospy.Duration(0.020), self.timer_cmd)
00094             rospy.loginfo('Started thrashing the throttle pedal command to try and induce a fault.')
00095         
00096         # Prepare for next iteration
00097         self.msg_gear_report_ready = False
00098         self.msg_steering_report_ready = False
00099 
00100     def timer_cmd(self, event):
00101         if not self.shutdown:
00102             msg = ThrottleCmd()
00103             msg.enable = True
00104             msg.pedal_cmd_type = ThrottleCmd.CMD_PEDAL
00105             if self.cmd_state:
00106                 msg.pedal_cmd = 1.0
00107             else:
00108                 msg.pedal_cmd = 0.0
00109             self.pub.publish(msg)
00110             self.cmd_state = not self.cmd_state
00111 
00112     def recv_enabled(self, msg):
00113         self.dbw_enabled = msg.data
00114 
00115     def recv_gear(self, msg):
00116         self.msg_gear_report = msg
00117         self.msg_gear_report_ready = True
00118 
00119     def recv_steering(self, msg):
00120         self.msg_steering_report = msg
00121         self.msg_steering_report_ready = True
00122 
00123     def shutdown_handler(self):
00124         pass
00125 
00126 if __name__ == '__main__':
00127     try:
00128         node = ThrottleThrash()
00129         rospy.on_shutdown(node.shutdown_handler)
00130         rospy.spin()
00131     except rospy.ROSInterruptException:
00132         pass


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