Local position plugin. Publish local position to TF, PositionStamped, TwistStamped and Odometry. More...
Public Member Functions | |
Subscriptions | get_subscriptions () |
Return vector of MAVLink message subscriptions (handlers) More... | |
void | initialize (UAS &uas_) |
Plugin initializer. More... | |
LocalPositionPlugin () | |
Public Member Functions inherited from mavros::plugin::PluginBase | |
virtual | ~PluginBase () |
Private Member Functions | |
void | handle_local_position_ned (const mavlink::mavlink_message_t *msg, mavlink::common::msg::LOCAL_POSITION_NED &pos_ned) |
void | handle_local_position_ned_cov (const mavlink::mavlink_message_t *msg, mavlink::common::msg::LOCAL_POSITION_NED_COV &pos_ned) |
void | publish_tf (boost::shared_ptr< nav_msgs::Odometry > &odom) |
Private Attributes | |
std::string | frame_id |
frame for Pose More... | |
bool | has_local_position_ned |
bool | has_local_position_ned_cov |
ros::Publisher | local_accel |
ros::Publisher | local_odom |
ros::Publisher | local_position |
ros::Publisher | local_position_cov |
ros::Publisher | local_velocity_body |
ros::Publisher | local_velocity_cov |
ros::Publisher | local_velocity_local |
ros::NodeHandle | lp_nh |
std::string | tf_child_frame_id |
frame for TF More... | |
std::string | tf_frame_id |
origin for TF More... | |
bool | tf_send |
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 |
Local position plugin. Publish local position to TF, PositionStamped, TwistStamped and Odometry.
Definition at line 38 of file local_position.cpp.