Skip to content

Commit 6b60e0d

Browse files
committed
ArduPlane: avoid creating mission items to convey altitude data in guided-change-alt
1 parent 6029c37 commit 6b60e0d

File tree

2 files changed

+13
-14
lines changed

2 files changed

+13
-14
lines changed

ArduPlane/GCS_Mavlink.cpp

Lines changed: 12 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -736,14 +736,14 @@ bool GCS_MAVLINK_Plane::handle_guided_request(AP_Mission::Mission_Command &cmd)
736736
handle a request to change current WP altitude. This happens via a
737737
callback from handle_mission_item()
738738
*/
739-
void GCS_MAVLINK_Plane::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
739+
void GCS_MAVLINK_Plane::handle_change_alt_request(const Location &location)
740740
{
741-
plane.next_WP_loc.alt = cmd.content.location.alt;
742-
if (cmd.content.location.relative_alt) {
741+
plane.next_WP_loc.alt = location.alt;
742+
if (location.relative_alt) {
743743
plane.next_WP_loc.alt += plane.home.alt;
744744
}
745745
plane.next_WP_loc.relative_alt = false;
746-
plane.next_WP_loc.terrain_alt = cmd.content.location.terrain_alt;
746+
plane.next_WP_loc.terrain_alt = location.terrain_alt;
747747
plane.reset_offset_altitude();
748748
}
749749

@@ -1375,26 +1375,25 @@ void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_mess
13751375
const uint16_t alt_mask = 0b1111111111111011; // (z mask at bit 3)
13761376

13771377
bool msg_valid = true;
1378-
AP_Mission::Mission_Command cmd = {0};
1379-
1378+
Location location;
13801379
if (pos_target.type_mask & alt_mask)
13811380
{
1382-
cmd.content.location.alt = pos_target.alt * 100;
1383-
cmd.content.location.relative_alt = false;
1384-
cmd.content.location.terrain_alt = false;
1381+
location.alt = pos_target.alt * 100;
1382+
location.relative_alt = false;
1383+
location.terrain_alt = false;
13851384
switch (pos_target.coordinate_frame)
13861385
{
13871386
case MAV_FRAME_GLOBAL:
13881387
case MAV_FRAME_GLOBAL_INT:
13891388
break; //default to MSL altitude
13901389
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
13911390
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
1392-
cmd.content.location.relative_alt = true;
1391+
location.relative_alt = true;
13931392
break;
13941393
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
13951394
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
1396-
cmd.content.location.relative_alt = true;
1397-
cmd.content.location.terrain_alt = true;
1395+
location.relative_alt = true;
1396+
location.terrain_alt = true;
13981397
break;
13991398
default:
14001399
gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT");
@@ -1403,7 +1402,7 @@ void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_mess
14031402
}
14041403

14051404
if (msg_valid) {
1406-
handle_change_alt_request(cmd);
1405+
handle_change_alt_request(location);
14071406
}
14081407
} // end if alt_mask
14091408
}

ArduPlane/GCS_Mavlink.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK
5656

5757
void handle_message(const mavlink_message_t &msg) override;
5858
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
59-
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
59+
void handle_change_alt_request(const Location &location) override;
6060
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
6161
MAV_RESULT handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet);
6262
MAV_RESULT handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet);

0 commit comments

Comments
 (0)