19 #include <mavros_msgs/CompanionProcessStatus.h> 22 namespace extra_plugins {
27 using mavlink::common::MAV_COMPONENT;
66 mavlink::common::msg::HEARTBEAT heartbeat {};
68 heartbeat.type =
enum_value(mavlink::common::MAV_TYPE::ONBOARD_CONTROLLER);
69 heartbeat.autopilot =
enum_value(mavlink::common::MAV_AUTOPILOT::PX4);
70 heartbeat.base_mode =
enum_value(mavlink::common::MAV_MODE_FLAG::CUSTOM_MODE_ENABLED);
71 heartbeat.system_status = req->state;
74 utils::to_string_enum<MAV_COMPONENT>(req->component) <<
" companion process status: " <<
75 utils::to_string_enum<MAV_STATE>(heartbeat.system_status) << std::endl << heartbeat.to_yaml());
77 UAS_FCU(
m_uas)->send_message_ignore_drop(heartbeat, req->component);
std::shared_ptr< MAVConnInterface const > ConstPtr
#define ROS_DEBUG_STREAM_NAMED(name, args)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
mavlink::common::MAV_TYPE MAV_TYPE
void initialize(UAS &uas_)
ros::Subscriber status_sub
#define UAS_FCU(uasobjptr)
ros::NodeHandle status_nh
Subscriptions get_subscriptions()
void status_cb(const mavros_msgs::CompanionProcessStatus::ConstPtr &req)
Send companion process status to FCU over a heartbeat message.
std::vector< HandlerInfo > Subscriptions
void initialize(UAS &uas_)
CompanionProcessStatusPlugin()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mavlink::common::MAV_STATE MAV_STATE
constexpr std::underlying_type< _T >::type enum_value(_T e)