Rover: send obstacle_distance messages to proximity lib

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

View File

@ -1227,6 +1227,9 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
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);