Multicopter lock if primary gyro fails

Hello guys,

Problem:
If the primary gyro fails the multicopter attitude controller will not fall-back on secondary gyro but instead it stops functioning. If for example, the primary gyro is an external IMU connected over a cable to PX4, this failure can not be excluded.

Cause:
In the main loop in the method MulticopterAttitudeControl::run() line 838 we have the code:

while (!should_exit()) {

	poll_fds.fd = _sensor_gyro_sub[_selected_gyro];

	/* wait for up to 100ms for data */
	int pret = px4_poll(&poll_fds, 1, 100);

	/* timed out - periodic check for should_exit() */
	if (pret == 0) {
		continue;
           }

If the selected gyro timesout, the main loop will just wait indefinitely for it or for module exit. This can have “severely unpleasant” effects if happens in flight.

Proposed solution:
Since the sensor modules falls-back on the secondary gyro, we can just update the _selected_gyro in case of time-out and then the controller can keep flying. It is enough to change the if statement to:

	if (pret == 0) {
                    sensor_correction_poll();
		continue;
           }

in order to achieve an automatic switch to the next gyro selected by sensor module.

Question:
Do you see any problem with this mitigation?
Do you consider a good idea to also attempt it after a certain number of consecutive failure of poll function (i.e. the next if statement in the code)?

Thank you,
MTM

Oh, interesting! I think you’re right, this seems indeed wrong.

Would you mind making a pull request and to propose a solution? That would be great. If not, someone of the maintainers should definitely look into this.

@dagar do you agree?

MTM gave me a build with that solution to test (because I have an external IMU on my system).
While running the vehicle on a bench test (armed motors running), I disconnected the external IMU cable (which was primary) and the multicopter controller seemed unphased by the swap over to the internal IMU. Accel time outs were displayed an the motors seemed unaffected.

Reviewing the log, the EKF biases reset and the sensor combined took 50ms to get data from the backup imu.

Right, I would expect the sensors module to swap automatically and thus ekf2 to swap as well.

However, as @MTM showed, the mc_att_control attitude rate controller does not failover as it probably should.

Created pull request:
Failover in case of gyroscope failure #11516

Fixed in https://github.com/PX4/Firmware/pull/11516

Thank you for your help with the issue.

Great, thanks @MTM and @dagar!