mirror of https://github.com/ArduPilot/ardupilot
Plane: adjust for location flags being moved out of union
This commit is contained in:
parent
f48d757bd4
commit
acafb0f3c1
|
@ -711,9 +711,9 @@ bool GCS_MAVLINK_Plane::handle_guided_request(AP_Mission::Mission_Command &cmd)
|
|||
plane.guided_WP_loc = cmd.content.location;
|
||||
|
||||
// add home alt if needed
|
||||
if (plane.guided_WP_loc.flags.relative_alt) {
|
||||
if (plane.guided_WP_loc.relative_alt) {
|
||||
plane.guided_WP_loc.alt += plane.home.alt;
|
||||
plane.guided_WP_loc.flags.relative_alt = 0;
|
||||
plane.guided_WP_loc.relative_alt = 0;
|
||||
}
|
||||
|
||||
plane.set_guided_WP();
|
||||
|
@ -727,11 +727,11 @@ bool GCS_MAVLINK_Plane::handle_guided_request(AP_Mission::Mission_Command &cmd)
|
|||
void GCS_MAVLINK_Plane::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
|
||||
{
|
||||
plane.next_WP_loc.alt = cmd.content.location.alt;
|
||||
if (cmd.content.location.flags.relative_alt) {
|
||||
if (cmd.content.location.relative_alt) {
|
||||
plane.next_WP_loc.alt += plane.home.alt;
|
||||
}
|
||||
plane.next_WP_loc.flags.relative_alt = false;
|
||||
plane.next_WP_loc.flags.terrain_alt = cmd.content.location.flags.terrain_alt;
|
||||
plane.next_WP_loc.relative_alt = false;
|
||||
plane.next_WP_loc.terrain_alt = cmd.content.location.terrain_alt;
|
||||
plane.reset_offset_altitude();
|
||||
}
|
||||
|
||||
|
@ -836,10 +836,10 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||
|
||||
// load option flags
|
||||
if (packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) {
|
||||
requested_position.flags.relative_alt = 1;
|
||||
requested_position.relative_alt = 1;
|
||||
}
|
||||
else if (packet.frame == MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) {
|
||||
requested_position.flags.terrain_alt = 1;
|
||||
requested_position.terrain_alt = 1;
|
||||
}
|
||||
else if (packet.frame != MAV_FRAME_GLOBAL_INT) {
|
||||
// not a supported frame
|
||||
|
@ -847,9 +847,9 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||
}
|
||||
|
||||
if (is_zero(packet.param4)) {
|
||||
requested_position.flags.loiter_ccw = 0;
|
||||
requested_position.loiter_ccw = 0;
|
||||
} else {
|
||||
requested_position.flags.loiter_ccw = 1;
|
||||
requested_position.loiter_ccw = 1;
|
||||
}
|
||||
|
||||
if (location_sanitize(plane.current_loc, requested_position)) {
|
||||
|
@ -864,9 +864,9 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||
plane.guided_WP_loc = requested_position;
|
||||
|
||||
// add home alt if needed
|
||||
if (plane.guided_WP_loc.flags.relative_alt) {
|
||||
if (plane.guided_WP_loc.relative_alt) {
|
||||
plane.guided_WP_loc.alt += plane.home.alt;
|
||||
plane.guided_WP_loc.flags.relative_alt = 0;
|
||||
plane.guided_WP_loc.relative_alt = 0;
|
||||
}
|
||||
|
||||
plane.set_guided_WP();
|
||||
|
@ -1435,18 +1435,18 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|||
if (pos_target.type_mask & alt_mask)
|
||||
{
|
||||
cmd.content.location.alt = pos_target.alt * 100;
|
||||
cmd.content.location.flags.relative_alt = false;
|
||||
cmd.content.location.flags.terrain_alt = false;
|
||||
cmd.content.location.relative_alt = false;
|
||||
cmd.content.location.terrain_alt = false;
|
||||
switch (pos_target.coordinate_frame)
|
||||
{
|
||||
case MAV_FRAME_GLOBAL_INT:
|
||||
break; //default to MSL altitude
|
||||
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
|
||||
cmd.content.location.flags.relative_alt = true;
|
||||
cmd.content.location.relative_alt = true;
|
||||
break;
|
||||
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
|
||||
cmd.content.location.flags.relative_alt = true;
|
||||
cmd.content.location.flags.terrain_alt = true;
|
||||
cmd.content.location.relative_alt = true;
|
||||
cmd.content.location.terrain_alt = true;
|
||||
break;
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT");
|
||||
|
|
|
@ -186,7 +186,7 @@ void Plane::set_target_altitude_current_adjusted(void)
|
|||
void Plane::set_target_altitude_location(const Location &loc)
|
||||
{
|
||||
target_altitude.amsl_cm = loc.alt;
|
||||
if (loc.flags.relative_alt) {
|
||||
if (loc.relative_alt) {
|
||||
target_altitude.amsl_cm += home.alt;
|
||||
}
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
|
@ -196,10 +196,10 @@ void Plane::set_target_altitude_location(const Location &loc)
|
|||
terrain altitude
|
||||
*/
|
||||
float height;
|
||||
if (loc.flags.terrain_alt && terrain.height_above_terrain(height, true)) {
|
||||
if (loc.terrain_alt && terrain.height_above_terrain(height, true)) {
|
||||
target_altitude.terrain_following = true;
|
||||
target_altitude.terrain_alt_cm = loc.alt;
|
||||
if (!loc.flags.relative_alt) {
|
||||
if (!loc.relative_alt) {
|
||||
// it has home added, remove it
|
||||
target_altitude.terrain_alt_cm -= home.alt;
|
||||
}
|
||||
|
@ -359,7 +359,7 @@ void Plane::set_offset_altitude_location(const Location &loc)
|
|||
terrain altitude
|
||||
*/
|
||||
float height;
|
||||
if (loc.flags.terrain_alt &&
|
||||
if (loc.terrain_alt &&
|
||||
target_altitude.terrain_following &&
|
||||
terrain.height_above_terrain(height, true)) {
|
||||
target_altitude.offset_cm = target_altitude.terrain_alt_cm - (height * 100);
|
||||
|
@ -396,10 +396,10 @@ bool Plane::above_location_current(const Location &loc)
|
|||
{
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
float terrain_alt;
|
||||
if (loc.flags.terrain_alt &&
|
||||
if (loc.terrain_alt &&
|
||||
terrain.height_above_terrain(terrain_alt, true)) {
|
||||
float loc_alt = loc.alt*0.01f;
|
||||
if (!loc.flags.relative_alt) {
|
||||
if (!loc.relative_alt) {
|
||||
loc_alt -= home.alt*0.01f;
|
||||
}
|
||||
return terrain_alt > loc_alt;
|
||||
|
@ -407,7 +407,7 @@ bool Plane::above_location_current(const Location &loc)
|
|||
#endif
|
||||
|
||||
float loc_alt_cm = loc.alt;
|
||||
if (loc.flags.relative_alt) {
|
||||
if (loc.relative_alt) {
|
||||
loc_alt_cm += home.alt;
|
||||
}
|
||||
return current_loc.alt > loc_alt_cm;
|
||||
|
@ -421,7 +421,7 @@ void Plane::setup_terrain_target_alt(Location &loc)
|
|||
{
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
if (g.terrain_follow) {
|
||||
loc.flags.terrain_alt = true;
|
||||
loc.terrain_alt = true;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@ -471,14 +471,14 @@ float Plane::mission_alt_offset(void)
|
|||
float Plane::height_above_target(void)
|
||||
{
|
||||
float target_alt = next_WP_loc.alt*0.01;
|
||||
if (!next_WP_loc.flags.relative_alt) {
|
||||
if (!next_WP_loc.relative_alt) {
|
||||
target_alt -= ahrs.get_home().alt*0.01f;
|
||||
}
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
// also record the terrain altitude if possible
|
||||
float terrain_altitude;
|
||||
if (next_WP_loc.flags.terrain_alt &&
|
||||
if (next_WP_loc.terrain_alt &&
|
||||
terrain.height_above_terrain(terrain_altitude, true)) {
|
||||
return terrain_altitude - target_alt;
|
||||
}
|
||||
|
|
|
@ -34,14 +34,14 @@ void Plane::set_next_WP(const struct Location &loc)
|
|||
// additionally treat zero altitude as current altitude
|
||||
if (next_WP_loc.alt == 0) {
|
||||
next_WP_loc.alt = current_loc.alt;
|
||||
next_WP_loc.flags.relative_alt = false;
|
||||
next_WP_loc.flags.terrain_alt = false;
|
||||
next_WP_loc.relative_alt = false;
|
||||
next_WP_loc.terrain_alt = false;
|
||||
}
|
||||
}
|
||||
|
||||
// convert relative alt to absolute alt
|
||||
if (next_WP_loc.flags.relative_alt) {
|
||||
next_WP_loc.flags.relative_alt = false;
|
||||
if (next_WP_loc.relative_alt) {
|
||||
next_WP_loc.relative_alt = false;
|
||||
next_WP_loc.alt += home.alt;
|
||||
}
|
||||
|
||||
|
@ -68,7 +68,7 @@ void Plane::set_next_WP(const struct Location &loc)
|
|||
|
||||
void Plane::set_guided_WP(void)
|
||||
{
|
||||
if (aparm.loiter_radius < 0 || guided_WP_loc.flags.loiter_ccw) {
|
||||
if (aparm.loiter_radius < 0 || guided_WP_loc.loiter_ccw) {
|
||||
loiter.direction = -1;
|
||||
} else {
|
||||
loiter.direction = 1;
|
||||
|
|
|
@ -437,7 +437,7 @@ void Plane::do_landing_vtol_approach(const AP_Mission::Mission_Command& cmd)
|
|||
|
||||
void Plane::loiter_set_direction_wp(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
if (cmd.content.location.flags.loiter_ccw) {
|
||||
if (cmd.content.location.loiter_ccw) {
|
||||
loiter.direction = -1;
|
||||
} else {
|
||||
loiter.direction = 1;
|
||||
|
@ -1122,7 +1122,7 @@ bool Plane::verify_loiter_heading(bool init)
|
|||
// Want to head in a straight line from _here_ to the next waypoint instead of center of loiter wp
|
||||
|
||||
// 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
|
||||
if (next_WP_loc.flags.loiter_xtrack) {
|
||||
if (next_WP_loc.loiter_xtrack) {
|
||||
next_WP_loc = current_loc;
|
||||
}
|
||||
return true;
|
||||
|
|
|
@ -396,6 +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));
|
||||
if (g.fence_retalt > 0) {
|
||||
//fly to the return point using fence_retalt
|
||||
guided_WP_loc.alt = home.alt + 100.0f*g.fence_retalt;
|
||||
|
@ -407,7 +408,6 @@ void Plane::geofence_check(bool altitude_check_only)
|
|||
// min and max
|
||||
guided_WP_loc.alt = home.alt + 100.0f*(g.fence_minalt + g.fence_maxalt)/2;
|
||||
}
|
||||
guided_WP_loc.options = 0;
|
||||
guided_WP_loc.lat = geofence_state->boundary[0].x;
|
||||
guided_WP_loc.lng = geofence_state->boundary[0].y;
|
||||
}
|
||||
|
|
|
@ -206,7 +206,7 @@ void Plane::update_loiter(uint16_t radius)
|
|||
if (radius <= 1) {
|
||||
// if radius is <=1 then use the general loiter radius. if it's small, use default
|
||||
radius = (abs(aparm.loiter_radius) <= 1) ? LOITER_RADIUS_DEFAULT : abs(aparm.loiter_radius);
|
||||
if (next_WP_loc.flags.loiter_ccw == 1) {
|
||||
if (next_WP_loc.loiter_ccw == 1) {
|
||||
loiter.direction = -1;
|
||||
} else {
|
||||
loiter.direction = (aparm.loiter_radius < 0) ? -1 : 1;
|
||||
|
|
Loading…
Reference in New Issue