#include <path2d.h>
|
| | Pose2D () |
| |
| | Pose2D (const Eigen::Vector2d &p, float y, float velocity) |
| |
| | Pose2D (const geometry_msgs::Pose &pose, float velocity) |
| |
| | Pose2D (const geometry_msgs::PoseStamped &pose) |
| |
| | Pose2D (const trajectory_tracker_msgs::PoseStampedWithVelocity &pose) |
| |
| void | rotate (const float ang) |
| |
| void | toMsg (geometry_msgs::PoseStamped &pose) const |
| |
| void | toMsg (trajectory_tracker_msgs::PoseStampedWithVelocity &pose) const |
| |
Definition at line 52 of file path2d.h.
◆ Pose2D() [1/5]
| trajectory_tracker::Pose2D::Pose2D |
( |
| ) |
|
|
inline |
◆ Pose2D() [2/5]
| trajectory_tracker::Pose2D::Pose2D |
( |
const Eigen::Vector2d & |
p, |
|
|
float |
y, |
|
|
float |
velocity |
|
) |
| |
|
inline |
◆ Pose2D() [3/5]
| trajectory_tracker::Pose2D::Pose2D |
( |
const geometry_msgs::Pose & |
pose, |
|
|
float |
velocity |
|
) |
| |
|
inline |
◆ Pose2D() [4/5]
| trajectory_tracker::Pose2D::Pose2D |
( |
const geometry_msgs::PoseStamped & |
pose | ) |
|
|
inlineexplicit |
◆ Pose2D() [5/5]
| trajectory_tracker::Pose2D::Pose2D |
( |
const trajectory_tracker_msgs::PoseStampedWithVelocity & |
pose | ) |
|
|
inlineexplicit |
◆ rotate()
| void trajectory_tracker::Pose2D::rotate |
( |
const float |
ang | ) |
|
|
inline |
◆ toMsg() [1/2]
| void trajectory_tracker::Pose2D::toMsg |
( |
geometry_msgs::PoseStamped & |
pose | ) |
const |
|
inline |
◆ toMsg() [2/2]
| void trajectory_tracker::Pose2D::toMsg |
( |
trajectory_tracker_msgs::PoseStampedWithVelocity & |
pose | ) |
const |
|
inline |
◆ pos_
| Eigen::Vector2d trajectory_tracker::Pose2D::pos_ |
◆ velocity_
| float trajectory_tracker::Pose2D::velocity_ |
◆ yaw_
| float trajectory_tracker::Pose2D::yaw_ |
The documentation for this class was generated from the following file: