Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008 import rospy, math
00009 from teb_local_planner.msg import FeedbackMsg, TrajectoryMsg, TrajectoryPointMsg
00010 from geometry_msgs.msg import PolygonStamped, Point32
00011 import numpy as np
00012 import matplotlib.pyplot as plotter
00013
00014 def feedback_callback(data):
00015 global trajectory
00016
00017 if not data.trajectories:
00018 trajectory = []
00019 return
00020 trajectory = data.trajectories[data.selected_trajectory_idx].trajectory
00021
00022
00023 def plot_velocity_profile(fig, ax_v, ax_omega, t, v, omega):
00024 ax_v.cla()
00025 ax_v.grid()
00026 ax_v.set_ylabel('Trans. velocity [m/s]')
00027 ax_v.plot(t, v, '-bx')
00028 ax_omega.cla()
00029 ax_omega.grid()
00030 ax_omega.set_ylabel('Rot. velocity [rad/s]')
00031 ax_omega.set_xlabel('Time [s]')
00032 ax_omega.plot(t, omega, '-bx')
00033 fig.canvas.draw()
00034
00035
00036
00037 def velocity_plotter():
00038 global trajectory
00039 rospy.init_node("visualize_velocity_profile", anonymous=True)
00040
00041 topic_name = "/test_optim_node/teb_feedback"
00042 topic_name = rospy.get_param('~feedback_topic', topic_name)
00043 rospy.Subscriber(topic_name, FeedbackMsg, feedback_callback, queue_size = 1)
00044
00045 rospy.loginfo("Visualizing velocity profile published on '%s'.",topic_name)
00046 rospy.loginfo("Make sure to enable rosparam 'publish_feedback' in the teb_local_planner.")
00047
00048
00049 fig, (ax_v, ax_omega) = plotter.subplots(2, sharex=True)
00050 plotter.ion()
00051 plotter.show()
00052
00053
00054 r = rospy.Rate(2)
00055 while not rospy.is_shutdown():
00056
00057 t = []
00058 v = []
00059 omega = []
00060
00061 for point in trajectory:
00062 t.append(point.time_from_start.to_sec())
00063 v.append(point.velocity.linear.x)
00064 omega.append(point.velocity.angular.z)
00065
00066 plot_velocity_profile(fig, ax_v, ax_omega, np.asarray(t), np.asarray(v), np.asarray(omega))
00067
00068 r.sleep()
00069
00070 if __name__ == '__main__':
00071 try:
00072 trajectory = []
00073 velocity_plotter()
00074 except rospy.ROSInterruptException:
00075 pass
00076