Global position plugin. More...
Public Member Functions | |
Subscriptions | get_subscriptions () override |
Return vector of MAVLink message subscriptions (handlers) More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | GlobalPositionPlugin () |
void | initialize (UAS &uas_) override |
Plugin initializer. More... | |
Public Member Functions inherited from mavros::plugin::PluginBase | |
virtual | ~PluginBase () |
Private Member Functions | |
template<typename MsgT > | |
void | fill_lla (MsgT &msg, sensor_msgs::NavSatFix::Ptr fix) |
void | fill_unknown_cov (sensor_msgs::NavSatFix::Ptr fix) |
void | gps_diag_run (diagnostic_updater::DiagnosticStatusWrapper &stat) |
void | handle_global_position_int (const mavlink::mavlink_message_t *msg, mavlink::common::msg::GLOBAL_POSITION_INT &gpos) |
void | handle_gps_global_origin (const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS_GLOBAL_ORIGIN &glob_orig) |
void | handle_gps_raw_int (const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS_RAW_INT &raw_gps) |
void | handle_lpned_system_global_offset (const mavlink::mavlink_message_t *msg, mavlink::common::msg::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET &offset) |
void | home_position_cb (const mavros_msgs::HomePosition::ConstPtr &req) |
void | set_gp_origin_cb (const geographic_msgs::GeoPointStamped::ConstPtr &req) |
Private Attributes | |
std::string | child_frame_id |
body-fixed frame for topic headers More... | |
Eigen::Vector3d | ecef_origin {} |
geocentric origin of map frame [m] More... | |
std::string | frame_id |
origin frame for topic headers More... | |
ros::Publisher | gp_fix_pub |
ros::Publisher | gp_global_offset_pub |
ros::Publisher | gp_global_origin_pub |
ros::Publisher | gp_hdg_pub |
ros::NodeHandle | gp_nh |
ros::Publisher | gp_odom_pub |
ros::Publisher | gp_rel_alt_pub |
ros::Subscriber | gp_set_global_origin_sub |
double | gps_uere |
ros::Subscriber | hp_sub |
bool | is_map_init |
Eigen::Vector3d | local_ecef {} |
local ECEF coordinates on map frame [m] More... | |
Eigen::Vector3d | map_origin {} |
geodetic origin of map frame [lla] More... | |
ros::Publisher | raw_fix_pub |
ros::Publisher | raw_sat_pub |
ros::Publisher | raw_vel_pub |
double | rot_cov |
std::string | tf_child_frame_id |
frame for TF and Pose More... | |
std::string | tf_frame_id |
origin for TF More... | |
std::string | tf_global_frame_id |
global origin for TF More... | |
bool | tf_send |
bool | use_relative_alt |
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 |
Global position plugin.
Publishes global position. Conversion from GPS LLA to ECEF allows publishing local position to TF and PoseWithCovarianceStamped.
Definition at line 45 of file global_position.cpp.