Copter: remove x100 from IMAX definitions

This commit is contained in:
Randy Mackay 2013-08-19 22:37:57 +09:00
parent a06f8a156d
commit d8eb7fb82f
2 changed files with 21 additions and 21 deletions

View File

@ -440,27 +440,27 @@ public:
// PID controller initial P initial I initial D
// initial imax
//-----------------------------------------------------------------------------------------------------
pid_rate_roll (RATE_ROLL_P, RATE_ROLL_I, RATE_ROLL_D, RATE_ROLL_IMAX * 100),
pid_rate_pitch (RATE_PITCH_P, RATE_PITCH_I, RATE_PITCH_D, RATE_PITCH_IMAX * 100),
pid_rate_yaw (RATE_YAW_P, RATE_YAW_I, RATE_YAW_D, RATE_YAW_IMAX * 100),
pid_rate_roll (RATE_ROLL_P, RATE_ROLL_I, RATE_ROLL_D, RATE_ROLL_IMAX),
pid_rate_pitch (RATE_PITCH_P, RATE_PITCH_I, RATE_PITCH_D, RATE_PITCH_IMAX),
pid_rate_yaw (RATE_YAW_P, RATE_YAW_I, RATE_YAW_D, RATE_YAW_IMAX),
pid_loiter_rate_lat (LOITER_RATE_P, LOITER_RATE_I, LOITER_RATE_D, LOITER_RATE_IMAX * 100),
pid_loiter_rate_lon (LOITER_RATE_P, LOITER_RATE_I, LOITER_RATE_D, LOITER_RATE_IMAX * 100),
pid_loiter_rate_lat (LOITER_RATE_P, LOITER_RATE_I, LOITER_RATE_D, LOITER_RATE_IMAX),
pid_loiter_rate_lon (LOITER_RATE_P, LOITER_RATE_I, LOITER_RATE_D, LOITER_RATE_IMAX),
pid_throttle_rate (THROTTLE_RATE_P, THROTTLE_RATE_I, THROTTLE_RATE_D, THROTTLE_RATE_IMAX),
pid_throttle_accel (THROTTLE_ACCEL_P, THROTTLE_ACCEL_I, THROTTLE_ACCEL_D, THROTTLE_ACCEL_IMAX),
pid_optflow_roll (OPTFLOW_ROLL_P, OPTFLOW_ROLL_I, OPTFLOW_ROLL_D, OPTFLOW_IMAX * 100),
pid_optflow_pitch (OPTFLOW_PITCH_P, OPTFLOW_PITCH_I, OPTFLOW_PITCH_D, OPTFLOW_IMAX * 100),
pid_optflow_roll (OPTFLOW_ROLL_P, OPTFLOW_ROLL_I, OPTFLOW_ROLL_D, OPTFLOW_IMAX),
pid_optflow_pitch (OPTFLOW_PITCH_P, OPTFLOW_PITCH_I, OPTFLOW_PITCH_D, OPTFLOW_IMAX),
// PI controller initial P initial I initial
// imax
//----------------------------------------------------------------------
pi_loiter_lat (LOITER_P, LOITER_I, LOITER_IMAX * 100),
pi_loiter_lon (LOITER_P, LOITER_I, LOITER_IMAX * 100),
pi_loiter_lat (LOITER_P, LOITER_I, LOITER_IMAX),
pi_loiter_lon (LOITER_P, LOITER_I, LOITER_IMAX),
pi_stabilize_roll (STABILIZE_ROLL_P, STABILIZE_ROLL_I, STABILIZE_ROLL_IMAX * 100),
pi_stabilize_pitch (STABILIZE_PITCH_P, STABILIZE_PITCH_I, STABILIZE_PITCH_IMAX * 100),
pi_stabilize_yaw (STABILIZE_YAW_P, STABILIZE_YAW_I, STABILIZE_YAW_IMAX * 100),
pi_stabilize_roll (STABILIZE_ROLL_P, STABILIZE_ROLL_I, STABILIZE_ROLL_IMAX),
pi_stabilize_pitch (STABILIZE_PITCH_P, STABILIZE_PITCH_I, STABILIZE_PITCH_IMAX),
pi_stabilize_yaw (STABILIZE_YAW_P, STABILIZE_YAW_I, STABILIZE_YAW_IMAX),
pi_alt_hold (ALT_HOLD_P, ALT_HOLD_I, ALT_HOLD_IMAX)
{

View File

@ -468,7 +468,7 @@
#define OPTFLOW_PITCH_D 0.12f
#endif
#ifndef OPTFLOW_IMAX
#define OPTFLOW_IMAX 1
#define OPTFLOW_IMAX 100
#endif
//////////////////////////////////////////////////////////////////////////////
@ -790,7 +790,7 @@
# define STABILIZE_ROLL_I 0.0f
#endif
#ifndef STABILIZE_ROLL_IMAX
# define STABILIZE_ROLL_IMAX 8.0f // degrees
# define STABILIZE_ROLL_IMAX 0
#endif
#ifndef STABILIZE_PITCH_P
@ -800,7 +800,7 @@
# define STABILIZE_PITCH_I 0.0f
#endif
#ifndef STABILIZE_PITCH_IMAX
# define STABILIZE_PITCH_IMAX 8.0f // degrees
# define STABILIZE_PITCH_IMAX 0
#endif
#ifndef STABILIZE_YAW_P
@ -810,7 +810,7 @@
# define STABILIZE_YAW_I 0.0f
#endif
#ifndef STABILIZE_YAW_IMAX
# define STABILIZE_YAW_IMAX 8.0f // degrees * 100
# define STABILIZE_YAW_IMAX 0
#endif
#ifndef YAW_LOOK_AHEAD_MIN_SPEED
@ -837,7 +837,7 @@
# define RATE_ROLL_D 0.004f
#endif
#ifndef RATE_ROLL_IMAX
# define RATE_ROLL_IMAX 5.0f // degrees
# define RATE_ROLL_IMAX 500
#endif
#ifndef RATE_PITCH_P
@ -850,7 +850,7 @@
# define RATE_PITCH_D 0.004f
#endif
#ifndef RATE_PITCH_IMAX
# define RATE_PITCH_IMAX 5.0f // degrees
# define RATE_PITCH_IMAX 500
#endif
#ifndef RATE_YAW_P
@ -863,7 +863,7 @@
# define RATE_YAW_D 0.000f
#endif
#ifndef RATE_YAW_IMAX
# define RATE_YAW_IMAX 8.0f // degrees
# define RATE_YAW_IMAX 800
#endif
@ -901,7 +901,7 @@
# define LOITER_I 0.0f
#endif
#ifndef LOITER_IMAX
# define LOITER_IMAX 30 // degrees
# define LOITER_IMAX 0
#endif
//////////////////////////////////////////////////////////////////////////////
@ -917,7 +917,7 @@
# define LOITER_RATE_D 0.0f
#endif
#ifndef LOITER_RATE_IMAX
# define LOITER_RATE_IMAX 4 // maximum acceleration from I term build-up in m/s/s
# define LOITER_RATE_IMAX 400 // maximum acceleration from I term build-up in cm/s/s
#endif
//////////////////////////////////////////////////////////////////////////////