mirror of https://github.com/ArduPilot/ardupilot
Copter: remove ACRO's axis enabled parameter
Acro is now body frame (with earth frame leveling) while Sport is earth frame acro
This commit is contained in:
parent
786d6824ae
commit
82082e044c
|
@ -1476,11 +1476,7 @@ void update_yaw_mode(void)
|
|||
|
||||
case YAW_ACRO:
|
||||
// pilot controlled yaw using rate controller
|
||||
if(g.axis_enabled) {
|
||||
get_yaw_rate_stabilized_bf(g.rc_4.control_in);
|
||||
}else{
|
||||
get_acro_yaw(g.rc_4.control_in);
|
||||
}
|
||||
get_yaw_rate_stabilized_bf(g.rc_4.control_in);
|
||||
break;
|
||||
|
||||
case YAW_LOOK_AT_NEXT_WP:
|
||||
|
@ -1673,32 +1669,21 @@ void update_roll_pitch_mode(void)
|
|||
control_pitch = g.rc_2.control_in;
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
if(g.axis_enabled) {
|
||||
acro_level_mix = constrain_float(1-max(max(abs(g.rc_1.control_in), abs(g.rc_2.control_in)), abs(g.rc_4.control_in))/4500.0, 0, 1)*cos_pitch_x;
|
||||
get_roll_rate_stabilized_bf(g.rc_1.control_in);
|
||||
get_pitch_rate_stabilized_bf(g.rc_2.control_in);
|
||||
get_acro_level_rates();
|
||||
// ACRO does not get SIMPLE mode ability
|
||||
if (motors.flybar_mode == 1) {
|
||||
g.rc_1.servo_out = g.rc_1.control_in;
|
||||
g.rc_2.servo_out = g.rc_2.control_in;
|
||||
}else{
|
||||
// ACRO does not get SIMPLE mode ability
|
||||
if (motors.flybar_mode == 1) {
|
||||
g.rc_1.servo_out = g.rc_1.control_in;
|
||||
g.rc_2.servo_out = g.rc_2.control_in;
|
||||
} else {
|
||||
get_acro_roll(g.rc_1.control_in);
|
||||
get_acro_pitch(g.rc_2.control_in);
|
||||
}
|
||||
}
|
||||
#else // !HELI_FRAME
|
||||
if(g.axis_enabled) {
|
||||
acro_level_mix = constrain_float(1-max(max(abs(g.rc_1.control_in), abs(g.rc_2.control_in)), abs(g.rc_4.control_in))/4500.0, 0, 1)*cos_pitch_x;
|
||||
get_roll_rate_stabilized_bf(g.rc_1.control_in);
|
||||
get_pitch_rate_stabilized_bf(g.rc_2.control_in);
|
||||
get_acro_level_rates();
|
||||
}else{
|
||||
// ACRO does not get SIMPLE mode ability
|
||||
get_acro_roll(g.rc_1.control_in);
|
||||
get_acro_pitch(g.rc_2.control_in);
|
||||
}
|
||||
}
|
||||
#else // !HELI_FRAME
|
||||
acro_level_mix = constrain_float(1-max(max(abs(g.rc_1.control_in), abs(g.rc_2.control_in)), abs(g.rc_4.control_in))/4500.0, 0, 1)*cos_pitch_x;
|
||||
get_roll_rate_stabilized_bf(g.rc_1.control_in);
|
||||
get_pitch_rate_stabilized_bf(g.rc_2.control_in);
|
||||
get_acro_level_rates();
|
||||
#endif // HELI_FRAME
|
||||
break;
|
||||
|
||||
|
|
|
@ -146,7 +146,7 @@ public:
|
|||
k_param_auto_slew_rate, // deprecated - can be deleted
|
||||
k_param_sonar_type,
|
||||
k_param_super_simple = 155,
|
||||
k_param_axis_enabled = 157,
|
||||
k_param_axis_enabled = 157, // deprecated - remove with next eeprom number change
|
||||
k_param_copter_leds_mode,
|
||||
k_param_ahrs, // AHRS group
|
||||
|
||||
|
@ -290,7 +290,6 @@ public:
|
|||
AP_Float low_voltage;
|
||||
AP_Int8 super_simple;
|
||||
AP_Int16 rtl_alt_final;
|
||||
AP_Int8 axis_enabled;
|
||||
AP_Int8 copter_leds_mode; // Operating mode of LED
|
||||
// lighting system
|
||||
|
||||
|
|
|
@ -521,13 +521,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
// @User: Standard
|
||||
GSCALAR(acro_p, "ACRO_P", ACRO_P),
|
||||
|
||||
// @Param: AXIS_ENABLE
|
||||
// @DisplayName: Acro Axis
|
||||
// @Description: Used to control whether acro mode actively maintains the current angle when control sticks are released (Enabled = maintains current angle)
|
||||
// @Values: 0:Disabled, 1:Enabled
|
||||
// @User: Standard
|
||||
GSCALAR(axis_enabled, "AXIS_ENABLE", AXIS_LOCK_ENABLED),
|
||||
|
||||
// @Param: ACRO_BAL_ROLL
|
||||
// @DisplayName: Acro Balance Roll
|
||||
// @Description: rate at which roll angle returns to level in acro mode
|
||||
|
|
Loading…
Reference in New Issue