AP_MotorsCoax: rename _rev_roll to _roll_reverse

Also rename _rev_pitch to _pitch_reverse and _rev_yaw to _yaw_reverse
This commit is contained in:
Leonard Hall 2016-01-20 12:49:43 +09:00 committed by Randy Mackay
parent 5cb44901ff
commit 7d6c6b5556
2 changed files with 7 additions and 6 deletions

View File

@ -39,19 +39,19 @@ const AP_Param::GroupInfo AP_MotorsCoax::var_info[] = {
// @DisplayName: Reverse roll feedback // @DisplayName: Reverse roll feedback
// @Description: Ensure the feedback is negative // @Description: Ensure the feedback is negative
// @Values: -1:Reversed,1:Normal // @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 // @Param: PITCH_SV_REV
// @DisplayName: Reverse roll feedback // @DisplayName: Reverse roll feedback
// @Description: Ensure the feedback is negative // @Description: Ensure the feedback is negative
// @Values: -1:Reversed,1:Normal // @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 // @Param: YAW_SV_REV
// @DisplayName: Reverse roll feedback // @DisplayName: Reverse roll feedback
// @Description: Ensure the feedback is negative // @Description: Ensure the feedback is negative
// @Values: -1:Reversed,1:Normal // @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 // @Param: SV_SPEED
// @DisplayName: Servo speed // @DisplayName: Servo speed

View File

@ -60,9 +60,10 @@ protected:
// output - sends commands to the motors // output - sends commands to the motors
void output_armed_stabilizing(); void output_armed_stabilizing();
AP_Int8 _rev_roll; // REV Roll feedback // We shouldn't need roll, pitch, and yaw reversing with servo reversing.
AP_Int8 _rev_pitch; // REV pitch feedback AP_Int8 _roll_reverse; // Reverse roll output
AP_Int8 _rev_yaw; // REV yaw feedback AP_Int8 _pitch_reverse; // Reverse pitch output
AP_Int8 _yaw_reverse; // Reverse yaw output
AP_Int16 _servo_speed; // servo speed AP_Int16 _servo_speed; // servo speed
RC_Channel& _servo1; RC_Channel& _servo1;
RC_Channel& _servo2; RC_Channel& _servo2;