Setpoint RAW plugin. More...
Public Member Functions | |
Subscriptions | get_subscriptions () override |
Return vector of MAVLink message subscriptions (handlers) More... | |
void | initialize (UAS &uas_) override |
Plugin initializer. More... | |
SetpointRawPlugin () | |
Public Member Functions inherited from mavros::plugin::PluginBase | |
virtual | ~PluginBase () |
Private Member Functions | |
void | attitude_cb (const mavros_msgs::AttitudeTarget::ConstPtr &req) |
void | global_cb (const mavros_msgs::GlobalPositionTarget::ConstPtr &req) |
void | handle_attitude_target (const mavlink::mavlink_message_t *msg, mavlink::common::msg::ATTITUDE_TARGET &tgt) |
void | handle_position_target_global_int (const mavlink::mavlink_message_t *msg, mavlink::common::msg::POSITION_TARGET_GLOBAL_INT &tgt) |
void | handle_position_target_local_ned (const mavlink::mavlink_message_t *msg, mavlink::common::msg::POSITION_TARGET_LOCAL_NED &tgt) |
void | local_cb (const mavros_msgs::PositionTarget::ConstPtr &req) |
Private Member Functions inherited from mavros::plugin::SetPositionTargetLocalNEDMixin< SetpointRawPlugin > | |
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 Member Functions inherited from mavros::plugin::SetPositionTargetGlobalIntMixin< SetpointRawPlugin > | |
void | set_position_target_global_int (uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, Eigen::Vector3d v, Eigen::Vector3d af, float yaw, float yaw_rate) |
Message specification: https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT . More... | |
Private Member Functions inherited from mavros::plugin::SetAttitudeTargetMixin< SetpointRawPlugin > | |
void | set_attitude_target (uint32_t time_boot_ms, uint8_t type_mask, Eigen::Quaterniond orientation, Eigen::Vector3d body_rate, float thrust) |
Message sepecification: https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET . More... | |
Friends | |
class | SetAttitudeTargetMixin |
class | SetPositionTargetGlobalIntMixin |
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 | capabilities_cb (UAS::MAV_CAP capabilities) |
virtual void | connection_cb (bool connected) |
void | enable_capabilities_cb () |
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 RAW plugin.
Send position setpoints and publish current state (return loop). User can decide what set of filed needed for operation via IGNORE bits.
Definition at line 33 of file setpoint_raw.cpp.