From 74d22594db96636e27051d5eefc55cd9484144b9 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 12 May 2021 13:31:07 +0900 Subject: [PATCH] Sub: integrate AC_PosControl::get_roll_cd rename --- ArduSub/motors.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index 89e6566a1a..679f8bdd7e 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -167,8 +167,8 @@ void Sub::translate_circle_nav_rp(float &lateral_out, float &forward_out) void Sub::translate_pos_control_rp(float &lateral_out, float &forward_out) { // get roll and pitch targets in centidegrees - int32_t lateral = pos_control.get_roll(); - int32_t forward = -pos_control.get_pitch(); // output is reversed + int32_t lateral = pos_control.get_roll_cd(); + int32_t forward = -pos_control.get_pitch_cd(); // output is reversed // constrain target forward/lateral values lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);