Skip to content

Commit

Permalink
AR_PosControl: adjust for logging having moved into AC_AttitudeControl
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Feb 29, 2024
1 parent 6b9928c commit 5e75961
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions libraries/APM_Control/AR_PosControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -385,15 +385,16 @@ void AR_PosControl::write_log()
// convert position to required format
Vector2f pos_target_2d_cm = get_pos_target().tofloat() * 100.0;

AP::logger().Write_PSCN(pos_target_2d_cm.x, // position target
// reuse logging from AC_PosControl:
AC_PosControl::Write_PSCN(pos_target_2d_cm.x, // position target
curr_pos_NED.x * 100.0, // position
_vel_desired.x * 100.0, // desired velocity
_vel_target.x * 100.0, // target velocity
curr_vel_NED.x * 100.0, // velocity
_accel_desired.x * 100.0, // desired accel
_accel_target.x * 100.0, // target accel
curr_accel_NED.x); // accel
AP::logger().Write_PSCE(pos_target_2d_cm.y, // position target
AC_PosControl::Write_PSCE(pos_target_2d_cm.y, // position target
curr_pos_NED.y * 100.0, // position
_vel_desired.y * 100.0, // desired velocity
_vel_target.y * 100.0, // target velocity
Expand Down

0 comments on commit 5e75961

Please sign in to comment.