|
void | autopilot_version_cb (const ros::TimerEvent &event) |
|
void | connection_cb (bool connected) override |
|
M_VehicleInfo::iterator | find_or_create_vehicle_info (uint8_t sysid, uint8_t compid) |
|
uint16_t | get_vehicle_key (uint8_t sysid, uint8_t compid) |
|
void | handle_autopilot_version (const mavlink::mavlink_message_t *msg, mavlink::common::msg::AUTOPILOT_VERSION &apv) |
|
void | handle_battery_status (const mavlink::mavlink_message_t *msg, mavlink::common::msg::BATTERY_STATUS &bs) |
|
void | handle_estimator_status (const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESTIMATOR_STATUS &status) |
|
void | handle_extended_sys_state (const mavlink::mavlink_message_t *msg, mavlink::common::msg::EXTENDED_SYS_STATE &state) |
|
void | handle_heartbeat (const mavlink::mavlink_message_t *msg, mavlink::minimal::msg::HEARTBEAT &hb) |
|
void | handle_hwstatus (const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::HWSTATUS &hwst) |
|
void | handle_meminfo (const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::MEMINFO &mem) |
|
void | handle_statustext (const mavlink::mavlink_message_t *msg, mavlink::common::msg::STATUSTEXT &textm) |
|
void | handle_sys_status (const mavlink::mavlink_message_t *msg, mavlink::common::msg::SYS_STATUS &stat) |
|
void | heartbeat_cb (const ros::TimerEvent &event) |
|
void | process_autopilot_version_apm_quirk (mavlink::common::msg::AUTOPILOT_VERSION &apv, uint8_t sysid, uint8_t compid) |
|
void | process_autopilot_version_normal (mavlink::common::msg::AUTOPILOT_VERSION &apv, uint8_t sysid, uint8_t compid) |
|
void | process_statustext_normal (uint8_t severity, std::string &text) |
|
void | publish_disconnection () |
|
bool | set_message_interval_cb (mavros_msgs::MessageInterval::Request &req, mavros_msgs::MessageInterval::Response &res) |
|
bool | set_mode_cb (mavros_msgs::SetMode::Request &req, mavros_msgs::SetMode::Response &res) |
|
bool | set_rate_cb (mavros_msgs::StreamRate::Request &req, mavros_msgs::StreamRate::Response &res) |
|
void | statustext_cb (const mavros_msgs::StatusText::ConstPtr &req) |
|
void | timeout_cb (const ros::TimerEvent &event) |
|
bool | vehicle_info_get_cb (mavros_msgs::VehicleInfoGet::Request &req, mavros_msgs::VehicleInfoGet::Response &res) |
|
|
using | ConstPtr = boost::shared_ptr< PluginBase const > |
|
using | HandlerCb = mavconn::MAVConnInterface::ReceivedCb |
| generic message handler callback More...
|
|
using | HandlerInfo = std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCb > |
| Tuple: MSG ID, MSG NAME, message type into hash_code, message handler callback. More...
|
|
using | Ptr = boost::shared_ptr< PluginBase > |
|
using | Subscriptions = std::vector< HandlerInfo > |
| Subscriptions vector. More...
|
|
virtual void | capabilities_cb (UAS::MAV_CAP capabilities) |
|
void | enable_capabilities_cb () |
|
void | enable_connection_cb () |
|
template<class _C > |
HandlerInfo | make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing)) |
|
template<class _C , class _T > |
HandlerInfo | make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &)) |
|
| PluginBase () |
| Plugin constructor Should not do anything before initialize() More...
|
|
UAS * | m_uas |
|
System status plugin.
Required by all plugins.
Definition at line 422 of file sys_status.cpp.