Copter: let GCS base class handle proximity and rangefinder messages

This commit is contained in:
Peter Barker 2019-12-10 13:45:51 +11:00 committed by Andrew Tridgell
parent 05562968e1
commit a56ab9136e

View File

@ -1131,23 +1131,6 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg)
}
#endif
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
{
copter.rangefinder.handle_msg(msg);
#if PROXIMITY_ENABLED == ENABLED
copter.g2.proximity.handle_msg(msg);
#endif
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
{