|
|
|
@ -1103,6 +1103,15 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
@@ -1103,6 +1103,15 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|
|
|
|
|
|
|
|
|
switch(packet.command) { |
|
|
|
|
|
|
|
|
|
case MAV_CMD_START_RX_PAIR: |
|
|
|
|
// initiate bind procedure
|
|
|
|
|
if (!hal.rcin->rc_bind(packet.param1)) { |
|
|
|
|
result = MAV_RESULT_FAILED; |
|
|
|
|
} else { |
|
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_CMD_NAV_TAKEOFF: { |
|
|
|
|
// param3 : horizontal navigation by pilot acceptable
|
|
|
|
|
// param4 : yaw angle (not supported)
|
|
|
|
|