GCS_MAVLink: Add support for OBSTACLE_DISTANCE_3D

This commit is contained in:
Rishabh 2020-12-06 17:47:48 +05:30 committed by Randy Mackay
parent 1262d73071
commit a5fafe57d8
2 changed files with 13 additions and 0 deletions

View File

@ -396,6 +396,7 @@ protected:
void handle_distance_sensor(const mavlink_message_t &msg);
void handle_obstacle_distance(const mavlink_message_t &msg);
void handle_obstacle_distance_3d(const mavlink_message_t &msg);
void handle_osd_param_config(const mavlink_message_t &msg);

View File

@ -3224,6 +3224,14 @@ void GCS_MAVLINK::handle_obstacle_distance(const mavlink_message_t &msg)
}
}
void GCS_MAVLINK::handle_obstacle_distance_3d(const mavlink_message_t &msg)
{
AP_Proximity *proximity = AP::proximity();
if (proximity != nullptr) {
proximity->handle_msg(msg);
}
}
void GCS_MAVLINK::handle_osd_param_config(const mavlink_message_t &msg)
{
#if OSD_PARAM_ENABLED
@ -3419,6 +3427,10 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
handle_obstacle_distance(msg);
break;
case MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D:
handle_obstacle_distance_3d(msg);
break;
case MAVLINK_MSG_ID_OSD_PARAM_CONFIG:
case MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG: