33 from dbw_mkz_msgs.msg
import ThrottleCmd, ThrottleReport, ThrottleInfoReport
34 from dbw_mkz_msgs.msg
import GearReport, SteeringReport
39 rospy.init_node(
'throttle_sweep')
60 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.')
61 rospy.loginfo(
'This will take ' + str((self.
end - self.
start) / self.
resolution * self.duration.to_sec() / 60.0) +
' minutes.')
64 self.
csv_file = open(
'throttle_sweep_data.csv',
'w')
66 self.csv_writer.writerow([
'Throttle (%)',
'Measured (%)'])
69 self.
pub = rospy.Publisher(
'/vehicle/throttle_cmd', ThrottleCmd, queue_size=1)
70 rospy.Subscriber(
'/vehicle/throttle_report', ThrottleReport, self.
recv_throttle)
71 rospy.Subscriber(
'/vehicle/throttle_info_report', ThrottleInfoReport, self.
recv_throttle_info)
72 rospy.Subscriber(
'/vehicle/gear_report', GearReport, self.
recv_gear)
73 rospy.Subscriber(
'/vehicle/steering_report', SteeringReport, self.
recv_steering)
74 rospy.Timer(rospy.Duration(0.02), self.
timer_cmd)
81 rospy.logerr(
'Speed check failed. No messages on topic \'/vehicle/steering_report\'')
82 rospy.signal_shutdown(
'')
83 if self.msg_steering_report.speed > 1.0:
84 rospy.logerr(
'Speed check failed. Vehicle speed is greater than 1 m/s.')
85 rospy.signal_shutdown(
'')
87 rospy.logerr(
'Gear check failed. No messages on topic \'/vehicle/gear_report\'')
88 rospy.signal_shutdown(
'')
89 if not self.msg_gear_report.state.gear == self.msg_gear_report.state.PARK:
90 rospy.logerr(
'Gear check failed. Vehicle not in park.')
91 rospy.signal_shutdown(
'')
95 rospy.logerr(
'No new messages on topic \'/vehicle/throttle_report\'')
96 rospy.signal_shutdown(
'')
98 rospy.logerr(
'No new messages on topic \'/vehicle/throttle_info_report\'')
99 rospy.signal_shutdown(
'')
100 if not self.msg_throttle_report.enabled:
101 rospy.logerr(
'Throttle module not enabled!')
102 rospy.signal_shutdown(
'')
105 diff = self.
throttle_cmd - self.msg_throttle_report.pedal_output
106 if (fabs(diff) > 0.01):
107 rospy.logwarn(
'Not saving data point. Large disparity between pedal request and actual: ' + str(diff))
110 rospy.loginfo(
'Data point: ' +
"{:.03f}".format(self.msg_throttle_report.pedal_output) +
', ' +
111 "{:.03f}".format(self.msg_throttle_info_report.throttle_pc))
112 self.csv_writer.writerow([
"{:.03f}".format(self.msg_throttle_report.pedal_output),
113 "{:.03f}".format(self.msg_throttle_info_report.throttle_pc)])
115 rospy.signal_shutdown(
'')
127 msg.pedal_cmd_type = ThrottleCmd.CMD_PEDAL
129 self.pub.publish(msg)
148 rospy.loginfo(
'Saving csv file')
149 self.csv_file.close()
151 if __name__ ==
'__main__':
154 rospy.on_shutdown(node.shutdown_handler)
156 except rospy.ROSInterruptException:
def shutdown_handler(self)
def recv_steering(self, msg)
def timer_cmd(self, event)
def recv_throttle_info(self, msg)
def timer_process(self, event)
def recv_throttle(self, msg)
msg_steering_report_ready
msg_throttle_info_report_ready
msg_throttle_report_ready