Copter: set accel and gyro disabled during calibration
This commit is contained in:
parent
f9c6e35d19
commit
72d1113501
@ -245,7 +245,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (!ap.initialised) {
|
if (!ap.initialised || ins.calibrating()) {
|
||||||
// while initialising the gyros and accels are not enabled
|
// 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_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);
|
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
||||||
|
Loading…
Reference in New Issue
Block a user