Setpoint velocity plugin. More...

Public Member Functions | |
| Subscriptions | get_subscriptions () |
| Return vector of MAVLink message subscriptions (handlers) More... | |
| void | initialize (UAS &uas_) |
| Plugin initializer. More... | |
| SetpointVelocityPlugin () | |
Public Member Functions inherited from mavros::plugin::PluginBase | |
| virtual | ~PluginBase () |
Private Member Functions | |
| void | send_setpoint_velocity (const ros::Time &stamp, Eigen::Vector3d &vel_enu, double yaw_rate) |
| Send velocity to FCU velocity controller. More... | |
| bool | set_mav_frame_cb (mavros_msgs::SetMavFrame::Request &req, mavros_msgs::SetMavFrame::Response &res) |
| void | vel_cb (const geometry_msgs::TwistStamped::ConstPtr &req) |
| void | vel_unstamped_cb (const geometry_msgs::Twist::ConstPtr &req) |
Private Member Functions inherited from mavros::plugin::SetPositionTargetLocalNEDMixin< SetpointVelocityPlugin > | |
| void | set_position_target_local_ned (uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, Eigen::Vector3d p, Eigen::Vector3d v, Eigen::Vector3d af, float yaw, float yaw_rate) |
Message specification: https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED. More... | |
Private Attributes | |
| MAV_FRAME | mav_frame |
| ros::ServiceServer | mav_frame_srv |
| ros::NodeHandle | sp_nh |
| ros::Subscriber | vel_sub |
| ros::Subscriber | vel_unstamped_sub |
Friends | |
| class | SetPositionTargetLocalNEDMixin |
Additional Inherited Members | |
Public Types inherited from mavros::plugin::PluginBase | |
| using | ConstPtr = boost::shared_ptr< PluginBase const > |
| using | HandlerCb = mavconn::MAVConnInterface::ReceivedCb |
| generic message handler callback More... | |
| using | HandlerInfo = std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCb > |
| Tuple: MSG ID, MSG NAME, message type into hash_code, message handler callback. More... | |
| using | Ptr = boost::shared_ptr< PluginBase > |
| using | Subscriptions = std::vector< HandlerInfo > |
| Subscriptions vector. More... | |
Protected Member Functions inherited from mavros::plugin::PluginBase | |
| virtual void | connection_cb (bool connected) |
| void | enable_connection_cb () |
| template<class _C > | |
| HandlerInfo | make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing)) |
| template<class _C , class _T > | |
| HandlerInfo | make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &)) |
| PluginBase () | |
| Plugin constructor Should not do anything before initialize() More... | |
Protected Attributes inherited from mavros::plugin::PluginBase | |
| UAS * | m_uas |
Setpoint velocity plugin.
Send setpoint velocities to FCU controller.
Definition at line 35 of file setpoint_velocity.cpp.