mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: always log QPOS when changing control state
This commit is contained in:
parent
9d0b7f8efe
commit
fd5faa866f
@ -2090,6 +2090,17 @@ void QuadPlane::poscontrol_init_approach(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
log the QPOS message
|
||||||
|
*/
|
||||||
|
void QuadPlane::log_QPOS(void)
|
||||||
|
{
|
||||||
|
AP::logger().WriteStreaming("QPOS", "TimeUS,State,Dist", "QBf",
|
||||||
|
AP_HAL::micros64(),
|
||||||
|
poscontrol.get_state(),
|
||||||
|
plane.auto_state.wp_distance);
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
change position control state
|
change position control state
|
||||||
*/
|
*/
|
||||||
@ -2116,6 +2127,7 @@ void QuadPlane::PosControlState::set_state(enum position_control_state s)
|
|||||||
// reset throttle descent control
|
// reset throttle descent control
|
||||||
qp.thr_ctrl_land = false;
|
qp.thr_ctrl_land = false;
|
||||||
}
|
}
|
||||||
|
qp.log_QPOS();
|
||||||
}
|
}
|
||||||
state = s;
|
state = s;
|
||||||
last_state_change_ms = AP_HAL::millis();
|
last_state_change_ms = AP_HAL::millis();
|
||||||
@ -2551,10 +2563,7 @@ void QuadPlane::vtol_position_controller(void)
|
|||||||
if (now_ms - poscontrol.last_log_ms >= 40) {
|
if (now_ms - poscontrol.last_log_ms >= 40) {
|
||||||
// log poscontrol at 25Hz
|
// log poscontrol at 25Hz
|
||||||
poscontrol.last_log_ms = now_ms;
|
poscontrol.last_log_ms = now_ms;
|
||||||
AP::logger().WriteStreaming("QPOS", "TimeUS,State,Dist", "QBf",
|
log_QPOS();
|
||||||
AP_HAL::micros64(),
|
|
||||||
poscontrol.get_state(),
|
|
||||||
plane.auto_state.wp_distance);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -249,6 +249,7 @@ private:
|
|||||||
bool should_relax(void);
|
bool should_relax(void);
|
||||||
void motors_output(bool run_rate_controller = true);
|
void motors_output(bool run_rate_controller = true);
|
||||||
void Log_Write_QControl_Tuning();
|
void Log_Write_QControl_Tuning();
|
||||||
|
void log_QPOS(void);
|
||||||
float landing_descent_rate_cms(float height_above_ground);
|
float landing_descent_rate_cms(float height_above_ground);
|
||||||
|
|
||||||
// setup correct aux channels for frame class
|
// setup correct aux channels for frame class
|
||||||
|
Loading…
Reference in New Issue
Block a user