9 from teb_local_planner.msg
import FeedbackMsg, TrajectoryMsg, TrajectoryPointMsg
10 from geometry_msgs.msg
import PolygonStamped, Point32
12 import matplotlib.pyplot
as plotter
17 if not data.trajectories:
20 trajectory = data.trajectories[data.selected_trajectory_idx].trajectory
26 ax_v.set_ylabel(
'Trans. velocity [m/s]')
27 ax_v.plot(t, v,
'-bx')
30 ax_omega.set_ylabel(
'Rot. velocity [rad/s]')
31 ax_omega.set_xlabel(
'Time [s]')
32 ax_omega.plot(t, omega,
'-bx')
39 rospy.init_node(
"visualize_velocity_profile", anonymous=
True)
41 topic_name =
"/test_optim_node/teb_feedback" 42 topic_name = rospy.get_param(
'~feedback_topic', topic_name)
43 rospy.Subscriber(topic_name, FeedbackMsg, feedback_callback, queue_size = 1)
45 rospy.loginfo(
"Visualizing velocity profile published on '%s'.",topic_name)
46 rospy.loginfo(
"Make sure to enable rosparam 'publish_feedback' in the teb_local_planner.")
49 fig, (ax_v, ax_omega) = plotter.subplots(2, sharex=
True)
55 while not rospy.is_shutdown():
61 for point
in trajectory:
62 t.append(point.time_from_start.to_sec())
63 v.append(point.velocity.linear.x)
64 omega.append(point.velocity.angular.z)
70 if __name__ ==
'__main__':
74 except rospy.ROSInterruptException:
def plot_velocity_profile(fig, ax_v, ax_omega, t, v, omega)
def feedback_callback(data)