@@ -736,14 +736,14 @@ bool GCS_MAVLINK_Plane::handle_guided_request(AP_Mission::Mission_Command &cmd)
736
736
handle a request to change current WP altitude. This happens via a
737
737
callback from handle_mission_item()
738
738
*/
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 )
740
740
{
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 ) {
743
743
plane.next_WP_loc .alt += plane.home .alt ;
744
744
}
745
745
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 ;
747
747
plane.reset_offset_altitude ();
748
748
}
749
749
@@ -1375,26 +1375,25 @@ void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_mess
1375
1375
const uint16_t alt_mask = 0b1111111111111011 ; // (z mask at bit 3)
1376
1376
1377
1377
bool msg_valid = true ;
1378
- AP_Mission::Mission_Command cmd = {0 };
1379
-
1378
+ Location location;
1380
1379
if (pos_target.type_mask & alt_mask)
1381
1380
{
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 ;
1385
1384
switch (pos_target.coordinate_frame )
1386
1385
{
1387
1386
case MAV_FRAME_GLOBAL:
1388
1387
case MAV_FRAME_GLOBAL_INT:
1389
1388
break ; // default to MSL altitude
1390
1389
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
1391
1390
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
1392
- cmd. content . location .relative_alt = true ;
1391
+ location.relative_alt = true ;
1393
1392
break ;
1394
1393
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
1395
1394
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 ;
1398
1397
break ;
1399
1398
default :
1400
1399
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
1403
1402
}
1404
1403
1405
1404
if (msg_valid) {
1406
- handle_change_alt_request (cmd );
1405
+ handle_change_alt_request (location );
1407
1406
}
1408
1407
} // end if alt_mask
1409
1408
}
0 commit comments