mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Arducopter : Force home alt to 0
This commit is contained in:
parent
89fec907e2
commit
19d8c405fd
@ -759,7 +759,7 @@ static void do_set_home()
|
||||
home.id = MAV_CMD_NAV_WAYPOINT;
|
||||
home.lng = command_cond_queue.lng; // Lon * 10**7
|
||||
home.lat = command_cond_queue.lat; // Lat * 10**7
|
||||
home.alt = max(command_cond_queue.alt, 0);
|
||||
home.alt = 0;
|
||||
home_is_set = true;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user