AP_MotorsSingle: 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 13:31:34 +09:00 committed by Randy Mackay
parent 4db73d86af
commit f53d6e95e8
2 changed files with 7 additions and 6 deletions

View File

@ -39,19 +39,19 @@ const AP_Param::GroupInfo AP_MotorsSingle::var_info[] = {
// @DisplayName: Reverse roll feedback
// @Description: Ensure the feedback is negative
// @Values: -1:Reversed,1:Normal
AP_GROUPINFO("ROLL_SV_REV", 40, AP_MotorsSingle, _rev_roll, AP_MOTORS_SING_POSITIVE),
AP_GROUPINFO("ROLL_SV_REV", 40, AP_MotorsSingle, _roll_reverse, AP_MOTORS_SING_POSITIVE),
// @Param: PITCH_SV_REV
// @DisplayName: Reverse pitch feedback
// @Description: Ensure the feedback is negative
// @Values: -1:Reversed,1:Normal
AP_GROUPINFO("PITCH_SV_REV", 41, AP_MotorsSingle, _rev_pitch, AP_MOTORS_SING_POSITIVE),
AP_GROUPINFO("PITCH_SV_REV", 41, AP_MotorsSingle, _pitch_reverse, AP_MOTORS_SING_POSITIVE),
// @Param: YAW_SV_REV
// @DisplayName: Reverse yaw feedback
// @Description: Ensure the feedback is negative
// @Values: -1:Reversed,1:Normal
AP_GROUPINFO("YAW_SV_REV", 42, AP_MotorsSingle, _rev_yaw, AP_MOTORS_SING_POSITIVE),
AP_GROUPINFO("YAW_SV_REV", 42, AP_MotorsSingle, _yaw_reverse, AP_MOTORS_SING_POSITIVE),
// @Param: SV_SPEED
// @DisplayName: Servo speed

View File

@ -61,9 +61,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;