mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_AccelCal: make collect_sample responsible for state changes
Also only set the snoop if the step has changed
This commit is contained in:
parent
34649ef66a
commit
c07f377eb1
@ -45,8 +45,6 @@ void AP_AccelCal::update()
|
|||||||
}
|
}
|
||||||
if(_start_collect_sample) {
|
if(_start_collect_sample) {
|
||||||
collect_sample();
|
collect_sample();
|
||||||
_gcs->set_snoop(nullptr);
|
|
||||||
_start_collect_sample = false;
|
|
||||||
}
|
}
|
||||||
switch(_status) {
|
switch(_status) {
|
||||||
case ACCEL_CAL_NOT_STARTED:
|
case ACCEL_CAL_NOT_STARTED:
|
||||||
@ -96,9 +94,9 @@ void AP_AccelCal::update()
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
_printf("Place vehicle %s and press any key.", msg);
|
_printf("Place vehicle %s and press any key.", msg);
|
||||||
}
|
|
||||||
// setup snooping of packets so we can see the COMMAND_ACK
|
// setup snooping of packets so we can see the COMMAND_ACK
|
||||||
_gcs->set_snoop(_snoop);
|
_gcs->set_snoop(_snoop);
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case ACCEL_CAL_COLLECTING_SAMPLE:
|
case ACCEL_CAL_COLLECTING_SAMPLE:
|
||||||
@ -246,6 +244,7 @@ void AP_AccelCal::collect_sample()
|
|||||||
}
|
}
|
||||||
// setup snooping of packets so we can see the COMMAND_ACK
|
// setup snooping of packets so we can see the COMMAND_ACK
|
||||||
_gcs->set_snoop(nullptr);
|
_gcs->set_snoop(nullptr);
|
||||||
|
_start_collect_sample = false;
|
||||||
update_status();
|
update_status();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user