Browse Source

ArduCopter: added ACRO_TRAINER parameter to allow enabling/disabling the acro training function which will bring the roll back to within +- 45 degrees

mission-4.1.18
rmackay9 12 years ago
parent
commit
2f1b2b70e6
  1. 4
      ArduCopter/Attitude.pde
  2. 6
      ArduCopter/Parameters.h
  3. 7
      ArduCopter/Parameters.pde
  4. 4
      ArduCopter/config.h

4
ArduCopter/Attitude.pde

@ -130,7 +130,7 @@ get_roll_rate_stabilized_ef(int32_t stick_angle) @@ -130,7 +130,7 @@ get_roll_rate_stabilized_ef(int32_t stick_angle)
roll_axis = wrap_180(roll_axis);
// ensure that we don't reach gimbal lock
if (roll_axis > 4500 || roll_axis < -4500) {
if (labs(roll_axis > 4500) && g.acro_trainer_enabled) {
roll_axis = constrain(roll_axis, -4500, 4500);
angle_error = wrap_180(roll_axis - ahrs.roll_sensor);
} else {
@ -166,7 +166,7 @@ get_pitch_rate_stabilized_ef(int32_t stick_angle) @@ -166,7 +166,7 @@ get_pitch_rate_stabilized_ef(int32_t stick_angle)
pitch_axis = wrap_180(pitch_axis);
// ensure that we don't reach gimbal lock
if (pitch_axis > 4500 || pitch_axis < -4500) {
if (labs(pitch_axis) > 4500) {
pitch_axis = constrain(pitch_axis, -4500, 4500);
angle_error = wrap_180(pitch_axis - ahrs.pitch_sensor);
} else {

6
ArduCopter/Parameters.h

@ -73,6 +73,7 @@ public: @@ -73,6 +73,7 @@ public:
k_param_rssi_pin,
k_param_throttle_accel_enabled,
k_param_yaw_override_behaviour,
k_param_acro_trainer_enabled, // 27
// 65: AP_Limits Library
k_param_limits = 65,
@ -226,8 +227,8 @@ public: @@ -226,8 +227,8 @@ public:
k_param_pid_throttle,
k_param_pid_optflow_roll,
k_param_pid_optflow_pitch,
k_param_acro_balance_roll,
k_param_acro_balance_pitch,
k_param_acro_balance_roll, // scalar (not PID)
k_param_acro_balance_pitch, // scalar (not PID)
k_param_pid_throttle_accel, // 241
// 254,255: reserved
@ -354,6 +355,7 @@ public: @@ -354,6 +355,7 @@ public:
AP_Float acro_p;
AP_Int16 acro_balance_roll;
AP_Int16 acro_balance_pitch;
AP_Int8 acro_trainer_enabled;
// PI/D controllers
AC_PID pid_rate_roll;

7
ArduCopter/Parameters.pde

@ -499,6 +499,13 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -499,6 +499,13 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),
// @Param: ACRO_TRAINER
// @DisplayName: Acro Trainer Enabled
// @Description: Set to 1 (Enabled) to make roll return to within 45 degrees of level automatically
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
GSCALAR(acro_trainer_enabled, "ACRO_TRAINER", ACRO_TRAINER_ENABLED),
// @Param: LED_MODE
// @DisplayName: Copter LED Mode
// @Description: bitmap to control the copter led mode

4
ArduCopter/config.h

@ -781,6 +781,10 @@ @@ -781,6 +781,10 @@
#define ACRO_BALANCE_PITCH 200
#endif
#ifndef ACRO_TRAINER_ENABLED
#define ACRO_TRAINER_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Loiter control gains
//

Loading…
Cancel
Save