mirror of https://github.com/ArduPilot/ardupilot
Copter: fix spelling in drift mode variable name
non-functional change
This commit is contained in:
parent
c6c5603382
commit
60c3ae1ec2
|
@ -40,7 +40,7 @@ bool Copter::ModeDrift::init(bool ignore_checks)
|
|||
// should be called at 100hz or more
|
||||
void Copter::ModeDrift::run()
|
||||
{
|
||||
static float breaker = 0.0f;
|
||||
static float braker = 0.0f;
|
||||
static float roll_input = 0.0f;
|
||||
float target_roll, target_pitch;
|
||||
float target_yaw_rate;
|
||||
|
@ -90,11 +90,11 @@ void Copter::ModeDrift::run()
|
|||
// If we let go of sticks, bring us to a stop
|
||||
if(is_zero(target_pitch)){
|
||||
// .14/ (.03 * 100) = 4.6 seconds till full braking
|
||||
breaker += .03f;
|
||||
breaker = MIN(breaker, DRIFT_SPEEDGAIN);
|
||||
target_pitch = pitch_vel * breaker;
|
||||
braker += .03f;
|
||||
braker = MIN(braker, DRIFT_SPEEDGAIN);
|
||||
target_pitch = pitch_vel * braker;
|
||||
}else{
|
||||
breaker = 0.0f;
|
||||
braker = 0.0f;
|
||||
}
|
||||
|
||||
// set motors to full range
|
||||
|
|
Loading…
Reference in New Issue