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

Plugin for Debug msgs from MAVLink API. More...

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

Public Member Functions

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

Private Member Functions

void debug_cb (const mavros_msgs::DebugValue::ConstPtr &req)
 Debug callbacks. More...
 
void debug_logger (const std::string &type, const mavros_msgs::DebugValue &dv)
 Helper function to log debug messages. More...
 
void handle_debug (const mavlink::mavlink_message_t *msg, mavlink::common::msg::DEBUG &debug)
 Handle DEBUG message. Message specification: https://mavlink.io/en/messages/common.html#DEBUG. More...
 
void handle_debug_vector (const mavlink::mavlink_message_t *msg, mavlink::common::msg::DEBUG_VECT &debug)
 Handle DEBUG_VECT message. Message specification: https://mavlink.io/en/messages/common.html#DEBUG_VECT. More...
 
void handle_named_value_float (const mavlink::mavlink_message_t *msg, mavlink::common::msg::NAMED_VALUE_FLOAT &value)
 Handle NAMED_VALUE_FLOAT message. Message specification: https://mavlink.io/en/messages/common.html#NAMED_VALUE_FLOAT. More...
 
void handle_named_value_int (const mavlink::mavlink_message_t *msg, mavlink::common::msg::NAMED_VALUE_INT &value)
 Handle NAMED_VALUE_INT message. Message specification: https://mavlink.io/en/messages/common.html#NAMED_VALUE_INT. More...
 

Private Attributes

ros::NodeHandle debug_nh
 
ros::Publisher debug_pub
 
ros::Subscriber debug_sub
 
ros::Publisher debug_vector_pub
 
ros::Publisher named_value_float_pub
 
ros::Publisher named_value_int_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 connection_cb (bool connected)
 
void enable_connection_cb ()
 
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
 PluginBase ()
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

Plugin for Debug msgs from MAVLink API.

Definition at line 24 of file debug_value.cpp.


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


mavros_extras
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:18