Browse Source

ArduCopter: changed ACRO_ROLL_STABILIZE and ACRO_PITCH_STABILIZE to parameters

Changes on behalf of Leonard Hall
mission-4.1.18
rmackay9 12 years ago
parent
commit
5e8043fd9c
  1. 4
      ArduCopter/Attitude.pde
  2. 7
      ArduCopter/Parameters.h
  3. 25
      ArduCopter/Parameters.pde
  4. 8
      ArduCopter/config.h

4
ArduCopter/Attitude.pde

@ -154,7 +154,7 @@ get_roll_rate_stabilized_ef(int32_t stick_angle) @@ -154,7 +154,7 @@ get_roll_rate_stabilized_ef(int32_t stick_angle)
int32_t angle_error = 0;
// convert the input to the desired roll rate
int32_t target_rate = stick_angle * g.acro_p - (roll_axis * ACRO_ROLL_STABILISE)/100;
int32_t target_rate = stick_angle * g.acro_p - (roll_axis * g.acro_balance_roll)/100;
// convert the input to the desired roll rate
roll_axis += target_rate * G_Dt;
@ -190,7 +190,7 @@ get_pitch_rate_stabilized_ef(int32_t stick_angle) @@ -190,7 +190,7 @@ get_pitch_rate_stabilized_ef(int32_t stick_angle)
int32_t angle_error = 0;
// convert the input to the desired pitch rate
int32_t target_rate = stick_angle * g.acro_p - (pitch_axis * ACRO_PITCH_STABILISE)/100;
int32_t target_rate = stick_angle * g.acro_p - (pitch_axis * g.acro_balance_pitch)/100;
// convert the input to the desired pitch rate
pitch_axis += target_rate * G_Dt;

7
ArduCopter/Parameters.h

@ -212,6 +212,8 @@ public: @@ -212,6 +212,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,
// 254,255: reserved
};
@ -337,10 +339,13 @@ public: @@ -337,10 +339,13 @@ public:
AP_Float stabilize_d;
AP_Float stabilize_d_schedule;
// PI/D controllers
// Acro parameters
AP_Float acro_p;
AP_Float axis_lock_p;
AP_Int16 acro_balance_roll;
AP_Int16 acro_balance_pitch;
// PI/D controllers
AC_PID pid_rate_roll;
AC_PID pid_rate_pitch;
AC_PID pid_rate_yaw;

25
ArduCopter/Parameters.pde

@ -307,10 +307,27 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -307,10 +307,27 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(stabilize_d_schedule, "STAB_D_S", STABILIZE_D_SCHEDULE),
GSCALAR(acro_p, "ACRO_P", ACRO_P),
GSCALAR(axis_lock_p, "AXIS_P", AXIS_LOCK_P),
GSCALAR(axis_enabled, "AXIS_ENABLE", AXIS_LOCK_ENABLED),
GSCALAR(copter_leds_mode, "LED_MODE", 9),
// Acro parameters
GSCALAR(acro_p, "ACRO_P", ACRO_P),
GSCALAR(axis_lock_p, "AXIS_P", AXIS_LOCK_P),
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
// @Range: 0 300
// @Increment: 1
// @User: Advanced
GSCALAR(acro_balance_roll, "ACRO_BAL_ROLL", ACRO_BALANCE_ROLL),
// @Param: ACRO_BAL_PITCH
// @DisplayName: Acro Balance Pitch
// @Description: rate at which pitch angle returns to level in acro mode
// @Range: 0 300
// @Increment: 1
// @User: Advanced
GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH),
GSCALAR(copter_leds_mode, "LED_MODE", 9),
// PID controller
//---------------

8
ArduCopter/config.h

@ -771,12 +771,12 @@ @@ -771,12 +771,12 @@
#define MAX_YAW_OVERSHOOT 1000
#endif
#ifndef ACRO_ROLL_STABILISE
#define ACRO_ROLL_STABILISE 100
#ifndef ACRO_BALANCE_ROLL
#define ACRO_BALANCE_ROLL 200
#endif
#ifndef ACRO_PITCH_STABILISE
#define ACRO_PITCH_STABILISE 0
#ifndef ACRO_BALANCE_PITCH
#define ACRO_BALANCE_PITCH 200
#endif
//////////////////////////////////////////////////////////////////////////////

Loading…
Cancel
Save