mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
ArduPlane: Add help for QPOS log message
This commit is contained in:
parent
6aa662d5d0
commit
7d2000f3d5
@ -2218,6 +2218,16 @@ void QuadPlane::poscontrol_init_approach(void)
|
||||
*/
|
||||
void QuadPlane::log_QPOS(void)
|
||||
{
|
||||
// @LoggerMessage: QPOS
|
||||
// @Description: Quadplane position data
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: State: Position control state
|
||||
// @FieldValueEnum: State: QuadPlane::position_control_state
|
||||
// @Field: Dist: Distance to next waypoint
|
||||
// @Field: TSpd: Target speed
|
||||
// @Field: TAcc: Target acceleration
|
||||
// @Field: OShoot: True if landing point is overshot or heading off by more than 60 degrees
|
||||
|
||||
AP::logger().WriteStreaming("QPOS", "TimeUS,State,Dist,TSpd,TAcc,OShoot", "QBfffB",
|
||||
AP_HAL::micros64(),
|
||||
poscontrol.get_state(),
|
||||
|
Loading…
Reference in New Issue
Block a user