Browse Source

AC_PosControl: log PSC data in metres in place of centimetres

master
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
eb1fc3107c
  1. 33
      libraries/AC_AttitudeControl/AC_PosControl.cpp

33
libraries/AC_AttitudeControl/AC_PosControl.cpp

@ -838,21 +838,24 @@ void AC_PosControl::write_log()
float accel_x, accel_y; float accel_x, accel_y;
lean_angles_to_accel(accel_x, accel_y); lean_angles_to_accel(accel_x, accel_y);
AP::logger().Write("PSC", "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY", AP::logger().Write("PSC",
"smmmmnnnnoooo", "FBBBBBBBBBBBB", "Qffffffffffff", "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY",
AP_HAL::micros64(), "smmmmnnnnoooo",
(double)pos_target.x, "F000000000000",
(double)pos_target.y, "Qffffffffffff",
(double)position.x, AP_HAL::micros64(),
(double)position.y, double(pos_target.x * 0.01f),
(double)vel_target.x, double(pos_target.y * 0.01f),
(double)vel_target.y, double(position.x * 0.01f),
(double)velocity.x, double(position.y * 0.01f),
(double)velocity.y, double(vel_target.x * 0.01f),
(double)accel_target.x, double(vel_target.y * 0.01f),
(double)accel_target.y, double(velocity.x * 0.01f),
(double)accel_x, double(velocity.y * 0.01f),
(double)accel_y); double(accel_target.x * 0.01f),
double(accel_target.y * 0.01f),
double(accel_x * 0.01f),
double(accel_y * 0.01f));
} }
/// init_vel_controller_xyz - initialise the velocity controller - should be called once before the caller attempts to use the controller /// init_vel_controller_xyz - initialise the velocity controller - should be called once before the caller attempts to use the controller

Loading…
Cancel
Save