Browse Source

Plane: command-long DO_SET_HOME check first param is zero

mission-4.1.18
Randy Mackay 7 years ago
parent
commit
2073d65975
  1. 4
      ArduPlane/GCS_Mavlink.cpp

4
ArduPlane/GCS_Mavlink.cpp

@ -1321,6 +1321,10 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) @@ -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…
Cancel
Save