Copter: pass distance-sensor messages to AP_Proximity
This commit is contained in:
parent
a0a8472a44
commit
20ca021cab
@ -1765,6 +1765,9 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
{
|
{
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
copter.rangefinder.handle_msg(msg);
|
copter.rangefinder.handle_msg(msg);
|
||||||
|
#if PROXIMITY_ENABLED == ENABLED
|
||||||
|
copter.g2.proximity.handle_msg(msg);
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user