MAVROS Plugin base class. More...
#include <mavros_plugin.h>
Public Types | |
typedef boost::shared_ptr < MavRosPlugin const > | ConstPtr |
typedef boost::function< void(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) | message_handler ) |
typedef std::map< uint8_t, message_handler > | message_map |
typedef boost::shared_ptr < MavRosPlugin > | Ptr |
Public Member Functions | |
virtual const std::string | get_name () const =0 |
Plugin name (CamelCase) | |
virtual const message_map | get_rx_handlers ()=0 |
Return map with message rx handlers. | |
virtual void | initialize (UAS &uas, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)=0 |
Plugin initializer. | |
virtual | ~MavRosPlugin () |
Protected Member Functions | |
MavRosPlugin () | |
Plugin constructor Should not do anything before initialize() | |
Private Member Functions | |
MavRosPlugin (const MavRosPlugin &) |