Rover: let GCS base class handle proximity and rangefinder messages

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

View File

@ -1038,14 +1038,6 @@ void GCS_MAVLINK_Rover::handleMessage(const mavlink_message_t &msg)
break;
}
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
rover.rangefinder.handle_msg(msg);
rover.g2.proximity.handle_msg(msg);
break;
case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
rover.g2.proximity.handle_msg(msg);
break;
default:
handle_common_message(msg);
break;