diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index f34b2949e1..c23592df2e 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -39,19 +39,19 @@ const AP_Param::GroupInfo AP_MotorsCoax::var_info[] = { // @DisplayName: Reverse roll feedback // @Description: Ensure the feedback is negative // @Values: -1:Reversed,1:Normal - AP_GROUPINFO("ROLL_SV_REV", 40, AP_MotorsCoax, _rev_roll, AP_MOTORS_COAX_POSITIVE), + AP_GROUPINFO("ROLL_SV_REV", 40, AP_MotorsCoax, _roll_reverse, AP_MOTORS_COAX_POSITIVE), // @Param: PITCH_SV_REV // @DisplayName: Reverse roll feedback // @Description: Ensure the feedback is negative // @Values: -1:Reversed,1:Normal - AP_GROUPINFO("PITCH_SV_REV", 41, AP_MotorsCoax, _rev_pitch, AP_MOTORS_COAX_POSITIVE), + AP_GROUPINFO("PITCH_SV_REV", 41, AP_MotorsCoax, _pitch_reverse, AP_MOTORS_COAX_POSITIVE), // @Param: YAW_SV_REV // @DisplayName: Reverse roll feedback // @Description: Ensure the feedback is negative // @Values: -1:Reversed,1:Normal - AP_GROUPINFO("YAW_SV_REV", 42, AP_MotorsCoax, _rev_yaw, AP_MOTORS_COAX_POSITIVE), + AP_GROUPINFO("YAW_SV_REV", 42, AP_MotorsCoax, _yaw_reverse, AP_MOTORS_COAX_POSITIVE), // @Param: SV_SPEED // @DisplayName: Servo speed diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index 318506421b..67ed3ec441 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -60,9 +60,10 @@ protected: // output - sends commands to the motors void output_armed_stabilizing(); - AP_Int8 _rev_roll; // REV Roll feedback - AP_Int8 _rev_pitch; // REV pitch feedback - AP_Int8 _rev_yaw; // REV yaw feedback + // We shouldn't need roll, pitch, and yaw reversing with servo reversing. + AP_Int8 _roll_reverse; // Reverse roll output + AP_Int8 _pitch_reverse; // Reverse pitch output + AP_Int8 _yaw_reverse; // Reverse yaw output AP_Int16 _servo_speed; // servo speed RC_Channel& _servo1; RC_Channel& _servo2;