From a6ccc1dae2e8279662d904aaa47e2d1f96f35bdb Mon Sep 17 00:00:00 2001 From: Simon Hancock Date: Tue, 18 Jun 2024 10:01:20 +0100 Subject: [PATCH] ArduPlane: Add help for QPOS log message --- ArduPlane/quadplane.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 03f7f78fb9c5a..d2f74a5b55312 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -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(),