Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Motors: TradHeli - Fixed Directdrive Variable Pitch Feature #7281

Merged
merged 4 commits into from Jan 21, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
22 changes: 0 additions & 22 deletions libraries/AP_Motors/AP_MotorsHeli_Dual.cpp
Expand Up @@ -123,28 +123,6 @@ const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
// @Increment: 0.1
AP_GROUPINFO("YAW_SCALER", 12, AP_MotorsHeli_Dual, _yaw_scaler, 1.0f),

// @Param: RSC_PWM_MIN
// @DisplayName: RSC PWM output miniumum
// @Description: This sets the PWM output on RSC channel for maximum rotor speed
// @Range: 0 2000
// @User: Standard
AP_GROUPINFO("RSC_PWM_MIN", 13, AP_MotorsHeli_Dual, _rotor._pwm_min, 1000),

// @Param: RSC_PWM_MAX
// @DisplayName: RSC PWM output maxiumum
// @Description: This sets the PWM output on RSC channel for miniumum rotor speed
// @Range: 0 2000
// @User: Standard
AP_GROUPINFO("RSC_PWM_MAX", 14, AP_MotorsHeli_Dual, _rotor._pwm_max, 2000),

// @Param: RSC_PWM_REV
// @DisplayName: RSC PWM reversal
// @Description: This controls reversal of the RSC channel output
// @Values: -1:Reversed,1:Normal
// @User: Standard
AP_GROUPINFO("RSC_PWM_REV", 15, AP_MotorsHeli_Dual, _rotor._pwm_rev, 1),


// @Param: COL2_MIN
// @DisplayName: Collective Pitch Minimum for rear swashplate
// @Description: Lowest possible servo position in PWM microseconds for the rear swashplate
Expand Down
21 changes: 0 additions & 21 deletions libraries/AP_Motors/AP_MotorsHeli_Quad.cpp
Expand Up @@ -23,27 +23,6 @@ extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_MotorsHeli_Quad::var_info[] = {
AP_NESTEDGROUPINFO(AP_MotorsHeli, 0),

// @Param: RSC_PWM_MIN
// @DisplayName: RSC PWM output miniumum
// @Description: This sets the PWM output on RSC channel for maximum rotor speed
// @Range: 0 2000
// @User: Standard
AP_GROUPINFO("RSC_PWM_MIN", 1, AP_MotorsHeli_Quad, _rotor._pwm_min, 1000),

// @Param: RSC_PWM_MAX
// @DisplayName: RSC PWM output maxiumum
// @Description: This sets the PWM output on RSC channel for miniumum rotor speed
// @Range: 0 2000
// @User: Standard
AP_GROUPINFO("RSC_PWM_MAX", 2, AP_MotorsHeli_Quad, _rotor._pwm_max, 2000),

// @Param: RSC_PWM_REV
// @DisplayName: RSC PWM reversal
// @Description: This controls reversal of the RSC channel output
// @Values: -1:Reversed,1:Normal
// @User: Standard
AP_GROUPINFO("RSC_PWM_REV", 3, AP_MotorsHeli_Quad, _rotor._pwm_rev, 1),

AP_GROUPEND
};

Expand Down
9 changes: 1 addition & 8 deletions libraries/AP_Motors/AP_MotorsHeli_RSC.cpp
Expand Up @@ -187,13 +187,6 @@ void AP_MotorsHeli_RSC::write_rsc(float servo_out)
// ToDo: We should probably use RC_Channel_Aux to avoid this problem
return;
} else {
// calculate PWM value based on H_RSC_PWM_MIN, H_RSC_PWM_MAX and H_RSC_PWM_REV
uint16_t pwm = servo_out * (_pwm_max - _pwm_min);
if (_pwm_rev >= 0) {
pwm = _pwm_min + pwm;
} else {
pwm = _pwm_max - pwm;
}
SRV_Channels::set_output_pwm(_aux_fn, pwm);
SRV_Channels::set_output_scaled(_aux_fn, (uint16_t) (servo_out * 1000));
}
}
4 changes: 0 additions & 4 deletions libraries/AP_Motors/AP_MotorsHeli_RSC.h
Expand Up @@ -103,10 +103,6 @@ class AP_MotorsHeli_RSC {
uint16_t _power_slewrate = 0; // slewrate for throttle (percentage per second)
float _load_feedforward = 0.0f; // estimate of motor load, range 0-1.0f

AP_Int16 _pwm_min;
AP_Int16 _pwm_max;
AP_Int8 _pwm_rev;

// update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output
void update_rotor_ramp(float rotor_ramp_input, float dt);

Expand Down
38 changes: 13 additions & 25 deletions libraries/AP_Motors/AP_MotorsHeli_Single.cpp
Expand Up @@ -116,27 +116,6 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
// @User: Standard
AP_GROUPINFO("GYR_GAIN_ACRO", 11, AP_MotorsHeli_Single, _ext_gyro_gain_acro, 0),

// @Param: RSC_PWM_MIN
// @DisplayName: RSC PWM output miniumum
// @Description: This sets the PWM output on RSC channel for maximum rotor speed
// @Range: 0 2000
// @User: Standard
AP_GROUPINFO("RSC_PWM_MIN", 16, AP_MotorsHeli_Single, _main_rotor._pwm_min, 1000),

// @Param: RSC_PWM_MAX
// @DisplayName: RSC PWM output maxiumum
// @Description: This sets the PWM output on RSC channel for miniumum rotor speed
// @Range: 0 2000
// @User: Standard
AP_GROUPINFO("RSC_PWM_MAX", 17, AP_MotorsHeli_Single, _main_rotor._pwm_max, 2000),

// @Param: RSC_PWM_REV
// @DisplayName: RSC PWM reversal
// @Description: This controls reversal of the RSC channel output
// @Values: -1:Reversed,1:Normal
// @User: Standard
AP_GROUPINFO("RSC_PWM_REV", 18, AP_MotorsHeli_Single, _main_rotor._pwm_rev, 1),

// parameters up to and including 29 are reserved for tradheli

AP_GROUPEND
Expand Down Expand Up @@ -165,9 +144,16 @@ bool AP_MotorsHeli_Single::init_outputs()
_swash_servo_2 = SRV_Channels::get_channel_for(SRV_Channel::k_motor2, CH_2);
_swash_servo_3 = SRV_Channels::get_channel_for(SRV_Channel::k_motor3, CH_3);
_yaw_servo = SRV_Channels::get_channel_for(SRV_Channel::k_motor4, CH_4);
_servo_aux = SRV_Channels::get_channel_for(SRV_Channel::k_motor7, CH_7);
if (!_swash_servo_1 || !_swash_servo_2 || !_swash_servo_3 || !_yaw_servo || !_servo_aux) {
return false;
if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH) {
_tail_rotor.init_servo();
if (!_swash_servo_1 || !_swash_servo_2 || !_swash_servo_3 || !_yaw_servo) {
return false;
}
} else {
_servo_aux = SRV_Channels::get_channel_for(SRV_Channel::k_motor7, CH_7);
if (!_swash_servo_1 || !_swash_servo_2 || !_swash_servo_3 || !_yaw_servo || !_servo_aux) {
return false;
}
}
}

Expand Down Expand Up @@ -494,7 +480,9 @@ void AP_MotorsHeli_Single::move_yaw(float yaw_out)
// write_aux - converts servo_out parameter value (0 to 1 range) to pwm and outputs to aux channel (ch7)
void AP_MotorsHeli_Single::write_aux(float servo_out)
{
rc_write(AP_MOTORS_HELI_SINGLE_AUX, calc_pwm_output_0to1(servo_out, _servo_aux));
if (_servo_aux) {
rc_write(AP_MOTORS_HELI_SINGLE_AUX, calc_pwm_output_0to1(servo_out, _servo_aux));
}
}

// servo_test - move servos through full range of movement
Expand Down