ArduCopter: remove last remanants of rate_d to resolve compiler warning of unused variables

This commit is contained in:
rmackay9 2012-11-12 12:35:58 +09:00
parent 48fcf1ee8b
commit 702dd1fb2e
2 changed files with 0 additions and 31 deletions

View File

@ -611,9 +611,6 @@ int32_t pitch_axis;
AP_LeadFilter xLeadFilter; // Long GPS lag filter
AP_LeadFilter yLeadFilter; // Lat GPS lag filter
//AverageFilterInt32_Size3 roll_rate_d_filter; // filtered acceleration
//AverageFilterInt32_Size3 pitch_rate_d_filter; // filtered pitch acceleration
// Barometer filter
AverageFilterInt32_Size5 baro_filter;

View File

@ -301,23 +301,14 @@ run_rate_controllers()
static int16_t
get_rate_roll(int32_t target_rate)
{
static int32_t last_rate = 0; // previous iterations rate
int32_t p,i,d; // used to capture pid values for logging
int32_t current_rate; // this iteration's rate
int32_t rate_error; // simply target_rate - current_rate
//int32_t rate_d; // roll's acceleration
int32_t output; // output from pid controller
//int32_t rate_d_dampener; // value to dampen output based on acceleration
// get current rate
current_rate = (omega.x * DEGX100);
// calculate and filter the acceleration
//rate_d = roll_rate_d_filter.apply(current_rate - last_rate);
// store rate for next iteration
last_rate = current_rate;
// call pid controller
rate_error = target_rate - current_rate;
p = g.pid_rate_roll.get_p(rate_error);
@ -332,11 +323,6 @@ get_rate_roll(int32_t target_rate)
d = g.pid_rate_roll.get_d(rate_error, G_Dt);
output = p + i + d;
// Dampening output with D term
//rate_d_dampener = rate_d * roll_scale_d;
//rate_d_dampener = constrain(rate_d_dampener, -400, 400);
//output -= rate_d_dampener;
// constrain output
output = constrain(output, -5000, 5000);
@ -360,23 +346,14 @@ get_rate_roll(int32_t target_rate)
static int16_t
get_rate_pitch(int32_t target_rate)
{
static int32_t last_rate = 0; // previous iterations rate
int32_t p,i,d; // used to capture pid values for logging
int32_t current_rate; // this iteration's rate
int32_t rate_error; // simply target_rate - current_rate
//int32_t rate_d; // roll's acceleration
int32_t output; // output from pid controller
//int32_t rate_d_dampener; // value to dampen output based on acceleration
// get current rate
current_rate = (omega.y * DEGX100);
// calculate and filter the acceleration
//rate_d = pitch_rate_d_filter.apply(current_rate - last_rate);
// store rate for next iteration
last_rate = current_rate;
// call pid controller
rate_error = target_rate - current_rate;
p = g.pid_rate_pitch.get_p(rate_error);
@ -389,11 +366,6 @@ get_rate_pitch(int32_t target_rate)
d = g.pid_rate_pitch.get_d(rate_error, G_Dt);
output = p + i + d;
// Dampening output with D term
//rate_d_dampener = rate_d * pitch_scale_d;
//rate_d_dampener = constrain(rate_d_dampener, -400, 400);
//output -= rate_d_dampener;
// constrain output
output = constrain(output, -5000, 5000);