Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
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