mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
Plane: command-long DO_SET_HOME check first param is zero
This commit is contained in:
parent
640fb91329
commit
2073d65975
@ -1321,6 +1321,10 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
plane.init_home();
|
||||
} else {
|
||||
// ensure param1 is zero
|
||||
if (!is_zero(packet.param1)) {
|
||||
break;
|
||||
}
|
||||
if (is_zero(packet.param5) && is_zero(packet.param6) && is_zero(packet.param7)) {
|
||||
// don't allow the 0,0 position
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user