mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
Copter: land mode minor format fixes
This commit is contained in:
parent
06aa29eb2a
commit
8fdd439827
@ -29,7 +29,6 @@ bool Copter::ModeLand::init(bool ignore_checks)
|
||||
}
|
||||
|
||||
land_start_time = millis();
|
||||
|
||||
land_pause = false;
|
||||
|
||||
// reset flag indicating if pilot has applied roll or pitch inputs during landing
|
||||
@ -44,7 +43,7 @@ void Copter::ModeLand::run()
|
||||
{
|
||||
if (land_with_gps) {
|
||||
gps_run();
|
||||
}else{
|
||||
} else {
|
||||
nogps_run();
|
||||
}
|
||||
}
|
||||
@ -71,7 +70,7 @@ void Copter::ModeLand::gps_run()
|
||||
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
||||
|
||||
// pause before beginning land descent
|
||||
if(land_pause && millis()-land_start_time >= LAND_WITH_DELAY_MS) {
|
||||
if (land_pause && millis()-land_start_time >= LAND_WITH_DELAY_MS) {
|
||||
land_pause = false;
|
||||
}
|
||||
|
||||
@ -133,7 +132,7 @@ void Copter::ModeLand::nogps_run()
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
||||
|
||||
// pause before beginning land descent
|
||||
if(land_pause && millis()-land_start_time >= LAND_WITH_DELAY_MS) {
|
||||
if (land_pause && millis()-land_start_time >= LAND_WITH_DELAY_MS) {
|
||||
land_pause = false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user