dummy.cpp
Go to the documentation of this file.
00001 
00010 /*
00011  * Copyright 2013 Vladimir Ermakov.
00012  *
00013  * This file is part of the mavros package and subject to the license terms
00014  * in the top-level LICENSE file of the mavros repository.
00015  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
00016  */
00017 
00018 #include <mavros/mavros_plugin.h>
00019 #include <pluginlib/class_list_macros.h>
00020 
00021 namespace mavplugin {
00027 class DummyPlugin : public MavRosPlugin {
00028 public:
00029         DummyPlugin() :
00030                 nh("~"),
00031                 uas(nullptr)
00032         { };
00033 
00037         void initialize(UAS &uas_)
00038         {
00039                 uas = &uas_;
00040 
00041                 ROS_INFO_NAMED("dummy", "initialize");
00042         }
00043 
00049         const message_map get_rx_handlers() {
00050                 return {
00051                                MESSAGE_HANDLER(MAVLINK_MSG_ID_HEARTBEAT, &DummyPlugin::handle_heartbeat),
00052                                MESSAGE_HANDLER(MAVLINK_MSG_ID_SYS_STATUS, &DummyPlugin::handle_sys_status),
00053                                MESSAGE_HANDLER(MAVLINK_MSG_ID_STATUSTEXT, &DummyPlugin::handle_statustext)
00054                 };
00055         }
00056 
00057 private:
00058         ros::NodeHandle nh;
00059         UAS *uas;
00060 
00061         void handle_heartbeat(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
00062                 ROS_INFO_NAMED("dummy", "Dummy::handle_heartbeat(%p, %u, %u)",
00063                                 msg, sysid, compid);
00064         }
00065 
00066         void handle_sys_status(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
00067                 ROS_INFO_NAMED("dummy", "Dummy::handle_sys_status(%p, %u, %u)",
00068                                 msg, sysid, compid);
00069         }
00070 
00071         void handle_statustext(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) {
00072                 ROS_INFO_NAMED("dummy", "Dummy::handle_statustext(%p, %u, %u)",
00073                                 msg, sysid, compid);
00074         }
00075 };
00076 };      // namespace mavplugin
00077 
00078 PLUGINLIB_EXPORT_CLASS(mavplugin::DummyPlugin, mavplugin::MavRosPlugin)
00079 


mavros
Author(s): Vladimir Ermakov
autogenerated on Sat Jun 8 2019 19:55:19