brake_sine.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 import math
00033 
00034 from std_msgs.msg import Bool
00035 from dbw_fca_msgs.msg import BrakeCmd
00036 
00037 
00038 class SineTest:
00039     def __init__(self):
00040         rospy.init_node('sine_test')
00041         self.pub = rospy.Publisher('/vehicle/brake_cmd', BrakeCmd, queue_size=1)
00042         self.sub = rospy.Subscriber('/vehicle/dbw_enabled', Bool, self.recv_enable)
00043 
00044         self.high_peak = rospy.get_param('~high_peak', 0.40)
00045         self.low_peak = rospy.get_param('~low_peak', 0.15)
00046         self.period = rospy.get_param('~period', 10)
00047 
00048         self.enabled = False
00049         self.t = 0
00050         self.sample_time = 0.02
00051 
00052         rospy.Timer(rospy.Duration(self.sample_time), self.timer_cb)
00053 
00054     def timer_cb(self, event):
00055         if not self.enabled:
00056             self.t = 0
00057             return
00058 
00059         amplitude = 0.5 * (self.high_peak - self.low_peak)
00060         offset = 0.5 * (self.high_peak + self.low_peak)
00061         cmd = offset - amplitude * math.cos(2 * math.pi / self.period * self.t)
00062         self.t += self.sample_time
00063 
00064         self.pub.publish(BrakeCmd(enable=True, pedal_cmd_type=BrakeCmd.CMD_PEDAL, pedal_cmd=cmd))
00065 
00066     def recv_enable(self, msg):
00067         self.enabled = msg.data
00068 
00069 
00070 if __name__ == '__main__':
00071     try:
00072         node_instance = SineTest()
00073         rospy.spin()
00074     except rospy.ROSInterruptException:
00075         pass
00076 


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