mirror of https://github.com/ArduPilot/ardupilot
Copter: pass polygon fence mavlink messages to fence
This commit is contained in:
parent
865aad7598
commit
52d81f630f
|
@ -1944,6 +1944,14 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
// send or receive fence points with GCS
|
||||
case MAVLINK_MSG_ID_FENCE_POINT: // MAV ID: 160
|
||||
case MAVLINK_MSG_ID_FENCE_FETCH_POINT:
|
||||
copter.fence.handle_msg(chan, msg);
|
||||
break;
|
||||
#endif // AC_FENCE == ENABLED
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
//deprecated. Use MAV_CMD_DO_DIGICAM_CONFIGURE
|
||||
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE: // MAV ID: 202
|
||||
|
|
Loading…
Reference in New Issue