Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Split sending terrain report from terrain request #28244

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 9 additions & 4 deletions ArduCopter/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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,
Expand Down
13 changes: 9 additions & 4 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_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);
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 Expand Up @@ -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,
Expand Down
11 changes: 8 additions & 3 deletions ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -248,12 +248,16 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
send_info();
break;

case MSG_TERRAIN:
#if AP_TERRAIN_AVAILABLE
case MSG_TERRAIN_REQUEST:
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
sub.terrain.send_request(chan);
#endif
break;
case MSG_TERRAIN_REPORT:
CHECK_PAYLOAD_SIZE(TERRAIN_REPORT);
sub.terrain.send_report(chan);
break;
#endif

default:
return GCS_MAVLINK::try_send_message(id);
Expand Down Expand Up @@ -407,7 +411,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,
Expand Down
2 changes: 1 addition & 1 deletion Blimp/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {

// @Param: EXTRA3
// @DisplayName: Extra data type 3 stream rate to ground station
// @Description: Stream rate of AHRS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
// @Description: Stream rate of AHRS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
// @Units: Hz
// @Range: 0 10
// @Increment: 1
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Terrain/AP_Terrain.h
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,9 @@ class AP_Terrain {
void send_request(mavlink_channel_t chan);

// handle terrain data and reports from GCS
// send a terrain report for the current location, extrapolating height as we do for navigation:
void send_report(mavlink_channel_t chan);
// send a terrain report or Location loc
void send_terrain_report(mavlink_channel_t chan, const Location &loc, bool extrapolate);
void handle_data(mavlink_channel_t chan, const mavlink_message_t &msg);
void handle_terrain_check(mavlink_channel_t chan, const mavlink_message_t &msg);
Expand Down
19 changes: 13 additions & 6 deletions libraries/AP_Terrain/TerrainGCS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,17 +115,12 @@ void AP_Terrain::send_request(mavlink_channel_t chan)

Location loc;
if (!AP::ahrs().get_location(loc)) {
// we don't know where we are. Send a report and request any cached blocks.
// we don't know where we are. Request any cached blocks.
// this allows for download of mission items when we have no GPS lock
loc = {};
send_terrain_report(chan, loc, true);
send_cache_request(chan);
return;
}

// always send a terrain report
send_terrain_report(chan, loc, true);

// did we request recently?
if (AP_HAL::millis() - last_request_time_ms[chan] < 2000) {
// too soon to request again
Expand Down Expand Up @@ -207,6 +202,18 @@ void AP_Terrain::handle_data(mavlink_channel_t chan, const mavlink_message_t &ms
}
}

/*
send a TERRAIN_REPORT for the current location
*/
void AP_Terrain::send_report(mavlink_channel_t chan)
{
Location loc;
if (!AP::ahrs().get_location(loc)) {
loc = {};
}

send_terrain_report(chan, loc, true);
}

/*
send a TERRAIN_REPORT for a location
Expand Down
6 changes: 4 additions & 2 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1049,8 +1049,10 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_RANGEFINDER, MSG_RANGEFINDER},
#endif
{ MAVLINK_MSG_ID_DISTANCE_SENSOR, MSG_DISTANCE_SENSOR},
// request also does report:
{ MAVLINK_MSG_ID_TERRAIN_REQUEST, MSG_TERRAIN},
#if AP_TERRAIN_AVAILABLE
{ MAVLINK_MSG_ID_TERRAIN_REQUEST, MSG_TERRAIN_REQUEST},
{ MAVLINK_MSG_ID_TERRAIN_REPORT, MSG_TERRAIN_REPORT},
#endif
#if AP_MAVLINK_BATTERY2_ENABLED
{ MAVLINK_MSG_ID_BATTERY2, MSG_BATTERY2},
#endif
Expand Down
3 changes: 2 additions & 1 deletion libraries/GCS_MAVLink/ap_message.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@ enum ap_message : uint8_t {
MSG_WIND,
MSG_RANGEFINDER,
MSG_DISTANCE_SENSOR,
MSG_TERRAIN,
MSG_TERRAIN_REQUEST,
MSG_TERRAIN_REPORT,
MSG_BATTERY2,
MSG_CAMERA_FEEDBACK,
MSG_CAMERA_INFORMATION,
Expand Down
Loading