Skip to content

Commit

Permalink
ArduPlane: split sending terrain report from terrain request
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Sep 27, 2024
1 parent dfa0f17 commit 3f3d441
Showing 1 changed file with 7 additions and 3 deletions.
10 changes: 7 additions & 3 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
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);
Expand Down Expand Up @@ -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
Expand Down

0 comments on commit 3f3d441

Please sign in to comment.