mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Plane: added SENSOR_RC_RECEIVER reporting in SYS_STATUS
This commit is contained in:
parent
e0810c2e54
commit
017ebc440b
@ -3,7 +3,7 @@
|
||||
#include "Plane.h"
|
||||
|
||||
// default sensors are present and healthy: gyro, accelerometer, barometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control
|
||||
#define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS)
|
||||
#define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS | MAV_SYS_STATUS_SENSOR_RC_RECEIVER)
|
||||
|
||||
void Plane::send_heartbeat(mavlink_channel_t chan)
|
||||
{
|
||||
@ -252,6 +252,12 @@ void Plane::send_extended_status1(mavlink_channel_t chan)
|
||||
}
|
||||
#endif
|
||||
|
||||
if (millis() - failsafe.last_valid_rc_ms < 200) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||
} else {
|
||||
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||
}
|
||||
|
||||
int16_t battery_current = -1;
|
||||
int8_t battery_remaining = -1;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user