Copter: adjust for location flags being moved out of union
This commit is contained in:
parent
1f5727c0b2
commit
f48d757bd4
@ -525,7 +525,7 @@ bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd)
|
||||
void GCS_MAVLINK_Copter::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
|
||||
{
|
||||
// add home alt if needed
|
||||
if (cmd.content.location.flags.relative_alt) {
|
||||
if (cmd.content.location.relative_alt) {
|
||||
cmd.content.location.alt += copter.ahrs.get_home().alt;
|
||||
}
|
||||
|
||||
@ -1248,13 +1248,13 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
switch (packet.coordinate_frame) {
|
||||
case MAV_FRAME_GLOBAL_RELATIVE_ALT: // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT
|
||||
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
|
||||
loc.flags.relative_alt = true;
|
||||
loc.flags.terrain_alt = false;
|
||||
loc.relative_alt = true;
|
||||
loc.terrain_alt = false;
|
||||
break;
|
||||
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
|
||||
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
|
||||
loc.flags.relative_alt = true;
|
||||
loc.flags.terrain_alt = true;
|
||||
loc.relative_alt = true;
|
||||
loc.terrain_alt = true;
|
||||
break;
|
||||
case MAV_FRAME_GLOBAL:
|
||||
case MAV_FRAME_GLOBAL_INT:
|
||||
@ -1262,8 +1262,8 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
// pv_location_to_vector does not support absolute altitudes.
|
||||
// Convert the absolute altitude to a home-relative altitude before calling pv_location_to_vector
|
||||
loc.alt -= copter.ahrs.get_home().alt;
|
||||
loc.flags.relative_alt = true;
|
||||
loc.flags.terrain_alt = false;
|
||||
loc.relative_alt = true;
|
||||
loc.terrain_alt = false;
|
||||
break;
|
||||
}
|
||||
pos_neu_cm = copter.pv_location_to_vector(loc);
|
||||
|
@ -192,10 +192,8 @@ void RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const aux_sw
|
||||
if (copter.mode_auto.mission.num_commands() == 0) {
|
||||
// set our location ID to 16, MAV_CMD_NAV_WAYPOINT
|
||||
cmd.id = MAV_CMD_NAV_TAKEOFF;
|
||||
cmd.content.location.options = 0;
|
||||
cmd.p1 = 0;
|
||||
cmd.content.location.lat = 0;
|
||||
cmd.content.location.lng = 0;
|
||||
memset(&cmd.content.location, 0, sizeof(cmd.content.location));
|
||||
cmd.content.location.alt = MAX(copter.current_loc.alt,100);
|
||||
|
||||
// use the current altitude for the target alt for takeoff.
|
||||
|
@ -25,6 +25,6 @@ void Copter::read_inertia()
|
||||
}
|
||||
|
||||
// set flags and get velocity
|
||||
current_loc.flags.relative_alt = true;
|
||||
current_loc.relative_alt = true;
|
||||
climb_rate = inertial_nav.get_velocity_z();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user