18 #include <mavros_msgs/CellularStatus.h> 21 namespace extra_plugins {
31 cc_nh(
"~cellular_status")
67 mavlink::common::msg::CELLULAR_STATUS cs{};
69 cs.status = msg.status;
70 cs.failure_reason = msg.failure_reason;
72 cs.quality = msg.quality;
ros::Subscriber subCellularStatus
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void cellularStatusCb(const mavros_msgs::CellularStatus &msg)
Send Cellular Status messages to mavlink system.
void initialize(UAS &uas_)
#define UAS_FCU(uasobjptr)
Subscriptions get_subscriptions()
std::vector< HandlerInfo > Subscriptions
void initialize(UAS &uas_) override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)