Browse Source

Copter: send obstacle_distance messages to proximity lib

master
Raouf 7 years ago committed by Randy Mackay
parent
commit
46b669a056
  1. 8
      ArduCopter/GCS_Mavlink.cpp

8
ArduCopter/GCS_Mavlink.cpp

@ -1335,6 +1335,14 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
break; 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 #if HIL_MODE != HIL_MODE_DISABLED
case MAVLINK_MSG_ID_HIL_STATE: // MAV ID: 90 case MAVLINK_MSG_ID_HIL_STATE: // MAV ID: 90
{ {

Loading…
Cancel
Save