mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-08 10:50:19 +08:00
Commander: Fix level cal command
This commit is contained in:
@@ -3991,7 +3991,7 @@ void *commander_low_prio_loop(void *arg)
|
||||
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub, command_ack);
|
||||
calib_ret = do_gyro_calibration(&mavlink_log_pub);
|
||||
|
||||
} else if ((int)(cmd.param1) == 2 || (int)(cmd.param5) == 2 || (int)(cmd.param7) == 2) {
|
||||
} else if ((int)(cmd.param1) == 3 || (int)(cmd.param5) == 3 || (int)(cmd.param7) == 3) {
|
||||
/* temperature calibration: handled in events module */
|
||||
break;
|
||||
|
||||
|
||||
Reference in New Issue
Block a user