Skip to content

Commit

Permalink
plugins: Make name and messages methods const. (breaking).
Browse files Browse the repository at this point in the history
WARNING: this change broke external plugins.
Please add const to get_name() and get_supported_messages().

Part of #38.
  • Loading branch information
vooon committed Jul 11, 2014
1 parent cf1636f commit 715fb59
Show file tree
Hide file tree
Showing 10 changed files with 51 additions and 20 deletions.
37 changes: 34 additions & 3 deletions include/mavros/mavros_plugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
* @author Vladimir Ermakov <vooon341@gmail.com>
*
* @addtogroup plugin
* @{
* @brief MAVROS Plugin system
*/
/*
* Copyright 2013 Vladimir Ermakov.
Expand All @@ -29,20 +31,49 @@
#include <mavros/mavconn_interface.h>
#include <mavros/mavros_uas.h>

#include <boost/noncopyable.hpp>

namespace mavplugin {

class MavRosPlugin
/**
* @brief MAVROS Plugin base class
*/
class MavRosPlugin : private boost::noncopyable
{
public:
virtual ~MavRosPlugin() {};

/**
* @brief Plugin initializer
*
* @param[in] uas UAS instance (handles FCU connection and some statuses)
* @param[in] nh main mavros ros::NodeHandle (private)
* @param[in] diag_updater main diagnostic updater
*/
virtual void initialize(UAS &uas,
ros::NodeHandle &nh,
diagnostic_updater::Updater &diag_updater) = 0;
virtual std::string get_name() = 0;
virtual std::vector<uint8_t> get_supported_messages() = 0;

/**
* @brief Plugin name (CamelCase)
*/
virtual const std::string get_name() const = 0;

/**
* @brief List of messages supported by message_rx_cb()
*/
virtual const std::vector<uint8_t> get_supported_messages() const = 0;

/**
* @brief Message receive callback
*/
virtual void message_rx_cb(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) = 0;

protected:
/**
* @brief Plugin constructor
* Should not do anything before initialize()
*/
MavRosPlugin() {};
};

Expand Down
2 changes: 1 addition & 1 deletion include/mavros/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ inline bool set_thread_name(boost::thread &thd, const char *name, ...)
/**
* @brief Set boost::thread name (std::string variation)
*/
inline bool set_thread_name(boost::thread &thd, std::string name)
inline bool set_thread_name(boost::thread &thd, std::string &name)
{
return set_thread_name(thd, name.c_str());
};
Expand Down
4 changes: 2 additions & 2 deletions src/plugins/command.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,11 +70,11 @@ class CommandPlugin : public MavRosPlugin {
set_home_srv = cmd_nh.advertiseService("set_home", &CommandPlugin::set_home_cb, this);
}

std::string get_name() {
std::string const get_name() const {
return "Command";
}

std::vector<uint8_t> get_supported_messages() {
std::vector<uint8_t> const get_supported_messages() const {
return {
MAVLINK_MSG_ID_COMMAND_ACK
};
Expand Down
4 changes: 2 additions & 2 deletions src/plugins/dummy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,14 +53,14 @@ class DummyPlugin : public MavRosPlugin {
/**
* Returns plugin name (CamelCase)
*/
std::string get_name() {
std::string const get_name() const {
return "Dummy";
};

/**
* Returns vector with MSGID processed by message_rx_cb()
*/
std::vector<uint8_t> get_supported_messages() {
std::vector<uint8_t> const get_supported_messages() const {
return {
MAVLINK_MSG_ID_HEARTBEAT,
MAVLINK_MSG_ID_SYS_STATUS,
Expand Down
4 changes: 2 additions & 2 deletions src/plugins/gps.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,11 +97,11 @@ class GPSPlugin : public MavRosPlugin {
vel_pub = nh.advertise<geometry_msgs::TwistStamped>("gps_vel", 10);
}

std::string get_name() {
std::string const get_name() const {
return "GPS";
}

std::vector<uint8_t> get_supported_messages() {
std::vector<uint8_t> const get_supported_messages() const {
return {
MAVLINK_MSG_ID_GPS_RAW_INT,
MAVLINK_MSG_ID_GPS_STATUS,
Expand Down
4 changes: 2 additions & 2 deletions src/plugins/imu_pub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,11 +101,11 @@ class IMUPubPlugin : public MavRosPlugin {
imu_raw_pub = nh.advertise<sensor_msgs::Imu>("imu/data_raw", 10);
}

std::string get_name() {
std::string const get_name() const {
return "IMUPub";
}

std::vector<uint8_t> get_supported_messages() {
std::vector<uint8_t> const get_supported_messages() const {
return {
MAVLINK_MSG_ID_ATTITUDE,
MAVLINK_MSG_ID_RAW_IMU,
Expand Down
4 changes: 2 additions & 2 deletions src/plugins/param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -343,11 +343,11 @@ class ParamPlugin : public MavRosPlugin {
uas->sig_connection_changed.connect(boost::bind(&ParamPlugin::connection_cb, this, _1));
}

std::string get_name() {
std::string const get_name() const {
return "Param";
}

std::vector<uint8_t> get_supported_messages() {
std::vector<uint8_t> const get_supported_messages() const {
return {
MAVLINK_MSG_ID_PARAM_VALUE
};
Expand Down
4 changes: 2 additions & 2 deletions src/plugins/rc_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,11 +58,11 @@ class RCIOPlugin : public MavRosPlugin {
uas->sig_connection_changed.connect(boost::bind(&RCIOPlugin::connection_cb, this, _1));
};

std::string get_name() {
std::string const get_name() const {
return "RCIO";
};

std::vector<uint8_t> get_supported_messages() {
std::vector<uint8_t> const get_supported_messages() const {
return {
MAVLINK_MSG_ID_RC_CHANNELS_RAW,
MAVLINK_MSG_ID_RC_CHANNELS,
Expand Down
4 changes: 2 additions & 2 deletions src/plugins/sys_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -340,11 +340,11 @@ class SystemStatusPlugin : public MavRosPlugin
rate_srv = nh.advertiseService("set_stream_rate", &SystemStatusPlugin::set_rate_cb, this);
}

std::string get_name() {
const std::string get_name() const {
return "SystemStatus";
}

std::vector<uint8_t> get_supported_messages() {
const std::vector<uint8_t> get_supported_messages() const {
return {
MAVLINK_MSG_ID_HEARTBEAT,
MAVLINK_MSG_ID_SYS_STATUS,
Expand Down
4 changes: 2 additions & 2 deletions src/plugins/waypoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,11 +176,11 @@ class WaypointPlugin : public MavRosPlugin {
uas->sig_connection_changed.connect(boost::bind(&WaypointPlugin::connection_cb, this, _1));
};

std::string get_name() {
std::string const get_name() const {
return "Waypoint";
};

std::vector<uint8_t> get_supported_messages() {
std::vector<uint8_t> const get_supported_messages() const {
return {
MAVLINK_MSG_ID_MISSION_ITEM,
MAVLINK_MSG_ID_MISSION_REQUEST,
Expand Down

0 comments on commit 715fb59

Please sign in to comment.