From 4521334b06d560424871bfeb0143ddb00ee851cd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 7 Jun 2021 21:03:06 +0900 Subject: [PATCH] Rover: THR logs X-axis accel X-axis is forward-back acceleration which is what users may need for speed and throttle tuning --- Rover/Log.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Rover/Log.cpp b/Rover/Log.cpp index 6e1941cff8..87347a4324 100644 --- a/Rover/Log.cpp +++ b/Rover/Log.cpp @@ -222,7 +222,7 @@ struct PACKED log_Throttle { float throttle_out; float desired_speed; float speed; - float accel_y; + float accel_x; }; // Write a throttle control packet @@ -238,7 +238,7 @@ void Rover::Log_Write_Throttle() throttle_out : g2.motors.get_throttle(), desired_speed : g2.attitude_control.get_desired_speed(), speed : speed, - accel_y : accel.y + accel_x : accel.x }; logger.WriteBlock(&pkt, sizeof(pkt)); } @@ -284,10 +284,10 @@ const LogStructure Rover::log_structure[] = { // @Field: ThrOut: Throttle Output // @Field: DesSpeed: Desired speed // @Field: Speed: Actual speed -// @Field: AccY: Vehicle's acceleration in Y-Axis +// @Field: AccX: Acceleration { LOG_THR_MSG, sizeof(log_Throttle), - "THR", "Qhffff", "TimeUS,ThrIn,ThrOut,DesSpeed,Speed,AccY", "s--nno", "F--000" }, + "THR", "Qhffff", "TimeUS,ThrIn,ThrOut,DesSpeed,Speed,AccX", "s--nno", "F--000" }, // @LoggerMessage: NTUN // @Description: Navigation Tuning information - e.g. vehicle destination