Copter: send obstacle_distance messages to proximity lib

This commit is contained in:
Raouf 2018-09-06 19:18:03 +09:00 committed by Randy Mackay
parent 8bfb1d2445
commit 46b669a056

View File

@ -1335,6 +1335,14 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
break;
}
case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
{
#if PROXIMITY_ENABLED == ENABLED
copter.g2.proximity.handle_msg(msg);
#endif
break;
}
#if HIL_MODE != HIL_MODE_DISABLED
case MAVLINK_MSG_ID_HIL_STATE: // MAV ID: 90
{