teb_local_planner/TrajectoryPointMsg Message

File: teb_local_planner/TrajectoryPointMsg.msg

Raw Message Definition

# Message that contains single point on a trajectory suited for mobile navigation.
# The trajectory is described by a sequence of poses, velocities,
# accelerations and temporal information.

# Why this message type?
# nav_msgs/Path describes only a path without temporal information.
# trajectory_msgs package contains only messages for joint trajectories.

# The pose of the robot
geometry_msgs/Pose pose

# Corresponding velocity
geometry_msgs/Twist velocity

# Corresponding acceleration
geometry_msgs/Twist acceleration

duration time_from_start




Compact Message Definition

geometry_msgs/Pose pose
geometry_msgs/Twist velocity
geometry_msgs/Twist acceleration
duration time_from_start