diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 527f8dd68c..45a596bc63 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -423,12 +423,16 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) // unused break; - case MSG_TERRAIN: #if AP_TERRAIN_AVAILABLE + case MSG_TERRAIN_REQUEST: CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST); plane.terrain.send_request(chan); -#endif break; + case MSG_TERRAIN_REPORT: + CHECK_PAYLOAD_SIZE(TERRAIN_REPORT); + plane.terrain.send_report(chan); + break; +#endif case MSG_WIND: CHECK_PAYLOAD_SIZE(WIND); @@ -577,7 +581,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: EXTRA3 // @DisplayName: Extra data type 3 stream rate - // @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, and BATTERY_STATUS + // @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, TERRAIN_REPORT, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, and BATTERY_STATUS // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -686,7 +690,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_DISTANCE_SENSOR, MSG_SYSTEM_TIME, #if AP_TERRAIN_AVAILABLE - MSG_TERRAIN, + MSG_TERRAIN_REPORT, + MSG_TERRAIN_REQUEST, #endif #if AP_BATTERY_ENABLED MSG_BATTERY_STATUS,