19 #include <mavros_msgs/State.h> 20 #include <mavros_msgs/EstimatorStatus.h> 21 #include <mavros_msgs/ExtendedState.h> 22 #include <mavros_msgs/StreamRate.h> 23 #include <mavros_msgs/SetMode.h> 24 #include <mavros_msgs/CommandLong.h> 25 #include <mavros_msgs/StatusText.h> 26 #include <mavros_msgs/VehicleInfo.h> 27 #include <mavros_msgs/VehicleInfoGet.h> 28 #include <mavros_msgs/MessageInterval.h> 31 #ifdef HAVE_SENSOR_MSGS_BATTERYSTATE_MSG 32 #include <sensor_msgs/BatteryState.h> 35 #include <mavros_msgs/BatteryStatus.h> 40 namespace std_plugins {
41 using mavlink::minimal::MAV_TYPE;
42 using mavlink::minimal::MAV_AUTOPILOT;
43 using mavlink::minimal::MAV_STATE;
71 std::lock_guard<std::mutex> lock(
mutex);
83 void tick(uint8_t type_, uint8_t autopilot_,
84 std::string &mode_, uint8_t system_status_)
86 std::lock_guard<std::mutex> lock(
mutex);
90 autopilot =
static_cast<MAV_AUTOPILOT
>(autopilot_);
97 std::lock_guard<std::mutex> lock(
mutex);
103 double freq = events / window;
109 stat.
summary(2,
"No events recorded.");
112 stat.
summary(1,
"Frequency too low.");
115 stat.
summary(1,
"Frequency too high.");
121 stat.
addf(
"Heartbeats since startup",
"%d",
count_);
122 stat.
addf(
"Frequency (Hz)",
"%f", freq);
158 void set(mavlink::common::msg::SYS_STATUS &st)
160 std::lock_guard<std::mutex> lock(
mutex);
165 std::lock_guard<std::mutex> lock(
mutex);
167 if ((last_st.onboard_control_sensors_health & last_st.onboard_control_sensors_enabled)
168 != last_st.onboard_control_sensors_enabled)
169 stat.
summary(2,
"Sensor health");
173 stat.
addf(
"Sensor present",
"0x%08X", last_st.onboard_control_sensors_present);
174 stat.
addf(
"Sensor enabled",
"0x%08X", last_st.onboard_control_sensors_enabled);
175 stat.
addf(
"Sensor health",
"0x%08X", last_st.onboard_control_sensors_health);
177 using STS = mavlink::common::MAV_SYS_STATUS_SENSOR;
202 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::SENSOR_3D_GYRO))
203 stat.
add(
"3D gyro", (last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_GYRO)) ?
"Ok" :
"Fail");
204 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::SENSOR_3D_ACCEL))
205 stat.
add(
"3D accelerometer", (last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_ACCEL)) ?
"Ok" :
"Fail");
206 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::SENSOR_3D_MAG))
207 stat.
add(
"3D magnetometer", (last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_MAG)) ?
"Ok" :
"Fail");
208 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::ABSOLUTE_PRESSURE))
209 stat.
add(
"absolute pressure", (last_st.onboard_control_sensors_health &
enum_value(STS::ABSOLUTE_PRESSURE)) ?
"Ok" :
"Fail");
210 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::DIFFERENTIAL_PRESSURE))
211 stat.
add(
"differential pressure", (last_st.onboard_control_sensors_health &
enum_value(STS::DIFFERENTIAL_PRESSURE)) ?
"Ok" :
"Fail");
212 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::GPS))
213 stat.
add(
"GPS", (last_st.onboard_control_sensors_health &
enum_value(STS::GPS)) ?
"Ok" :
"Fail");
214 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::OPTICAL_FLOW))
215 stat.
add(
"optical flow", (last_st.onboard_control_sensors_health &
enum_value(STS::OPTICAL_FLOW)) ?
"Ok" :
"Fail");
216 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::VISION_POSITION))
217 stat.
add(
"computer vision position", (last_st.onboard_control_sensors_health &
enum_value(STS::VISION_POSITION)) ?
"Ok" :
"Fail");
218 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::LASER_POSITION))
219 stat.
add(
"laser based position", (last_st.onboard_control_sensors_health &
enum_value(STS::LASER_POSITION)) ?
"Ok" :
"Fail");
220 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::EXTERNAL_GROUND_TRUTH))
221 stat.
add(
"external ground truth (Vicon or Leica)", (last_st.onboard_control_sensors_health &
enum_value(STS::EXTERNAL_GROUND_TRUTH)) ?
"Ok" :
"Fail");
222 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::ANGULAR_RATE_CONTROL))
223 stat.
add(
"3D angular rate control", (last_st.onboard_control_sensors_health &
enum_value(STS::ANGULAR_RATE_CONTROL)) ?
"Ok" :
"Fail");
224 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::ATTITUDE_STABILIZATION))
225 stat.
add(
"attitude stabilization", (last_st.onboard_control_sensors_health &
enum_value(STS::ATTITUDE_STABILIZATION)) ?
"Ok" :
"Fail");
226 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::YAW_POSITION))
227 stat.
add(
"yaw position", (last_st.onboard_control_sensors_health &
enum_value(STS::YAW_POSITION)) ?
"Ok" :
"Fail");
228 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::Z_ALTITUDE_CONTROL))
229 stat.
add(
"z/altitude control", (last_st.onboard_control_sensors_health &
enum_value(STS::Z_ALTITUDE_CONTROL)) ?
"Ok" :
"Fail");
230 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::XY_POSITION_CONTROL))
231 stat.
add(
"x/y position control", (last_st.onboard_control_sensors_health &
enum_value(STS::XY_POSITION_CONTROL)) ?
"Ok" :
"Fail");
232 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::MOTOR_OUTPUTS))
233 stat.
add(
"motor outputs / control", (last_st.onboard_control_sensors_health &
enum_value(STS::MOTOR_OUTPUTS)) ?
"Ok" :
"Fail");
234 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::RC_RECEIVER))
235 stat.
add(
"rc receiver", (last_st.onboard_control_sensors_health &
enum_value(STS::RC_RECEIVER)) ?
"Ok" :
"Fail");
236 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::SENSOR_3D_GYRO2))
237 stat.
add(
"2nd 3D gyro", (last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_GYRO2)) ?
"Ok" :
"Fail");
238 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::SENSOR_3D_ACCEL2))
239 stat.
add(
"2nd 3D accelerometer", (last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_ACCEL2)) ?
"Ok" :
"Fail");
240 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::SENSOR_3D_MAG2))
241 stat.
add(
"2nd 3D magnetometer", (last_st.onboard_control_sensors_health &
enum_value(STS::SENSOR_3D_MAG2)) ?
"Ok" :
"Fail");
242 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::GEOFENCE))
243 stat.
add(
"geofence", (last_st.onboard_control_sensors_health &
enum_value(STS::GEOFENCE)) ?
"Ok" :
"Fail");
244 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::AHRS))
245 stat.
add(
"AHRS subsystem health", (last_st.onboard_control_sensors_health &
enum_value(STS::AHRS)) ?
"Ok" :
"Fail");
246 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::TERRAIN))
247 stat.
add(
"Terrain subsystem health", (last_st.onboard_control_sensors_health &
enum_value(STS::TERRAIN)) ?
"Ok" :
"Fail");
248 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::REVERSE_MOTOR))
249 stat.
add(
"Motors are reversed", (last_st.onboard_control_sensors_health &
enum_value(STS::REVERSE_MOTOR)) ?
"Ok" :
"Fail");
250 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::LOGGING))
251 stat.
add(
"Logging", (last_st.onboard_control_sensors_health &
enum_value(STS::LOGGING)) ?
"Ok" :
"Fail");
252 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::BATTERY))
253 stat.
add(
"Battery", (last_st.onboard_control_sensors_health &
enum_value(STS::BATTERY)) ?
"Ok" :
"Fail");
254 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::PROXIMITY))
255 stat.
add(
"Proximity", (last_st.onboard_control_sensors_health &
enum_value(STS::PROXIMITY)) ?
"Ok" :
"Fail");
256 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::SATCOM))
257 stat.
add(
"Satellite Communication", (last_st.onboard_control_sensors_health &
enum_value(STS::SATCOM)) ?
"Ok" :
"Fail");
258 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::PREARM_CHECK))
259 stat.
add(
"pre-arm check status. Always healthy when armed", (last_st.onboard_control_sensors_health &
enum_value(STS::PREARM_CHECK)) ?
"Ok" :
"Fail");
260 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::OBSTACLE_AVOIDANCE))
261 stat.
add(
"Avoidance/collision prevention", (last_st.onboard_control_sensors_health &
enum_value(STS::OBSTACLE_AVOIDANCE)) ?
"Ok" :
"Fail");
262 if (last_st.onboard_control_sensors_enabled &
enum_value(STS::PROPULSION))
263 stat.
add(
"propulsion (actuator, esc, motor or propellor)", (last_st.onboard_control_sensors_health &
enum_value(STS::PROPULSION)) ?
"Ok" :
"Fail");
266 stat.
addf(
"CPU Load (%)",
"%.1f", last_st.load / 10.0);
267 stat.
addf(
"Drop rate (%)",
"%.1f", last_st.drop_rate_comm / 10.0);
268 stat.
addf(
"Errors comm",
"%d", last_st.errors_comm);
269 stat.
addf(
"Errors count #1",
"%d", last_st.errors_count1);
270 stat.
addf(
"Errors count #2",
"%d", last_st.errors_count2);
271 stat.
addf(
"Errors count #3",
"%d", last_st.errors_count3);
272 stat.
addf(
"Errors count #4",
"%d", last_st.errors_count4);
296 std::lock_guard<std::mutex> lock(
mutex);
300 void set(
float volt,
float curr,
float rem) {
301 std::lock_guard<std::mutex> lock(
mutex);
309 std::lock_guard<std::mutex> lock(
mutex);
313 else if (voltage < min_voltage)
314 stat.
summary(1,
"Low voltage");
318 stat.
addf(
"Voltage",
"%.2f", voltage);
319 stat.
addf(
"Current",
"%.1f", current);
320 stat.
addf(
"Remaining",
"%.1f", remaining * 100);
344 void set(uint16_t
f, uint16_t
b) {
351 ssize_t freemem_ = freemem;
352 uint16_t brkval_ = brkval;
356 else if (freemem < 200)
361 stat.
addf(
"Free memory (B)",
"%zd", freemem_);
362 stat.
addf(
"Heap top",
"0x%04X", brkval_);
384 void set(uint16_t v, uint8_t
e) {
385 std::lock_guard<std::mutex> lock(
mutex);
392 std::lock_guard<std::mutex> lock(
mutex);
397 stat.
summary(1,
"Low voltage");
398 else if (i2cerr != i2cerr_last) {
399 i2cerr_last = i2cerr;
400 stat.
summary(1,
"New I2C error");
405 stat.
addf(
"Core voltage",
"%f", vcc);
406 stat.
addf(
"I2C errors",
"%zu", i2cerr);
427 hb_diag(
"Heartbeat", 10),
428 mem_diag(
"APM Memory"),
429 hwst_diag(
"APM Hardware"),
431 batt_diag(
"Battery"),
432 version_retries(RETRIES_COUNT),
434 has_battery_status(false),
435 battery_voltage(0.0),
436 conn_heartbeat_mav_type(
MAV_TYPE::ONBOARD_CONTROLLER)
441 PluginBase::initialize(uas_);
445 double conn_timeout_d;
446 double conn_heartbeat_d;
448 std::string conn_heartbeat_mav_type_str;
450 nh.param(
"conn/timeout", conn_timeout_d, 10.0);
451 nh.param(
"sys/min_voltage", min_voltage, 10.0);
452 nh.param(
"sys/disable_diag", disable_diag,
false);
455 if (nh.getParam(
"conn/heartbeat_rate", conn_heartbeat_d) && conn_heartbeat_d != 0.0) {
460 if (nh.getParam(
"conn/heartbeat_mav_type", conn_heartbeat_mav_type_str)) {
470 batt_diag.set_min_voltage(min_voltage);
475 timeout_timer = nh.createTimer(
ros::Duration(conn_timeout_d),
479 if (!conn_heartbeat.
isZero()) {
480 heartbeat_timer = nh.createTimer(conn_heartbeat,
488 autopilot_version_timer.stop();
490 state_pub = nh.advertise<mavros_msgs::State>(
"state", 10,
true);
491 extended_state_pub = nh.advertise<mavros_msgs::ExtendedState>(
"extended_state", 10);
492 batt_pub = nh.advertise<
BatteryMsg>(
"battery", 10);
493 estimator_status_pub = nh.advertise<mavros_msgs::EstimatorStatus>(
"estimator_status", 10);
494 statustext_pub = nh.advertise<mavros_msgs::StatusText>(
"statustext/recv", 10);
502 publish_disconnection();
503 enable_connection_cb();
544 static constexpr
int RETRIES_COUNT = 6;
550 using M_VehicleInfo = std::unordered_map<uint16_t, mavros_msgs::VehicleInfo>;
557 return sysid << 8 | compid;
562 auto key = get_vehicle_key(sysid, compid);
563 M_VehicleInfo::iterator ret = vehicles.find(key);
565 if (ret == vehicles.end()) {
567 mavros_msgs::VehicleInfo v;
570 v.available_info = 0;
572 auto res = vehicles.emplace(key, v);
587 using mavlink::common::MAV_SEVERITY;
629 memcpy(&b, array.data(),
sizeof(uint64_t));
638 std::snprintf(prefix,
sizeof(prefix),
"VER: %d.%d", sysid, compid);
640 ROS_INFO_NAMED(
"sys",
"%s: Capabilities 0x%016llx", prefix, (
long long int)apv.capabilities);
643 apv.flight_sw_version,
644 custom_version_to_hex_string(apv.flight_custom_version).c_str());
647 apv.middleware_sw_version,
648 custom_version_to_hex_string(apv.middleware_custom_version).c_str());
652 custom_version_to_hex_string(apv.os_custom_version).c_str());
653 ROS_INFO_NAMED(
"sys",
"%s: Board hardware: %08x", prefix, apv.board_version);
654 ROS_INFO_NAMED(
"sys",
"%s: VID/PID: %04x:%04x", prefix, apv.vendor_id, apv.product_id);
655 ROS_INFO_NAMED(
"sys",
"%s: UID: %016llx", prefix, (
long long int)apv.uid);
661 std::snprintf(prefix,
sizeof(prefix),
"VER: %d.%d", sysid, compid);
665 ROS_INFO_NAMED(
"sys",
"%s: Capabilities 0x%016llx", prefix, (
long long int)apv.capabilities);
668 apv.flight_sw_version,
669 8, apv.flight_custom_version.data());
672 apv.middleware_sw_version,
673 8, apv.middleware_custom_version.data());
677 8, apv.os_custom_version.data());
678 ROS_INFO_NAMED(
"sys",
"%s: Board hardware: %08x", prefix, apv.board_version);
679 ROS_INFO_NAMED(
"sys",
"%s: VID/PID: %04x:%04x", prefix, apv.vendor_id, apv.product_id);
680 ROS_INFO_NAMED(
"sys",
"%s: UID: %016llx", prefix, (
long long int)apv.uid);
684 auto state_msg = boost::make_shared<mavros_msgs::State>();
686 state_msg->connected =
false;
687 state_msg->armed =
false;
688 state_msg->guided =
false;
689 state_msg->mode =
"";
690 state_msg->system_status =
enum_value(MAV_STATE::UNINIT);
697 void handle_heartbeat(
const mavlink::mavlink_message_t *msg, mavlink::minimal::msg::HEARTBEAT &hb)
699 using mavlink::minimal::MAV_MODE_FLAG;
702 auto it = find_or_create_vehicle_info(msg->sysid, msg->compid);
704 auto vehicle_mode = m_uas->str_mode_v10(hb.base_mode, hb.custom_mode);
708 it->second.header.stamp = stamp;
709 it->second.available_info |= mavros_msgs::VehicleInfo::HAVE_INFO_HEARTBEAT;
710 it->second.autopilot = hb.autopilot;
711 it->second.type = hb.type;
712 it->second.system_status = hb.system_status;
713 it->second.base_mode = hb.base_mode;
714 it->second.custom_mode = hb.custom_mode;
715 it->second.mode = vehicle_mode;
717 if (!(hb.base_mode &
enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED))) {
718 it->second.mode_id = hb.base_mode;
720 it->second.mode_id = hb.custom_mode;
724 if (!m_uas->is_my_target(msg->sysid, msg->compid)) {
725 ROS_DEBUG_NAMED(
"sys",
"HEARTBEAT from [%d, %d] dropped.", msg->sysid, msg->compid);
730 m_uas->update_heartbeat(hb.type, hb.autopilot, hb.base_mode);
731 m_uas->update_connection_status(
true);
732 timeout_timer.
stop();
733 timeout_timer.
start();
736 auto state_msg = boost::make_shared<mavros_msgs::State>();
737 state_msg->header.stamp = stamp;
738 state_msg->connected =
true;
739 state_msg->armed = !!(hb.base_mode &
enum_value(MAV_MODE_FLAG::SAFETY_ARMED));
740 state_msg->guided = !!(hb.base_mode &
enum_value(MAV_MODE_FLAG::GUIDED_ENABLED));
741 state_msg->manual_input = !!(hb.base_mode &
enum_value(MAV_MODE_FLAG::MANUAL_INPUT_ENABLED));
742 state_msg->mode = vehicle_mode;
743 state_msg->system_status = hb.system_status;
746 hb_diag.
tick(hb.type, hb.autopilot, state_msg->mode, hb.system_status);
751 auto state_msg = boost::make_shared<mavros_msgs::ExtendedState>();
753 state_msg->vtol_state = state.vtol_state;
754 state_msg->landed_state = state.landed_state;
756 extended_state_pub.
publish(state_msg);
759 void handle_sys_status(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::SYS_STATUS &stat)
761 float volt = stat.voltage_battery / 1000.0f;
762 float curr = stat.current_battery / 100.0f;
763 float rem = stat.battery_remaining / 100.0f;
765 battery_voltage = volt;
767 batt_diag.
set(volt, curr, rem);
769 if (has_battery_status)
772 auto batt_msg = boost::make_shared<BatteryMsg>();
775 #ifdef HAVE_SENSOR_MSGS_BATTERYSTATE_MSG 776 batt_msg->voltage = volt;
777 batt_msg->current = -curr;
778 batt_msg->charge = NAN;
779 batt_msg->capacity = NAN;
780 batt_msg->design_capacity = NAN;
781 batt_msg->percentage = rem;
782 batt_msg->power_supply_status = BatteryMsg::POWER_SUPPLY_STATUS_DISCHARGING;
783 batt_msg->power_supply_health = BatteryMsg::POWER_SUPPLY_HEALTH_UNKNOWN;
784 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_UNKNOWN;
785 batt_msg->present =
true;
786 batt_msg->cell_voltage.clear();
787 batt_msg->location =
"";
788 batt_msg->serial_number =
"";
789 #else // mavros_msgs::BatteryStatus 790 batt_msg->voltage = volt;
791 batt_msg->current = curr;
792 batt_msg->remaining = rem;
798 void handle_statustext(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::STATUSTEXT &textm)
801 process_statustext_normal(textm.severity, text);
803 auto st_msg = boost::make_shared<mavros_msgs::StatusText>();
805 st_msg->severity = textm.severity;
807 statustext_pub.
publish(st_msg);
810 void handle_meminfo(
const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::MEMINFO &mem)
812 mem_diag.
set(mem.freemem, mem.brkval);
815 void handle_hwstatus(
const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::HWSTATUS &hwst)
817 hwst_diag.
set(hwst.Vcc, hwst.I2Cerr);
823 if (m_uas->is_my_target(msg->sysid, msg->compid)) {
824 autopilot_version_timer.
stop();
825 m_uas->update_capabilities(
true, apv.capabilities);
829 if (m_uas->is_ardupilotmega())
830 process_autopilot_version_apm_quirk(apv, msg->sysid, msg->compid);
832 process_autopilot_version_normal(apv, msg->sysid, msg->compid);
835 auto it = find_or_create_vehicle_info(msg->sysid, msg->compid);
839 it->second.available_info |= mavros_msgs::VehicleInfo::HAVE_INFO_AUTOPILOT_VERSION;
840 it->second.capabilities = apv.capabilities;
841 it->second.flight_sw_version = apv.flight_sw_version;
842 it->second.middleware_sw_version = apv.middleware_sw_version;
843 it->second.os_sw_version = apv.os_sw_version;
844 it->second.board_version = apv.board_version;
845 it->second.flight_custom_version = custom_version_to_hex_string(apv.flight_custom_version);
846 it->second.vendor_id = apv.vendor_id;
847 it->second.product_id = apv.product_id;
848 it->second.uid = apv.uid;
854 #ifdef HAVE_SENSOR_MSGS_BATTERYSTATE_MSG 855 using BT = mavlink::common::MAV_BATTERY_TYPE;
857 has_battery_status =
true;
859 auto batt_msg = boost::make_shared<BatteryMsg>();
862 batt_msg->voltage = battery_voltage;
863 batt_msg->current = -(bs.current_battery / 100.0f);
864 batt_msg->charge = NAN;
865 batt_msg->capacity = NAN;
866 batt_msg->design_capacity = NAN;
867 batt_msg->percentage = bs.battery_remaining / 100.0f;
868 batt_msg->power_supply_status = BatteryMsg::POWER_SUPPLY_STATUS_DISCHARGING;
869 batt_msg->power_supply_health = BatteryMsg::POWER_SUPPLY_HEALTH_UNKNOWN;
886 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_LIPO;
889 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_LIFE;
892 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_LION;
895 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_NIMH;
899 batt_msg->power_supply_technology = BatteryMsg::POWER_SUPPLY_TECHNOLOGY_UNKNOWN;
904 batt_msg->present =
true;
906 batt_msg->cell_voltage.clear();
907 batt_msg->cell_voltage.reserve(bs.voltages.size());
908 for (
auto v : bs.voltages) {
912 batt_msg->cell_voltage.push_back(v / 1000.0
f);
916 batt_msg->serial_number =
"";
924 using ESF = mavlink::common::ESTIMATOR_STATUS_FLAGS;
926 auto est_status_msg = boost::make_shared<mavros_msgs::EstimatorStatus>();
949 est_status_msg->attitude_status_flag = !!(status.flags &
enum_value(ESF::ATTITUDE));
950 est_status_msg->velocity_horiz_status_flag = !!(status.flags &
enum_value(ESF::VELOCITY_HORIZ));
951 est_status_msg->velocity_vert_status_flag = !!(status.flags &
enum_value(ESF::VELOCITY_VERT));
952 est_status_msg->pos_horiz_rel_status_flag = !!(status.flags &
enum_value(ESF::POS_HORIZ_REL));
953 est_status_msg->pos_horiz_abs_status_flag = !!(status.flags &
enum_value(ESF::POS_HORIZ_ABS));
954 est_status_msg->pos_vert_abs_status_flag = !!(status.flags &
enum_value(ESF::POS_VERT_ABS));
955 est_status_msg->pos_vert_agl_status_flag = !!(status.flags &
enum_value(ESF::POS_VERT_AGL));
956 est_status_msg->const_pos_mode_status_flag = !!(status.flags &
enum_value(ESF::CONST_POS_MODE));
957 est_status_msg->pred_pos_horiz_rel_status_flag = !!(status.flags &
enum_value(ESF::PRED_POS_HORIZ_REL));
958 est_status_msg->pred_pos_horiz_abs_status_flag = !!(status.flags &
enum_value(ESF::PRED_POS_HORIZ_ABS));
959 est_status_msg->gps_glitch_status_flag = !!(status.flags &
enum_value(ESF::GPS_GLITCH));
960 est_status_msg->accel_error_status_flag = !!(status.flags &
enum_value(ESF::ACCEL_ERROR));
963 estimator_status_pub.
publish(est_status_msg);
970 m_uas->update_connection_status(
false);
975 using mavlink::common::MAV_MODE;
977 mavlink::minimal::msg::HEARTBEAT hb {};
979 hb.type =
enum_value(conn_heartbeat_mav_type);
980 hb.autopilot =
enum_value(MAV_AUTOPILOT::INVALID);
981 hb.base_mode =
enum_value(MAV_MODE::MANUAL_ARMED);
983 hb.system_status =
enum_value(MAV_STATE::ACTIVE);
985 UAS_FCU(m_uas)->send_message_ignore_drop(hb);
990 using mavlink::common::MAV_CMD;
995 bool do_broadcast = version_retries > RETRIES_COUNT / 2;
998 auto client = nh.
serviceClient<mavros_msgs::CommandLong>(
"cmd/command");
1000 mavros_msgs::CommandLong
cmd{};
1002 cmd.request.broadcast = do_broadcast;
1003 cmd.request.command =
enum_value(MAV_CMD::REQUEST_AUTOPILOT_CAPABILITIES);
1004 cmd.request.confirmation =
false;
1005 cmd.request.param1 = 1.0;
1008 (do_broadcast) ?
"broadcast" :
"unicast");
1009 ret = client.call(
cmd);
1017 if (version_retries > 0) {
1020 "VER: %s request timeout, retries left %d",
1021 (do_broadcast) ?
"broadcast" :
"unicast",
1025 m_uas->update_capabilities(
false);
1026 autopilot_version_timer.
stop();
1027 ROS_WARN_NAMED(
"sys",
"VER: your FCU don't support AUTOPILOT_VERSION, " 1028 "switched to default capabilities");
1034 has_battery_status =
false;
1037 version_retries = RETRIES_COUNT;
1039 autopilot_version_timer.
start();
1041 autopilot_version_timer.
stop();
1044 if (connected && disable_diag && m_uas->is_ardupilotmega()) {
1055 publish_disconnection();
1065 mavlink::common::msg::STATUSTEXT statustext {};
1066 statustext.severity = req->severity;
1070 "Status text too long: truncating...");
1073 UAS_FCU(m_uas)->send_message_ignore_drop(statustext);
1079 mavros_msgs::StreamRate::Response &res)
1081 mavlink::common::msg::REQUEST_DATA_STREAM rq = {};
1083 rq.target_system = m_uas->get_tgt_system();
1084 rq.target_component = m_uas->get_tgt_component();
1085 rq.req_stream_id = req.stream_id;
1086 rq.req_message_rate = req.message_rate;
1087 rq.start_stop = (req.on_off) ? 1 : 0;
1089 UAS_FCU(m_uas)->send_message_ignore_drop(rq);
1094 mavros_msgs::SetMode::Response &res)
1096 using mavlink::minimal::MAV_MODE_FLAG;
1098 uint8_t base_mode = req.base_mode;
1099 uint32_t custom_mode = 0;
1101 if (req.custom_mode !=
"") {
1102 if (!m_uas->cmode_from_str(req.custom_mode, custom_mode)) {
1103 res.mode_sent =
false;
1112 base_mode |= (m_uas->get_armed()) ?
enum_value(MAV_MODE_FLAG::SAFETY_ARMED) : 0;
1113 base_mode |= (m_uas->get_hil_state()) ?
enum_value(MAV_MODE_FLAG::HIL_ENABLED) : 0;
1114 base_mode |=
enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED);
1117 mavlink::common::msg::SET_MODE sm = {};
1118 sm.target_system = m_uas->get_tgt_system();
1119 sm.base_mode = base_mode;
1120 sm.custom_mode = custom_mode;
1122 UAS_FCU(m_uas)->send_message_ignore_drop(sm);
1123 res.mode_sent =
true;
1128 mavros_msgs::VehicleInfoGet::Response &res)
1132 for (
const auto &got : vehicles) {
1133 res.vehicles.emplace_back(got.second);
1140 uint8_t req_sysid = req.sysid;
1141 uint8_t req_compid = req.compid;
1143 if (req.sysid == 0 && req.compid == 0) {
1145 req_sysid = m_uas->get_tgt_system();
1146 req_compid = m_uas->get_tgt_component();
1149 uint16_t key = get_vehicle_key(req_sysid, req_compid);
1150 auto it = vehicles.find(key);
1152 if (it == vehicles.end()) {
1154 res.success =
false;
1158 res.vehicles.emplace_back(it->second);
1164 mavros_msgs::MessageInterval::Response &res)
1166 using mavlink::common::MAV_CMD;
1169 auto client = nh.
serviceClient<mavros_msgs::CommandLong>(
"cmd/command");
1173 if (req.message_rate < 0) {
1174 interval_us = -1.0f;
1175 }
else if (req.message_rate == 0) {
1178 interval_us = 1000000.0f / req.message_rate;
1181 mavros_msgs::CommandLong
cmd{};
1183 cmd.request.broadcast =
false;
1184 cmd.request.command =
enum_value(MAV_CMD::SET_MESSAGE_INTERVAL);
1185 cmd.request.confirmation =
false;
1186 cmd.request.param1 = req.message_id;
1187 cmd.request.param2 = interval_us;
1189 ROS_DEBUG_NAMED(
"sys",
"SetMessageInterval: Request msgid %u at %f hz",
1190 req.message_id, req.message_rate);
1191 res.success = client.call(
cmd);
1197 ROS_ERROR_COND_NAMED(!res.success,
"sys",
"SetMessageInterval: command plugin service call failed!");
MemInfo(const std::string &name)
MAVROS Plugin base class.
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
#define ROS_ERROR_COND_NAMED(cond, name,...)
#define ROS_WARN_COND_NAMED(cond, name,...)
MAV_TYPE conn_heartbeat_mav_type
std::shared_ptr< MAVConnInterface const > ConstPtr
ros::Publisher statustext_pub
bool set_mode_cb(mavros_msgs::SetMode::Request &req, mavros_msgs::SetMode::Response &res)
#define ROS_INFO_NAMED(name,...)
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
std::atomic< uint16_t > brkval
#define ROS_DEBUG_STREAM_NAMED(name, args)
std::string format(const std::string &fmt, Args...args)
void heartbeat_cb(const ros::TimerEvent &event)
std::vector< ros::Time > times_
mavros_msgs::BatteryStatus BatteryMsg
void publish(const boost::shared_ptr< M > &message) const
bool vehicle_info_get_cb(mavros_msgs::VehicleInfoGet::Request &req, mavros_msgs::VehicleInfoGet::Response &res)
#define ROS_ERROR_STREAM_NAMED(name, args)
#define ROS_WARN_NAMED(name,...)
System status diagnostic updater.
const size_t window_size_
void handle_heartbeat(const mavlink::mavlink_message_t *msg, mavlink::minimal::msg::HEARTBEAT &hb)
ros::Publisher estimator_status_pub
void summary(unsigned char lvl, const std::string s)
std::unordered_map< uint16_t, mavros_msgs::VehicleInfo > M_VehicleInfo
void statustext_cb(const mavros_msgs::StatusText::ConstPtr &req)
ros::Subscriber statustext_sub
void process_autopilot_version_apm_quirk(mavlink::common::msg::AUTOPILOT_VERSION &apv, uint8_t sysid, uint8_t compid)
void handle_autopilot_version(const mavlink::mavlink_message_t *msg, mavlink::common::msg::AUTOPILOT_VERSION &apv)
void handle_sys_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::SYS_STATUS &stat)
void tick(uint8_t type_, uint8_t autopilot_, std::string &mode_, uint8_t system_status_)
void set(float volt, float curr, float rem)
void initialize(UAS &uas_) override
Plugin initializer.
void handle_battery_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::BATTERY_STATUS &bs)
ros::Timer autopilot_version_timer
#define UAS_DIAG(uasobjptr)
helper accessor to diagnostic updater
#define ROS_INFO_STREAM_NAMED(name, args)
void process_autopilot_version_normal(mavlink::common::msg::AUTOPILOT_VERSION &apv, uint8_t sysid, uint8_t compid)
void timeout_cb(const ros::TimerEvent &event)
void addf(const std::string &key, const char *format,...)
Memory usage diag (APM-only)
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
SystemStatusDiag sys_diag
mavlink::common::msg::SYS_STATUS last_st
bool set_message_interval_cb(mavros_msgs::MessageInterval::Request &req, mavros_msgs::MessageInterval::Response &res)
bool set_rate_cb(mavros_msgs::StreamRate::Request &req, mavros_msgs::StreamRate::Response &res)
uint16_t get_vehicle_key(uint8_t sysid, uint8_t compid)
ros::ServiceServer rate_srv
#define ROS_DEBUG_NAMED(name,...)
void handle_extended_sys_state(const mavlink::mavlink_message_t *msg, mavlink::common::msg::EXTENDED_SYS_STATE &state)
ros::ServiceServer vehicle_info_get_srv
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
void handle_hwstatus(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::HWSTATUS &hwst)
void handle_statustext(const mavlink::mavlink_message_t *msg, mavlink::common::msg::STATUSTEXT &textm)
mavlink::minimal::MAV_TYPE mav_type_from_str(const std::string &mav_type)
Retreive MAV_TYPE from name.
ros::Timer heartbeat_timer
void handle_meminfo(const mavlink::mavlink_message_t *msg, mavlink::ardupilotmega::msg::MEMINFO &mem)
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
void set_string_z(std::array< char, _N > &a, const std::string &s)
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
std::atomic< ssize_t > freemem
HeartbeatStatus(const std::string &name, size_t win_size)
std::string to_string(timesync_mode e)
SystemStatusDiag(const std::string &name)
ros::ServiceServer mode_srv
void publish_disconnection()
HwStatus(const std::string &name)
Battery diagnostic updater.
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
BatteryStatusDiag batt_diag
ros::Publisher extended_state_pub
void autopilot_version_cb(const ros::TimerEvent &event)
const std::string & getName()
DiagnosticTask(const std::string name)
BatteryStatusDiag(const std::string &name)
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
#define ROS_ERROR_NAMED(name,...)
ros::ServiceServer message_interval_srv
void connection_cb(bool connected) override
M_VehicleInfo::iterator find_or_create_vehicle_info(uint8_t sysid, uint8_t compid)
static std::string custom_version_to_hex_string(std::array< uint8_t, 8 > &array)
void add(const std::string &key, const T &val)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void set(uint16_t v, uint8_t e)
void set(uint16_t f, uint16_t b)
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
std::string to_string(const std::array< char, _N > &a)
Hardware status (APM-only)
std::vector< int > seq_nums_
void set(mavlink::common::msg::SYS_STATUS &st)
void process_statustext_normal(uint8_t severity, std::string &text)
constexpr std::underlying_type< _T >::type enum_value(_T e)
std::recursive_mutex mutex
#define ROS_WARN_STREAM_NAMED(name, args)
void set_min_voltage(float volt)
void handle_estimator_status(const mavlink::mavlink_message_t *msg, mavlink::common::msg::ESTIMATOR_STATUS &status)