Mavlink GPS status plugin. More...

Public Member Functions | |
| Subscriptions | get_subscriptions () override |
| GpsStatusPlugin () | |
| void | initialize (UAS &uas_) override |
Public Member Functions inherited from mavros::plugin::PluginBase | |
| virtual | ~PluginBase () |
Private Member Functions | |
| void | handle_gps2_raw (const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS2_RAW &mav_msg) |
| Publish mavlink GPS2_RAW message into the gps2/raw topic. More... | |
| void | handle_gps2_rtk (const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS2_RTK &mav_msg) |
| Publish mavlink GPS2_RTK message into the gps2/rtk topic. More... | |
| void | handle_gps_raw_int (const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS_RAW_INT &mav_msg) |
| Publish mavlink GPS_RAW_INT message into the gps1/raw topic. More... | |
| void | handle_gps_rtk (const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS_RTK &mav_msg) |
| Publish mavlink GPS_RTK message into the gps1/rtk topic. More... | |
Private Attributes | |
| ros::Publisher | gps1_raw_pub |
| ros::Publisher | gps1_rtk_pub |
| ros::Publisher | gps2_raw_pub |
| ros::Publisher | gps2_rtk_pub |
| ros::NodeHandle | gpsstatus_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, HandlerCb > | HandlerInfo |
| typedef boost::shared_ptr< PluginBase > | Ptr |
| typedef std::vector< HandlerInfo > | Subscriptions |
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 () |
| HandlerInfo | make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing)) |
| HandlerInfo | make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &)) |
| PluginBase () | |
Protected Attributes inherited from mavros::plugin::PluginBase | |
| UAS * | m_uas |
Mavlink GPS status plugin.
This plugin publishes GPS sensor data from a Mavlink compatible FCU to ROS.
Definition at line 30 of file gps_status.cpp.