Public Member Functions | Private Member Functions | Private Attributes | List of all members
mavros::extra_plugins::TrajectoryPlugin Class Reference

Trajectory plugin to receive planned path from the FCU and send back to the FCU a corrected path (collision free, smoothed) More...

Inheritance diagram for mavros::extra_plugins::TrajectoryPlugin:
Inheritance graph
[legend]

Public Member Functions

Subscriptions get_subscriptions ()
 
void initialize (UAS &uas_)
 
 TrajectoryPlugin ()
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Member Functions

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_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)
 

Private Attributes

ros::Subscriber path_sub
 
ros::Publisher trajectory_desired_pub
 
ros::Subscriber trajectory_generated_sub
 
ros::NodeHandle trajectory_nh
 

Additional Inherited Members

- Public Types inherited from mavros::plugin::PluginBase
typedef boost::shared_ptr< PluginBase const > ConstPtr
 
typedef mavconn::MAVConnInterface::ReceivedCb HandlerCb
 
typedef std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCbHandlerInfo
 
typedef boost::shared_ptr< PluginBasePtr
 
typedef std::vector< HandlerInfoSubscriptions
 
- Protected Member Functions inherited from mavros::plugin::PluginBase
virtual void connection_cb (bool connected)
 
void enable_connection_cb ()
 
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
 PluginBase ()
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

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.


The documentation for this class was generated from the following file:


mavros_extras
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:18