Public Member Functions | Private Member Functions | Private Attributes | List of all members
mavros::extra_plugins::GpsRtkPlugin Class Reference

GPS RTK plugin. More...

Inheritance diagram for mavros::extra_plugins::GpsRtkPlugin:
Inheritance graph
[legend]

Public Member Functions

Subscriptions get_subscriptions () override
 
 GpsRtkPlugin ()
 
void initialize (UAS &uas_) override
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Member Functions

void handle_baseline_msg (const mavlink::mavlink_message_t *msg, mavlink::common::msg::GPS_RTK &rtk_bsln)
 Publish GPS_RTK message (MAvlink Common) received from FCU. The message is already decoded by Mavlink, we only need to convert to ROS. Details and units: https://mavlink.io/en/messages/common.html#GPS_RTK. More...
 
void rtcm_cb (const mavros_msgs::RTCM::ConstPtr &msg)
 Handle mavros_msgs::RTCM message It converts the message to the MAVLink GPS_RTCM_DATA message for GPS injection. Message specification: https://mavlink.io/en/messages/common.html#GPS_RTCM_DATA. More...
 

Private Attributes

ros::NodeHandle gps_rtk_nh
 
ros::Subscriber gps_rtk_sub
 
mavros_msgs::RTKBaseline rtk_baseline_
 
ros::Publisher rtk_baseline_pub_
 

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, HandlerCbHandlerInfo
 
typedef boost::shared_ptr< PluginBasePtr
 
typedef std::vector< HandlerInfoSubscriptions
 
- 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
UASm_uas
 

Detailed Description

GPS RTK plugin.

  1. Publish the RTCM messages from ROS to the FCU
  2. Publish RTK baseline data from the FCU to ROS

Definition at line 30 of file gps_rtk.cpp.


The documentation for this class was generated from the following file:


mavros_extras
Author(s): Vladimir Ermakov , Amilcar Lucas
autogenerated on Tue Jun 1 2021 02:36:37