Browse Source

Plane: correct bad case fallthrough

master
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
0708130b5e
  1. 4
      ArduPlane/GCS_Mavlink.cpp

4
ArduPlane/GCS_Mavlink.cpp

@ -1278,8 +1278,8 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) @@ -1278,8 +1278,8 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
result = MAV_RESULT_ACCEPTED;
}
break;
case MAV_CMD_DO_SET_HOME:
}
case MAV_CMD_DO_SET_HOME: {
// param1 : use current (1=use current location, 0=use specified location)
// param5 : latitude
// param6 : longitude

Loading…
Cancel
Save