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 csv
00033 from dbw_fca_msgs.msg import ThrottleCmd, ThrottleReport, ThrottleInfoReport
00034 from dbw_fca_msgs.msg import GearReport, SteeringReport
00035 from math import fabs
00036
00037 class ThrottleSweep:
00038 def __init__(self):
00039 rospy.init_node('throttle_sweep')
00040
00041
00042 self.throttle_cmd = 0.0
00043 self.msg_throttle_report = ThrottleReport()
00044 self.msg_throttle_report_ready = False
00045 self.msg_throttle_info_report = ThrottleInfoReport()
00046 self.msg_throttle_info_report_ready = False
00047
00048
00049 self.msg_gear_report = GearReport()
00050 self.msg_gear_report_ready = False
00051 self.msg_steering_report = SteeringReport()
00052 self.msg_steering_report_ready = False
00053
00054
00055 self.i = -1
00056 self.start = 0.07
00057 self.end = 0.93
00058 self.resolution = 0.002
00059 self.duration = rospy.Duration(1.0)
00060 rospy.loginfo('Recording throttle pedal data every ' + str(self.duration.to_sec()) + ' seconds from ' + str(self.start) + ' to ' + str(self.end) + ' with ' + str(self.resolution) + ' increments.')
00061 rospy.loginfo('This will take ' + str((self.end - self.start) / self.resolution * self.duration.to_sec() / 60.0) + ' minutes.')
00062
00063
00064 self.csv_file = open('throttle_sweep_data.csv', 'w')
00065 self.csv_writer = csv.writer(self.csv_file, delimiter=',')
00066 self.csv_writer.writerow(['Throttle (%)', 'Measured (%)'])
00067
00068
00069 self.pub = rospy.Publisher('/vehicle/throttle_cmd', ThrottleCmd, queue_size=1)
00070 rospy.Subscriber('/vehicle/throttle_report', ThrottleReport, self.recv_throttle)
00071 rospy.Subscriber('/vehicle/throttle_info_report', ThrottleInfoReport, self.recv_throttle_info)
00072 rospy.Subscriber('/vehicle/gear_report', GearReport, self.recv_gear)
00073 rospy.Subscriber('/vehicle/steering_report', SteeringReport, self.recv_steering)
00074 rospy.Timer(rospy.Duration(0.02), self.timer_cmd)
00075 rospy.Timer(self.duration, self.timer_process)
00076
00077 def timer_process(self, event):
00078 if self.i < 0:
00079
00080 if not self.msg_steering_report_ready:
00081 rospy.logerr('Speed check failed. No messages on topic \'/vehicle/steering_report\'')
00082 rospy.signal_shutdown('')
00083 if self.msg_steering_report.speed > 1.0:
00084 rospy.logerr('Speed check failed. Vehicle speed is greater than 1 m/s.')
00085 rospy.signal_shutdown('')
00086 if not self.msg_gear_report_ready:
00087 rospy.logerr('Gear check failed. No messages on topic \'/vehicle/gear_report\'')
00088 rospy.signal_shutdown('')
00089 if not self.msg_gear_report.state.gear == self.msg_gear_report.state.PARK:
00090 rospy.logerr('Gear check failed. Vehicle not in park.')
00091 rospy.signal_shutdown('')
00092 elif self.i < int((self.end - self.start) / self.resolution + 1):
00093
00094 if not self.msg_throttle_report_ready:
00095 rospy.logerr('No new messages on topic \'/vehicle/throttle_report\'')
00096 rospy.signal_shutdown('')
00097 if not self.msg_throttle_info_report_ready:
00098 rospy.logerr('No new messages on topic \'/vehicle/throttle_info_report\'')
00099 rospy.signal_shutdown('')
00100 if not self.msg_throttle_report.enabled:
00101 rospy.logerr('Throttle module not enabled!')
00102 rospy.signal_shutdown('')
00103
00104
00105 diff = self.throttle_cmd - self.msg_throttle_report.pedal_output
00106 if (fabs(diff) > 0.01):
00107 rospy.logwarn('Not saving data point. Large disparity between pedal request and actual: ' + str(diff))
00108 else:
00109
00110 rospy.loginfo('Data point: ' + "{:.03f}".format(self.msg_throttle_report.pedal_output) + ', ' +
00111 "{:.03f}".format(self.msg_throttle_info_report.throttle_pc))
00112 self.csv_writer.writerow(["{:.03f}".format(self.msg_throttle_report.pedal_output),
00113 "{:.03f}".format(self.msg_throttle_info_report.throttle_pc)])
00114 else:
00115 rospy.signal_shutdown('')
00116
00117
00118 self.i += 1
00119 self.msg_throttle_report_ready = False
00120 self.msg_throttle_info_report_ready = False
00121 self.throttle_cmd = self.start + self.i * self.resolution
00122
00123 def timer_cmd(self, event):
00124 if self.throttle_cmd > 0:
00125 msg = ThrottleCmd()
00126 msg.enable = True
00127 msg.pedal_cmd_type = ThrottleCmd.CMD_PEDAL
00128 msg.pedal_cmd = self.throttle_cmd
00129 self.pub.publish(msg)
00130
00131 def recv_throttle(self, msg):
00132 self.msg_throttle_report = msg
00133 self.msg_throttle_report_ready = True
00134
00135 def recv_throttle_info(self, msg):
00136 self.msg_throttle_info_report = msg
00137 self.msg_throttle_info_report_ready = True
00138
00139 def recv_gear(self, msg):
00140 self.msg_gear_report = msg
00141 self.msg_gear_report_ready = True
00142
00143 def recv_steering(self, msg):
00144 self.msg_steering_report = msg
00145 self.msg_steering_report_ready = True
00146
00147 def shutdown_handler(self):
00148 rospy.loginfo('Saving csv file')
00149 self.csv_file.close()
00150
00151 if __name__ == '__main__':
00152 try:
00153 node = ThrottleSweep()
00154 rospy.on_shutdown(node.shutdown_handler)
00155 rospy.spin()
00156 except rospy.ROSInterruptException:
00157 pass