Plane: adjust for Location_Class and Location unification

This commit is contained in:
Peter Barker 2019-01-02 14:25:29 +11:00 committed by Peter Barker
parent 61df15ffe8
commit b258e89a2d
2 changed files with 6 additions and 9 deletions

View File

@ -885,7 +885,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
{
switch(packet.command) {
case MAV_CMD_DO_CHANGE_SPEED:
case MAV_CMD_DO_CHANGE_SPEED: {
// if we're in failsafe modes (e.g., RTL, LOITER) or in pilot
// controlled modes (e.g., MANUAL, TRAINING)
// this command should be ignored since it comes in from GCS
@ -901,6 +901,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
}
case MAV_CMD_NAV_LOITER_UNLIM:
plane.set_mode(LOITER, MODE_REASON_GCS_COMMAND);
@ -1232,11 +1233,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
last_hil_state = packet;
// set gps hil sensor
Location loc;
memset(&loc, 0, sizeof(loc));
loc.lat = packet.lat;
loc.lng = packet.lon;
loc.alt = packet.alt/10;
const Location loc{packet.lat, packet.lon, packet.alt/10, Location::ALT_FRAME_ABSOLUTE};
Vector3f vel(packet.vx, packet.vy, packet.vz);
vel *= 0.01f;
@ -1442,10 +1439,10 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
case MAV_FRAME_GLOBAL_INT:
break; //default to MSL altitude
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
cmd.content.location.relative_alt = true;
cmd.content.location.relative_alt = true;
break;
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
cmd.content.location.relative_alt = true;
cmd.content.location.relative_alt = true;
cmd.content.location.terrain_alt = true;
break;
default:

View File

@ -396,7 +396,7 @@ void Plane::geofence_check(bool altitude_check_only)
guided_WP_loc = rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude());
} else { //return to fence return point, not a rally point
memset(&guided_WP_loc, 0, sizeof(guided_WP_loc));
guided_WP_loc = {};
if (g.fence_retalt > 0) {
//fly to the return point using fence_retalt
guided_WP_loc.alt = home.alt + 100.0f*g.fence_retalt;