mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Plane: quadplane: double log QPOS state change
This commit is contained in:
parent
4631392f31
commit
9f32204f15
@ -2162,6 +2162,7 @@ void QuadPlane::log_QPOS(void)
|
|||||||
*/
|
*/
|
||||||
void QuadPlane::PosControlState::set_state(enum position_control_state s)
|
void QuadPlane::PosControlState::set_state(enum position_control_state s)
|
||||||
{
|
{
|
||||||
|
const uint32_t now = AP_HAL::millis();
|
||||||
if (state != s) {
|
if (state != s) {
|
||||||
auto &qp = plane.quadplane;
|
auto &qp = plane.quadplane;
|
||||||
pilot_correction_done = false;
|
pilot_correction_done = false;
|
||||||
@ -2183,14 +2184,17 @@ void QuadPlane::PosControlState::set_state(enum position_control_state s)
|
|||||||
Vector2f rpos;
|
Vector2f rpos;
|
||||||
last_pos_reset_ms = plane.ahrs.getLastPosNorthEastReset(rpos);
|
last_pos_reset_ms = plane.ahrs.getLastPosNorthEastReset(rpos);
|
||||||
}
|
}
|
||||||
|
// double log to capture the state change
|
||||||
qp.log_QPOS();
|
qp.log_QPOS();
|
||||||
|
state = s;
|
||||||
|
qp.log_QPOS();
|
||||||
|
last_log_ms = now;
|
||||||
}
|
}
|
||||||
state = s;
|
last_state_change_ms = now;
|
||||||
last_state_change_ms = AP_HAL::millis();
|
|
||||||
|
|
||||||
// we consider setting the state to be equivalent to running to
|
// we consider setting the state to be equivalent to running to
|
||||||
// prevent code from overriding the state as stale
|
// prevent code from overriding the state as stale
|
||||||
last_run_ms = last_state_change_ms;
|
last_run_ms = now;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user