mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: command-long DO_SET_HOME check first param is zero
Also do not use current location just because lat,lon,alt are all zero
This commit is contained in:
parent
d982cfed4a
commit
a8a5c1d332
@ -973,11 +973,15 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
// param6 : longitude
|
||||
// param7 : altitude (absolute)
|
||||
result = MAV_RESULT_FAILED; // assume failure
|
||||
if(is_equal(packet.param1,1.0f) || (is_zero(packet.param5) && is_zero(packet.param6) && is_zero(packet.param7))) {
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
if (copter.set_home_to_current_location(true)) {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
} else {
|
||||
// ensure param1 is zero
|
||||
if (!is_zero(packet.param1)) {
|
||||
break;
|
||||
}
|
||||
// sanity check location
|
||||
if (!check_latlng(packet.param5, packet.param6)) {
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user