#include <mavros/mavros_plugin.h>
#include <pluginlib/class_list_macros.h>
namespace mavplugin {
class DummyPlugin : public MavRosPlugin {
public:
DummyPlugin() {
ROS_INFO_NAMED("dummy", "dummy constructor");
};
void initialize(UAS &uas,
ros::NodeHandle &nh,
diagnostic_updater::Updater &diag_updater)
{
ROS_INFO_NAMED("dummy", "initialize");
};
std::string const get_name() const {
return "Dummy";
};
const message_map get_rx_handlers() {
return {
MESSAGE_HANDLER(MAVLINK_MSG_ID_HEARTBEAT, &DummyPlugin::handle_heartbeat),
MESSAGE_HANDLER(MAVLINK_MSG_ID_SYS_STATUS, &DummyPlugin::handle_sys_status),
MESSAGE_HANDLER(MAVLINK_MSG_ID_STATUSTEXT, &DummyPlugin::handle_statustext)
};
}
private:
void handle_heartbeat(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
ROS_INFO_NAMED("dummy", "Dummy::handle_heartbeat(%p, %u, %u)",
msg, sysid, compid);
}
void handle_sys_status(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
ROS_INFO_NAMED("dummy", "Dummy::handle_sys_status(%p, %u, %u)",
msg, sysid, compid);
}
void handle_statustext(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
ROS_INFO_NAMED("dummy", "Dummy::handle_statustext(%p, %u, %u)",
msg, sysid, compid);
}
};
};
PLUGINLIB_EXPORT_CLASS(mavplugin::DummyPlugin, mavplugin::MavRosPlugin)