ArduCopter: split sending terrain report from terrain request

This commit is contained in:
Peter Barker 2024-09-27 11:01:25 +10:00 committed by Andrew Tridgell
parent 423daaa71f
commit 47618ccb72

View File

@ -336,12 +336,16 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
{
switch(id) {
case MSG_TERRAIN:
#if AP_TERRAIN_AVAILABLE
case MSG_TERRAIN_REQUEST:
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
copter.terrain.send_request(chan);
#endif
break;
case MSG_TERRAIN_REPORT:
CHECK_PAYLOAD_SIZE(TERRAIN_REPORT);
copter.terrain.send_report(chan);
break;
#endif
case MSG_WIND:
CHECK_PAYLOAD_SIZE(WIND);
@ -451,7 +455,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, BATTERY_STATUS, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, RPM, ESC TELEMETRY,GENERATOR_STATUS, and WINCH_STATUS
// @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, TERRAIN_REPORT, BATTERY_STATUS, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, RPM, ESC TELEMETRY,GENERATOR_STATUS, and WINCH_STATUS
// @Units: Hz
// @Range: 0 50
@ -544,7 +548,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
#endif
MSG_DISTANCE_SENSOR,
#if AP_TERRAIN_AVAILABLE
MSG_TERRAIN,
MSG_TERRAIN_REQUEST,
MSG_TERRAIN_REPORT,
#endif
#if AP_BATTERY_ENABLED
MSG_BATTERY_STATUS,