Copter: Helicopter: to use new Stab_Col and Acro_Col functions.

This commit is contained in:
Robert Lefebvre 2015-10-12 21:05:49 -04:00 committed by Randy Mackay
parent 3385d83177
commit bdbfd8fd5e
8 changed files with 29 additions and 41 deletions

View File

@ -806,7 +806,6 @@ private:
bool mode_allows_arming(uint8_t mode, bool arming_from_gcs);
void notify_flight_mode(uint8_t mode);
void heli_init();
int16_t get_pilot_desired_collective(int16_t control_in);
void check_dynamic_flight(void);
void update_heli_control_dynamics(void);
void heli_update_landing_swash();

View File

@ -519,24 +519,6 @@ const AP_Param::Info Copter::var_info[] PROGMEM = {
// @Group: H_RSC_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(heli_servo_rsc, "H_RSC_", RC_Channel),
// @Param: H_STAB_COL_MIN
// @DisplayName: Heli Stabilize Throttle Collective Minimum
// @Description: Helicopter's minimum collective position while pilot directly controls collective in stabilize mode
// @Range: 0 500
// @Units: Percent*10
// @Increment: 1
// @User: Standard
GSCALAR(heli_stab_col_min, "H_STAB_COL_MIN", HELI_STAB_COLLECTIVE_MIN_DEFAULT),
// @Param: H_STAB_COL_MAX
// @DisplayName: Stabilize Throttle Maximum
// @Description: Helicopter's maximum collective position while pilot directly controls collective in stabilize mode
// @Range: 500 1000
// @Units: Percent*10
// @Increment: 1
// @User: Standard
GSCALAR(heli_stab_col_max, "H_STAB_COL_MAX", HELI_STAB_COLLECTIVE_MAX_DEFAULT),
#endif
// RC channel

View File

@ -162,8 +162,8 @@ public:
k_param_heli_pitch_ff, // remove
k_param_heli_roll_ff, // remove
k_param_heli_yaw_ff, // remove
k_param_heli_stab_col_min,
k_param_heli_stab_col_max, // 88
k_param_heli_stab_col_min, // remove
k_param_heli_stab_col_max, // remove
k_param_heli_servo_rsc, // 89 = full!
//
@ -437,8 +437,6 @@ public:
// Heli
RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail
RC_Channel heli_servo_rsc; // servo for rotor speed control output
AP_Int16 heli_stab_col_min; // min collective while pilot directly controls collective in stabilize mode
AP_Int16 heli_stab_col_max; // min collective while pilot directly controls collective in stabilize mode
#endif
#if FRAME_CONFIG == SINGLE_FRAME
// Single

View File

@ -122,8 +122,6 @@
# define RATE_YAW_IMAX 4500
# define RATE_YAW_FF 0.02
# define RATE_YAW_FILT_HZ 20.0f
# define HELI_STAB_COLLECTIVE_MIN_DEFAULT 0
# define HELI_STAB_COLLECTIVE_MAX_DEFAULT 1000
# define THR_MIN_DEFAULT 0
# define AUTOTUNE_ENABLED DISABLED
#endif

View File

@ -243,6 +243,17 @@ void Copter::exit_mode(uint8_t old_control_mode, uint8_t new_control_mode)
attitude_control.use_flybar_passthrough(false, false);
}
// if we are changing from a mode that did not use manual throttle,
// stab col ramp value should be pre-loaded to the correct value to avoid a twitch
// heli_stab_col_ramp should really only be active switching between Stabilize and Acro modes
if (!mode_has_manual_throttle(old_control_mode)){
if (new_control_mode == STABILIZE){
input_manager.set_stab_col_ramp(1.0);
} else if (new_control_mode == ACRO){
input_manager.set_stab_col_ramp(0.0);
}
}
// reset RC Passthrough to motors
motors.reset_radio_passthrough();
#endif //HELI_FRAME

View File

@ -18,21 +18,10 @@ void Copter::heli_init()
{
// helicopters are always using motor interlock
set_using_interlock(true);
}
// get_pilot_desired_collective - converts pilot input (from 0 ~ 1000) to a value that can be fed into the channel_throttle->servo_out function
int16_t Copter::get_pilot_desired_collective(int16_t control_in)
{
// return immediately if reduce collective range for manual flight has not been configured
if (g.heli_stab_col_min == 0 && g.heli_stab_col_max == 1000) {
return control_in;
}
// scale pilot input to reduced collective range
float scalar = ((float)(g.heli_stab_col_max - g.heli_stab_col_min))/1000.0f;
int16_t collective_out = g.heli_stab_col_min + control_in * scalar;
collective_out = constrain_int16(collective_out, 0, 1000);
return collective_out;
// pre-load stab col values as mode is initialized as Stabilize, but stabilize_init() function is not run on start-up.
input_manager.set_use_stab_col(true);
input_manager.set_stab_col_ramp(1.0);
}
// heli_check_dynamic_flight - updates the dynamic_flight flag based on our horizontal velocity

View File

@ -13,6 +13,9 @@ bool Copter::heli_acro_init(bool ignore_checks)
// if heli is equipped with a flybar, then tell the attitude controller to pass through controls directly to servos
attitude_control.use_flybar_passthrough(motors.has_flybar(), motors.supports_yaw_passthrough());
// set stab collective false to use full collective pitch range
input_manager.set_use_stab_col(false);
// always successfully enter acro
return true;
}
@ -22,6 +25,7 @@ bool Copter::heli_acro_init(bool ignore_checks)
void Copter::heli_acro_run()
{
float target_roll, target_pitch, target_yaw;
int16_t pilot_throttle_scaled;
// Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because
// we may be in autorotation flight. These should be reset only when transitioning from disarmed
@ -56,8 +60,11 @@ void Copter::heli_acro_run()
attitude_control.passthrough_bf_roll_pitch_rate_yaw(channel_roll->control_in, channel_pitch->control_in, target_yaw);
}
// get pilot's desired throttle
pilot_throttle_scaled = input_manager.get_pilot_desired_collective(channel_throttle->control_in);
// output pilot's throttle without angle boost
attitude_control.set_throttle_out(channel_throttle->control_in, false, g.throttle_filt);
attitude_control.set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
}
// get_pilot_desired_yaw_rate - transform pilot's yaw input into a desired yaw angle rate

View File

@ -13,6 +13,10 @@ bool Copter::heli_stabilize_init(bool ignore_checks)
// set target altitude to zero for reporting
// To-Do: make pos controller aware when it's active/inactive so it can always report the altitude error?
pos_control.set_alt_target(0);
// set stab collective true to use stabilize scaled collective pitch range
input_manager.set_use_stab_col(true);
return true;
}
@ -56,7 +60,7 @@ void Copter::heli_stabilize_run()
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
// get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_collective(channel_throttle->control_in);
pilot_throttle_scaled = input_manager.get_pilot_desired_collective(channel_throttle->control_in);
// call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());