mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 14:38:44 -04:00
Copter: change variable type from float to int32_t
This commit is contained in:
parent
6a9f07ca02
commit
71e8229d75
@ -207,7 +207,7 @@ void ModeAuto::takeoff_start(const Location& dest_loc)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// sanity check target
|
// sanity check target
|
||||||
float alt_target_min_cm = copter.current_loc.alt + (copter.ap.land_complete ? 100 : 0);
|
int32_t alt_target_min_cm = copter.current_loc.alt + (copter.ap.land_complete ? 100 : 0);
|
||||||
if (alt_target < alt_target_min_cm ) {
|
if (alt_target < alt_target_min_cm ) {
|
||||||
dest.set_alt_cm(alt_target_min_cm , Location::AltFrame::ABOVE_HOME);
|
dest.set_alt_cm(alt_target_min_cm , Location::AltFrame::ABOVE_HOME);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user