mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: set gyros disabled when calibrating
This commit is contained in:
parent
47e9409d00
commit
d9950ea07f
@ -182,6 +182,12 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
||||
battery_current = battery.current_amps() * 100;
|
||||
}
|
||||
|
||||
if (AP_Notify::flags.initialising) {
|
||||
// while initialising the gyros and accels are not enabled
|
||||
control_sensors_enabled &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
||||
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
||||
}
|
||||
|
||||
mavlink_msg_sys_status_send(
|
||||
chan,
|
||||
control_sensors_present,
|
||||
|
Loading…
Reference in New Issue
Block a user