Trajectory plugin to receive planned path from the FCU and send back to the FCU a corrected path (collision free, smoothed)
More...
|
void | fill_msg_acceleration (geometry_msgs::Vector3 &acceleration, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i) |
|
void | fill_msg_position (geometry_msgs::Point &position, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i) |
|
void | fill_msg_velocity (geometry_msgs::Vector3 &velocity, const mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i) |
|
void | fill_points_acceleration (MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Vector3 &acceleration, const size_t i) |
|
void | fill_points_all_unused (mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i) |
|
void | fill_points_all_unused_bezier (mavlink::common::msg::TRAJECTORY_REPRESENTATION_BEZIER &t, const size_t i) |
|
void | fill_points_delta (MavPoints &y, const double time_horizon, const size_t i) |
|
void | fill_points_position (MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Point &position, const size_t i) |
|
auto | fill_points_unused_path (mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &t, const size_t i) |
|
void | fill_points_velocity (MavPoints &x, MavPoints &y, MavPoints &z, const geometry_msgs::Vector3 &velocity, const size_t i) |
|
void | fill_points_yaw_q (MavPoints &y, const geometry_msgs::Quaternion &orientation, const size_t i) |
|
void | fill_points_yaw_speed (MavPoints &yv, const double yaw_speed, const size_t i) |
|
void | fill_points_yaw_wp (MavPoints &y, const double yaw, const size_t i) |
|
void | handle_trajectory (const mavlink::mavlink_message_t *msg, mavlink::common::msg::TRAJECTORY_REPRESENTATION_WAYPOINTS &trajectory) |
|
void | path_cb (const nav_msgs::Path::ConstPtr &req) |
| Send corrected path to the FCU. More...
|
|
void | trajectory_cb (const mavros_msgs::Trajectory::ConstPtr &req) |
| Send corrected path to the FCU. More...
|
|
float | wrap_pi (float a) |
|
Trajectory plugin to receive planned path from the FCU and send back to the FCU a corrected path (collision free, smoothed)
- See also
- trajectory_cb()
Definition at line 40 of file trajectory.cpp.