cellular_status.cpp
Go to the documentation of this file.
1 
9 /*
10  * Copyright 2021 Jaeyoung Lim.
11  *
12  * This file is part of the mavros package and subject to the license terms
13  * in the top-level LICENSE file of the mavros repository.
14  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
15  */
16 
17 #include <mavros/mavros_plugin.h>
18 #include <mavros_msgs/CellularStatus.h>
19 
20 namespace mavros {
21 namespace extra_plugins {
29 public:
31  cc_nh("~cellular_status")
32  { }
33 
37  void initialize(UAS &uas_)
38  {
41  }
42 
52  return {};
53  }
54 
55 private:
58 
65  void cellularStatusCb(const mavros_msgs::CellularStatus &msg)
66  {
67  mavlink::common::msg::CELLULAR_STATUS cs{};
68 
69  cs.status = msg.status;
70  cs.failure_reason = msg.failure_reason;
71  cs.type = msg.type;
72  cs.quality = msg.quality;
73  cs.mcc = msg.mcc;
74  cs.mnc = msg.mnc;
75  cs.lac = msg.lac;
76 
77  UAS_FCU(m_uas)->send_message_ignore_drop(cs);
78  }
79 };
80 } // namespace std_plugins
81 } // namespace mavros
82 
mavros::plugin::PluginBase::m_uas
UAS * m_uas
mavros::plugin::PluginBase::Subscriptions
std::vector< HandlerInfo > Subscriptions
msg
msg
mavros::plugin::PluginBase::PluginBase
PluginBase()
UAS_FCU
#define UAS_FCU(uasobjptr)
mavros::UAS
mavros::extra_plugins::CellularStatusPlugin::cc_nh
ros::NodeHandle cc_nh
Definition: cellular_status.cpp:56
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mavros_plugin.h
mavros::extra_plugins::CellularStatusPlugin::CellularStatusPlugin
CellularStatusPlugin()
Definition: cellular_status.cpp:30
mavros::extra_plugins::CellularStatusPlugin::subCellularStatus
ros::Subscriber subCellularStatus
Definition: cellular_status.cpp:57
mavros::extra_plugins::CellularStatusPlugin
Cellular status plugin.
Definition: cellular_status.cpp:28
mavros::extra_plugins::CellularStatusPlugin::get_subscriptions
Subscriptions get_subscriptions()
Definition: cellular_status.cpp:51
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
mavros
initialize
virtual void initialize(UAS &uas)
mavros::plugin::PluginBase
class_list_macros.hpp
mavros::extra_plugins::CellularStatusPlugin::cellularStatusCb
void cellularStatusCb(const mavros_msgs::CellularStatus &msg)
Send Cellular Status messages to mavlink system.
Definition: cellular_status.cpp:65
mavros::extra_plugins::CellularStatusPlugin::initialize
void initialize(UAS &uas_)
Definition: cellular_status.cpp:37
ros::NodeHandle
ros::Subscriber


mavros_extras
Author(s): Vladimir Ermakov , Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08