mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Rover: send obstacle_distance messages to proximity lib
This commit is contained in:
parent
46b669a056
commit
fc5ce7b273
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user