20 #include <mavros_msgs/State.h>
21 #include <mavros_msgs/EstimatorStatus.h>
22 #include <mavros_msgs/ExtendedState.h>
23 #include <mavros_msgs/StreamRate.h>
24 #include <mavros_msgs/SetMode.h>
25 #include <mavros_msgs/CommandLong.h>
26 #include <mavros_msgs/StatusText.h>
27 #include <mavros_msgs/VehicleInfo.h>
28 #include <mavros_msgs/VehicleInfoGet.h>
29 #include <mavros_msgs/MessageInterval.h>
30 #include <mavros_msgs/SysStatus.h>
33 #ifdef HAVE_SENSOR_MSGS_BATTERYSTATE_MSG
34 #include <sensor_msgs/BatteryState.h>
37 #include <mavros_msgs/BatteryStatus.h>
42 namespace std_plugins {
43 using mavlink::minimal::MAV_TYPE;
44 using mavlink::minimal::MAV_AUTOPILOT;
45 using mavlink::minimal::MAV_STATE;
48 #define MAX_NR_BATTERY_STATUS 10
67 type(MAV_TYPE::GENERIC),
75 std::lock_guard<std::mutex> lock(
mutex);
87 void tick(uint8_t type_, uint8_t autopilot_,
88 std::string &mode_, uint8_t system_status_)
90 std::lock_guard<std::mutex> lock(
mutex);
93 type =
static_cast<MAV_TYPE
>(type_);
94 autopilot =
static_cast<MAV_AUTOPILOT
>(autopilot_);
101 std::lock_guard<std::mutex> lock(
mutex);
107 double freq = events / window;
113 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"No events recorded.");
116 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Frequency too low.");
119 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Frequency too high.");
122 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Normal");
125 stat.
addf(
"Heartbeats since startup",
"%d",
count_);
126 stat.
addf(
"Frequency (Hz)",
"%f", freq);
162 void set(mavlink::common::msg::SYS_STATUS &st)
164 std::lock_guard<std::mutex> lock(
mutex);
169 std::lock_guard<std::mutex> lock(
mutex);
171 if ((
last_st.onboard_control_sensors_health &
last_st.onboard_control_sensors_enabled)
172 !=
last_st.onboard_control_sensors_enabled)
173 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Sensor health");
175 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Normal");
177 stat.
addf(
"Sensor present",
"0x%08X",
last_st.onboard_control_sensors_present);
178 stat.
addf(
"Sensor enabled",
"0x%08X",
last_st.onboard_control_sensors_enabled);
179 stat.
addf(
"Sensor health",
"0x%08X",
last_st.onboard_control_sensors_health);
181 using STS = mavlink::common::MAV_SYS_STATUS_SENSOR;
207 stat.
add(
"3D gyro", (
last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_GYRO)) ?
"Ok" :
"Fail");
209 stat.
add(
"3D accelerometer", (
last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_ACCEL)) ?
"Ok" :
"Fail");
211 stat.
add(
"3D magnetometer", (
last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_MAG)) ?
"Ok" :
"Fail");
212 if (
last_st.onboard_control_sensors_enabled &
enum_value(STS::ABSOLUTE_PRESSURE))
213 stat.
add(
"absolute pressure", (
last_st.onboard_control_sensors_health &
enum_value(STS::ABSOLUTE_PRESSURE)) ?
"Ok" :
"Fail");
214 if (
last_st.onboard_control_sensors_enabled &
enum_value(STS::DIFFERENTIAL_PRESSURE))
215 stat.
add(
"differential pressure", (
last_st.onboard_control_sensors_health &
enum_value(STS::DIFFERENTIAL_PRESSURE)) ?
"Ok" :
"Fail");
217 stat.
add(
"GPS", (
last_st.onboard_control_sensors_health &
enum_value(STS::GPS)) ?
"Ok" :
"Fail");
219 stat.
add(
"optical flow", (
last_st.onboard_control_sensors_health &
enum_value(STS::OPTICAL_FLOW)) ?
"Ok" :
"Fail");
221 stat.
add(
"computer vision position", (
last_st.onboard_control_sensors_health &
enum_value(STS::VISION_POSITION)) ?
"Ok" :
"Fail");
223 stat.
add(
"laser based position", (
last_st.onboard_control_sensors_health &
enum_value(STS::LASER_POSITION)) ?
"Ok" :
"Fail");
224 if (
last_st.onboard_control_sensors_enabled &
enum_value(STS::EXTERNAL_GROUND_TRUTH))
225 stat.
add(
"external ground truth (Vicon or Leica)", (
last_st.onboard_control_sensors_health &
enum_value(STS::EXTERNAL_GROUND_TRUTH)) ?
"Ok" :
"Fail");
226 if (
last_st.onboard_control_sensors_enabled &
enum_value(STS::ANGULAR_RATE_CONTROL))
227 stat.
add(
"3D angular rate control", (
last_st.onboard_control_sensors_health &
enum_value(STS::ANGULAR_RATE_CONTROL)) ?
"Ok" :
"Fail");
228 if (
last_st.onboard_control_sensors_enabled &
enum_value(STS::ATTITUDE_STABILIZATION))
229 stat.
add(
"attitude stabilization", (
last_st.onboard_control_sensors_health &
enum_value(STS::ATTITUDE_STABILIZATION)) ?
"Ok" :
"Fail");
231 stat.
add(
"yaw position", (
last_st.onboard_control_sensors_health &
enum_value(STS::YAW_POSITION)) ?
"Ok" :
"Fail");
232 if (
last_st.onboard_control_sensors_enabled &
enum_value(STS::Z_ALTITUDE_CONTROL))
233 stat.
add(
"z/altitude control", (
last_st.onboard_control_sensors_health &
enum_value(STS::Z_ALTITUDE_CONTROL)) ?
"Ok" :
"Fail");
234 if (
last_st.onboard_control_sensors_enabled &
enum_value(STS::XY_POSITION_CONTROL))
235 stat.
add(
"x/y position control", (
last_st.onboard_control_sensors_health &
enum_value(STS::XY_POSITION_CONTROL)) ?
"Ok" :
"Fail");
237 stat.
add(
"motor outputs / control", (
last_st.onboard_control_sensors_health &
enum_value(STS::MOTOR_OUTPUTS)) ?
"Ok" :
"Fail");
239 stat.
add(
"rc receiver", (
last_st.onboard_control_sensors_health &
enum_value(STS::RC_RECEIVER)) ?
"Ok" :
"Fail");
241 stat.
add(
"2nd 3D gyro", (
last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_GYRO2)) ?
"Ok" :
"Fail");
243 stat.
add(
"2nd 3D accelerometer", (
last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_ACCEL2)) ?
"Ok" :
"Fail");
245 stat.
add(
"2nd 3D magnetometer", (
last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_MAG2)) ?
"Ok" :
"Fail");
247 stat.
add(
"geofence", (
last_st.onboard_control_sensors_health &
enum_value(STS::GEOFENCE)) ?
"Ok" :
"Fail");
249 stat.
add(
"AHRS subsystem health", (
last_st.onboard_control_sensors_health &
enum_value(STS::AHRS)) ?
"Ok" :
"Fail");
251 stat.
add(
"Terrain subsystem health", (
last_st.onboard_control_sensors_health &
enum_value(STS::TERRAIN)) ?
"Ok" :
"Fail");
253 stat.
add(
"Motors are reversed", (
last_st.onboard_control_sensors_health &
enum_value(STS::REVERSE_MOTOR)) ?
"Ok" :
"Fail");
255 stat.
add(
"Logging", (
last_st.onboard_control_sensors_health &
enum_value(STS::LOGGING)) ?
"Ok" :
"Fail");
257 stat.
add(
"Battery", (
last_st.onboard_control_sensors_health &
enum_value(STS::BATTERY)) ?
"Ok" :
"Fail");
259 stat.
add(
"Proximity", (
last_st.onboard_control_sensors_health &
enum_value(STS::PROXIMITY)) ?
"Ok" :
"Fail");
261 stat.
add(
"Satellite Communication", (
last_st.onboard_control_sensors_health &
enum_value(STS::SATCOM)) ?
"Ok" :
"Fail");
263 stat.
add(
"pre-arm check status. Always healthy when armed", (
last_st.onboard_control_sensors_health &
enum_value(STS::PREARM_CHECK)) ?
"Ok" :
"Fail");
264 if (
last_st.onboard_control_sensors_enabled &
enum_value(STS::OBSTACLE_AVOIDANCE))
265 stat.
add(
"Avoidance/collision prevention", (
last_st.onboard_control_sensors_health &
enum_value(STS::OBSTACLE_AVOIDANCE)) ?
"Ok" :
"Fail");
267 stat.
add(
"propulsion (actuator, esc, motor or propellor)", (
last_st.onboard_control_sensors_health &
enum_value(STS::PROPULSION)) ?
"Ok" :
"Fail");
270 stat.
addf(
"CPU Load (%)",
"%.1f",
last_st.load / 10.0);
271 stat.
addf(
"Drop rate (%)",
"%.1f",
last_st.drop_rate_comm / 10.0);
272 stat.
addf(
"Errors comm",
"%d",
last_st.errors_comm);
273 stat.
addf(
"Errors count #1",
"%d",
last_st.errors_count1);
274 stat.
addf(
"Errors count #2",
"%d",
last_st.errors_count2);
275 stat.
addf(
"Errors count #3",
"%d",
last_st.errors_count3);
276 stat.
addf(
"Errors count #4",
"%d",
last_st.errors_count4);
308 *
this = std::move(other);
316 *
this = std::move(other);
322 std::lock_guard<std::mutex> lock(
mutex);
326 void set(
float volt,
float curr,
float rem) {
327 std::lock_guard<std::mutex> lock(
mutex);
334 std::lock_guard<std::mutex> lock(
mutex);
340 std::lock_guard<std::mutex> lock(
mutex);
343 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"No data");
345 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Low voltage");
347 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Normal");
355 for (
int i = 1; i <= nr_cells ; ++i) {
384 void set(uint32_t f, uint16_t b) {
394 uint16_t brkval_ =
brkval;
397 constexpr
int timeout = 10.0;
402 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Not initialised");
404 stat.
summary(diagnostic_msgs::DiagnosticStatus::STALE,
"Not received for more than " +
std::to_string(timeout) +
"s");
407 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"No data");
409 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Low mem");
411 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Normal");
413 stat.
addf(
"Free memory (B)",
"%zd", freemem_);
414 stat.
addf(
"Heap top",
"0x%04X", brkval_);
438 void set(uint16_t v, uint8_t e) {
439 std::lock_guard<std::mutex> lock(
mutex);
447 std::lock_guard<std::mutex> lock(
mutex);
448 constexpr
int timeout = 10.0;
451 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Not initialised");
453 stat.
summary(diagnostic_msgs::DiagnosticStatus::STALE,
"Not received for more than " +
std::to_string(timeout) +
"s");
456 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"No data");
458 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Low voltage");
461 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"New I2C error");
464 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Normal");
466 stat.
addf(
"Core voltage",
"%f",
vcc);
507 PluginBase::initialize(uas_);
511 double conn_timeout_d;
512 double conn_heartbeat_d;
513 std::vector<double> min_voltage;
514 std::string conn_heartbeat_mav_type_str;
516 nh.
param(
"conn/timeout", conn_timeout_d, 10.0);
517 nh.
param(
"sys/min_voltage", min_voltage, {10.0});
521 if (
nh.
getParam(
"conn/heartbeat_rate", conn_heartbeat_d) && conn_heartbeat_d != 0.0) {
526 if (
nh.
getParam(
"conn/heartbeat_mav_type", conn_heartbeat_mav_type_str)) {
535 batt_diag[i].set_min_voltage(min_voltage[i]);
546 if (!conn_heartbeat.
isZero()) {
618 using M_VehicleInfo = std::unordered_map<uint16_t, mavros_msgs::VehicleInfo>;
625 return sysid << 8 | compid;
631 M_VehicleInfo::iterator ret =
vehicles.find(key);
635 mavros_msgs::VehicleInfo v;
638 v.available_info = 0;
640 auto res =
vehicles.emplace(key, v);
655 using mavlink::common::MAV_SEVERITY;
697 memcpy(&b, array.data(),
sizeof(uint64_t));
706 std::snprintf(prefix,
sizeof(prefix),
"VER: %d.%d", sysid, compid);
708 ROS_INFO_NAMED(
"sys",
"%s: Capabilities 0x%016llx", prefix, (
long long int)apv.capabilities);
711 apv.flight_sw_version,
715 apv.middleware_sw_version,
721 ROS_INFO_NAMED(
"sys",
"%s: Board hardware: %08x", prefix, apv.board_version);
722 ROS_INFO_NAMED(
"sys",
"%s: VID/PID: %04x:%04x", prefix, apv.vendor_id, apv.product_id);
723 ROS_INFO_NAMED(
"sys",
"%s: UID: %016llx", prefix, (
long long int)apv.uid);
729 std::snprintf(prefix,
sizeof(prefix),
"VER: %d.%d", sysid, compid);
733 ROS_INFO_NAMED(
"sys",
"%s: Capabilities 0x%016llx", prefix, (
long long int)apv.capabilities);
736 apv.flight_sw_version,
737 8, apv.flight_custom_version.data());
740 apv.middleware_sw_version,
741 8, apv.middleware_custom_version.data());
745 8, apv.os_custom_version.data());
746 ROS_INFO_NAMED(
"sys",
"%s: Board hardware: %08x", prefix, apv.board_version);
747 ROS_INFO_NAMED(
"sys",
"%s: VID/PID: %04x:%04x", prefix, apv.vendor_id, apv.product_id);
748 ROS_INFO_NAMED(
"sys",
"%s: UID: %016llx", prefix, (
long long int)apv.uid);
752 auto state_msg = boost::make_shared<mavros_msgs::State>();
754 state_msg->connected =
false;
755 state_msg->armed =
false;
756 state_msg->guided =
false;
757 state_msg->mode =
"";
758 state_msg->system_status =
enum_value(MAV_STATE::UNINIT);
765 void handle_heartbeat(
const mavlink::mavlink_message_t *msg, mavlink::minimal::msg::HEARTBEAT &hb)
767 using mavlink::minimal::MAV_MODE_FLAG;
776 it->second.header.stamp = stamp;
777 it->second.available_info |= mavros_msgs::VehicleInfo::HAVE_INFO_HEARTBEAT;
778 it->second.autopilot = hb.autopilot;
779 it->second.type = hb.type;
780 it->second.system_status = hb.system_status;
781 it->second.base_mode = hb.base_mode;
782 it->second.custom_mode = hb.custom_mode;
783 it->second.mode = vehicle_mode;
785 if (!(hb.base_mode &
enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED))) {
786 it->second.mode_id = hb.base_mode;
788 it->second.mode_id = hb.custom_mode;
804 auto state_msg = boost::make_shared<mavros_msgs::State>();
805 state_msg->header.stamp = stamp;
806 state_msg->connected =
true;
807 state_msg->armed = !!(hb.base_mode &
enum_value(MAV_MODE_FLAG::SAFETY_ARMED));
808 state_msg->guided = !!(hb.base_mode &
enum_value(MAV_MODE_FLAG::GUIDED_ENABLED));
809 state_msg->manual_input = !!(hb.base_mode &
enum_value(MAV_MODE_FLAG::MANUAL_INPUT_ENABLED));
810 state_msg->mode = vehicle_mode;
811 state_msg->system_status = hb.system_status;
814 hb_diag.
tick(hb.type, hb.autopilot, state_msg->mode, hb.system_status);
819 auto state_msg = boost::make_shared<mavros_msgs::ExtendedState>();
821 state_msg->vtol_state = state.vtol_state;
822 state_msg->landed_state = state.landed_state;
827 void handle_sys_status(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::SYS_STATUS &stat)
829 using MC = mavlink::minimal::MAV_COMPONENT;
830 if (
static_cast<MC
>(
msg->compid) == MC::COMP_ID_GIMBAL) {
834 float volt = stat.voltage_battery * 0.001f;
835 float curr = stat.current_battery * 0.01f;
836 float rem = stat.battery_remaining * 0.01f;
840 mavros_msgs::SysStatus sys_status;
842 sys_status.sensors_present = stat.onboard_control_sensors_present;
843 sys_status.sensors_enabled = stat.onboard_control_sensors_enabled;
844 sys_status.sensors_health = stat.onboard_control_sensors_health;
846 sys_status.load = stat.load;
847 sys_status.voltage_battery = stat.voltage_battery;
848 sys_status.current_battery = stat.current_battery;
849 sys_status.battery_remaining = stat.battery_remaining;
850 sys_status.drop_rate_comm = stat.drop_rate_comm;
851 sys_status.errors_comm = stat.errors_comm;
852 sys_status.errors_count1 = stat.errors_count1;
853 sys_status.errors_count2 = stat.errors_count2;
854 sys_status.errors_count3 = stat.errors_count3;
855 sys_status.errors_count4 = stat.errors_count4;
863 auto batt_msg = boost::make_shared<BatteryMsg>();
866 #ifdef HAVE_SENSOR_MSGS_BATTERYSTATE_MSG
867 batt_msg->voltage = volt;
868 batt_msg->current = -curr;
869 batt_msg->charge = NAN;
870 batt_msg->capacity = NAN;
871 batt_msg->design_capacity = NAN;
872 batt_msg->percentage = rem;
873 batt_msg->power_supply_status = BatteryMsg::POWER_SUPPLY_STATUS_DISCHARGING;
874 batt_msg->power_supply_health = BatteryMsg::POWER_SUPPLY_HEALTH_UNKNOWN;
875 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_UNKNOWN;
876 batt_msg->present =
true;
877 batt_msg->cell_voltage.clear();
878 batt_msg->location =
"";
879 batt_msg->serial_number =
"";
880 #else // mavros_msgs::BatteryStatus
881 batt_msg->voltage = volt;
882 batt_msg->current = curr;
883 batt_msg->remaining = rem;
889 void handle_statustext(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::STATUSTEXT &textm)
894 auto st_msg = boost::make_shared<mavros_msgs::StatusText>();
896 st_msg->severity = textm.severity;
901 void handle_meminfo(
const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::MEMINFO &mem)
903 mem_diag.
set(std::max(
static_cast<uint32_t
>(mem.freemem), mem.freemem32), mem.brkval);
906 void handle_hwstatus(
const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::HWSTATUS &hwst)
930 it->second.available_info |= mavros_msgs::VehicleInfo::HAVE_INFO_AUTOPILOT_VERSION;
931 it->second.capabilities = apv.capabilities;
932 it->second.flight_sw_version = apv.flight_sw_version;
933 it->second.middleware_sw_version = apv.middleware_sw_version;
934 it->second.os_sw_version = apv.os_sw_version;
935 it->second.board_version = apv.board_version;
937 it->second.vendor_id = apv.vendor_id;
938 it->second.product_id = apv.product_id;
939 it->second.uid = apv.uid;
944 #ifdef HAVE_SENSOR_MSGS_BATTERYSTATE_MSG
945 using BT = mavlink::common::MAV_BATTERY_TYPE;
946 auto batt_msg = boost::make_shared<BatteryMsg>();
949 batt_msg->current = bs.current_battery==-1?NAN:-(bs.current_battery * 0.01f);
950 batt_msg->charge = NAN;
951 batt_msg->capacity = NAN;
952 batt_msg->design_capacity = NAN;
953 batt_msg->percentage = bs.battery_remaining * 0.01f;
954 batt_msg->power_supply_status = BatteryMsg::POWER_SUPPLY_STATUS_DISCHARGING;
955 batt_msg->power_supply_health = BatteryMsg::POWER_SUPPLY_HEALTH_UNKNOWN;
972 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_LIPO;
975 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_LIFE;
978 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_LION;
981 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_NIMH;
985 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_UNKNOWN;
990 batt_msg->present =
true;
992 batt_msg->cell_voltage.clear();
993 batt_msg->cell_voltage.reserve(bs.voltages.size() + bs.voltages_ext.size());
995 float voltage_acc = 0.0f;
996 float total_voltage = 0.0f;
997 constexpr
float coalesce_voltage = (UINT16_MAX-1) * 0.001
f;
998 for (
auto v : bs.voltages) {
1002 if (v == UINT16_MAX-1)
1004 voltage_acc += coalesce_voltage;
1007 cell_voltage = voltage_acc + (v * 0.001f);
1009 batt_msg->cell_voltage.push_back(cell_voltage);
1010 total_voltage += cell_voltage;
1012 for (
auto v : bs.voltages_ext) {
1013 if (v == UINT16_MAX || v == 0)
1016 if (v == UINT16_MAX-1)
1018 voltage_acc += coalesce_voltage;
1021 cell_voltage = voltage_acc + (v * 0.001f);
1023 batt_msg->cell_voltage.push_back(cell_voltage);
1024 total_voltage += cell_voltage;
1026 batt_msg->voltage = total_voltage;
1029 batt_msg->serial_number =
"";
1037 batt_diag[bs.id].set(total_voltage, batt_msg->current, batt_msg->percentage);
1038 batt_diag[bs.id].setcell_v(batt_msg->cell_voltage);
1045 using ESF = mavlink::common::ESTIMATOR_STATUS_FLAGS;
1047 auto est_status_msg = boost::make_shared<mavros_msgs::EstimatorStatus>();
1070 est_status_msg->attitude_status_flag = !!(status.flags &
enum_value(ESF::ATTITUDE));
1071 est_status_msg->velocity_horiz_status_flag = !!(status.flags &
enum_value(ESF::VELOCITY_HORIZ));
1072 est_status_msg->velocity_vert_status_flag = !!(status.flags &
enum_value(ESF::VELOCITY_VERT));
1073 est_status_msg->pos_horiz_rel_status_flag = !!(status.flags &
enum_value(ESF::POS_HORIZ_REL));
1074 est_status_msg->pos_horiz_abs_status_flag = !!(status.flags &
enum_value(ESF::POS_HORIZ_ABS));
1075 est_status_msg->pos_vert_abs_status_flag = !!(status.flags &
enum_value(ESF::POS_VERT_ABS));
1076 est_status_msg->pos_vert_agl_status_flag = !!(status.flags &
enum_value(ESF::POS_VERT_AGL));
1077 est_status_msg->const_pos_mode_status_flag = !!(status.flags &
enum_value(ESF::CONST_POS_MODE));
1078 est_status_msg->pred_pos_horiz_rel_status_flag = !!(status.flags &
enum_value(ESF::PRED_POS_HORIZ_REL));
1079 est_status_msg->pred_pos_horiz_abs_status_flag = !!(status.flags &
enum_value(ESF::PRED_POS_HORIZ_ABS));
1080 est_status_msg->gps_glitch_status_flag = !!(status.flags &
enum_value(ESF::GPS_GLITCH));
1081 est_status_msg->accel_error_status_flag = !!(status.flags &
enum_value(ESF::ACCEL_ERROR));
1096 using mavlink::common::MAV_MODE;
1098 mavlink::minimal::msg::HEARTBEAT hb {};
1101 hb.autopilot =
enum_value(MAV_AUTOPILOT::INVALID);
1102 hb.base_mode =
enum_value(MAV_MODE::MANUAL_ARMED);
1104 hb.system_status =
enum_value(MAV_STATE::ACTIVE);
1111 using mavlink::common::MAV_CMD;
1119 auto client =
nh.
serviceClient<mavros_msgs::CommandLong>(
"cmd/command");
1121 mavros_msgs::CommandLong
cmd{};
1123 cmd.request.broadcast = do_broadcast;
1124 cmd.request.command =
enum_value(MAV_CMD::REQUEST_AUTOPILOT_CAPABILITIES);
1125 cmd.request.confirmation =
false;
1126 cmd.request.param1 = 1.0;
1129 (do_broadcast) ?
"broadcast" :
"unicast");
1130 ret = client.call(
cmd);
1141 "VER: %s request timeout, retries left %d",
1142 (do_broadcast) ?
"broadcast" :
"unicast",
1148 ROS_WARN_NAMED(
"sys",
"VER: your FCU don't support AUTOPILOT_VERSION, "
1149 "switched to default capabilities");
1186 mavlink::common::msg::STATUSTEXT statustext {};
1187 statustext.severity = req->severity;
1191 "Status text too long: truncating...");
1192 mavlink::set_string_z(statustext.text, req->text);
1200 mavros_msgs::StreamRate::Response &res)
1202 mavlink::common::msg::REQUEST_DATA_STREAM rq = {};
1206 rq.req_stream_id = req.stream_id;
1207 rq.req_message_rate = req.message_rate;
1208 rq.start_stop = (req.on_off) ? 1 : 0;
1215 mavros_msgs::SetMode::Response &res)
1217 using mavlink::minimal::MAV_MODE_FLAG;
1219 uint8_t base_mode = req.base_mode;
1220 uint32_t custom_mode = 0;
1222 if (req.custom_mode !=
"") {
1224 res.mode_sent =
false;
1235 base_mode |=
enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED);
1238 mavlink::common::msg::SET_MODE sm = {};
1240 sm.base_mode = base_mode;
1241 sm.custom_mode = custom_mode;
1244 res.mode_sent =
true;
1249 mavros_msgs::VehicleInfoGet::Response &res)
1254 res.vehicles.emplace_back(got.second);
1261 uint8_t req_sysid = req.sysid;
1262 uint8_t req_compid = req.compid;
1264 if (req.sysid == 0 && req.compid == 0) {
1275 res.success =
false;
1279 res.vehicles.emplace_back(it->second);
1285 mavros_msgs::MessageInterval::Response &res)
1287 using mavlink::common::MAV_CMD;
1290 auto client =
nh.
serviceClient<mavros_msgs::CommandLong>(
"cmd/command");
1294 if (req.message_rate < 0) {
1295 interval_us = -1.0f;
1296 }
else if (req.message_rate == 0) {
1299 interval_us = 1000000.0f / req.message_rate;
1302 mavros_msgs::CommandLong
cmd{};
1304 cmd.request.broadcast =
false;
1305 cmd.request.command =
enum_value(MAV_CMD::SET_MESSAGE_INTERVAL);
1306 cmd.request.confirmation =
false;
1307 cmd.request.param1 = req.message_id;
1308 cmd.request.param2 = interval_us;
1310 ROS_DEBUG_NAMED(
"sys",
"SetMessageInterval: Request msgid %u at %f hz",
1311 req.message_id, req.message_rate);
1312 res.success = client.call(
cmd);
1318 ROS_ERROR_COND_NAMED(!res.success,
"sys",
"SetMessageInterval: command plugin service call failed!");