Browse Source

Added acro_p to the params

master
Jason Short 13 years ago
parent
commit
3d63bb6cd4
  1. 4
      ArduCopter/Attitude.pde
  2. 4
      ArduCopter/Parameters.h
  3. 1
      ArduCopter/Parameters.pde
  4. 7
      ArduCopter/config.h

4
ArduCopter/Attitude.pde

@ -83,7 +83,7 @@ get_stabilize_yaw(int32_t target_angle) @@ -83,7 +83,7 @@ get_stabilize_yaw(int32_t target_angle)
static int
get_acro_roll(int32_t target_rate)
{
target_rate = target_rate * g.acro_P;
target_rate = target_rate * g.acro_p;
target_rate = constrain(target_rate, -10000, 10000);
return get_rate_roll(target_rate);
}
@ -91,7 +91,7 @@ get_acro_roll(int32_t target_rate) @@ -91,7 +91,7 @@ get_acro_roll(int32_t target_rate)
static int
get_acro_pitch(int32_t target_rate)
{
target_rate = target_rate * g.acro_P;
target_rate = target_rate * g.acro_p;
target_rate = constrain(target_rate, -10000, 10000);
return get_rate_pitch(target_rate);
}

4
ArduCopter/Parameters.h

@ -171,6 +171,7 @@ public: @@ -171,6 +171,7 @@ public:
// 220: PI/D Controllers
//
k_param_stabilize_d = 220,
k_param_acro_p,
k_param_pid_rate_roll,
k_param_pid_rate_pitch,
k_param_pid_rate_yaw,
@ -293,7 +294,7 @@ public: @@ -293,7 +294,7 @@ public:
AP_Float stabilize_d;
// PI/D controllers
AP_Float acro_P;
AP_Float acro_p;
AC_PID pid_rate_roll;
AC_PID pid_rate_pitch;
@ -399,6 +400,7 @@ public: @@ -399,6 +400,7 @@ public:
camera_pitch_gain (CAM_PITCH_GAIN),
camera_roll_gain (CAM_ROLL_GAIN),
stabilize_d (STABILIZE_D),
acro_p (ACRO_P),
// PID controller initial P initial I initial D initial imax
//-----------------------------------------------------------------------------------------------------

1
ArduCopter/Parameters.pde

@ -108,6 +108,7 @@ static const AP_Param::Info var_info[] PROGMEM = { @@ -108,6 +108,7 @@ static const AP_Param::Info var_info[] PROGMEM = {
GSCALAR(camera_pitch_gain, "CAM_P_G"),
GSCALAR(camera_roll_gain, "CAM_R_G"),
GSCALAR(stabilize_d, "STAB_D"),
GSCALAR(acro_p, "ACRO_P"),
// PID controller
//---------------

7
ArduCopter/config.h

@ -558,6 +558,13 @@ @@ -558,6 +558,13 @@
# define STABILIZE_D .06
#endif
#ifndef ACRO_P
# define ACRO_P 4.5
#endif
// Good for smaller payload motors.
#ifndef STABILIZE_ROLL_P
# define STABILIZE_ROLL_P 4.5

Loading…
Cancel
Save