Browse Source

Plane: replace location_offset() and get_distance() function calls with Location object member function calls

This allows removing duplicated code
mission-4.1.18
Dr.-Ing. Amilcar do Carmo Lucas 6 years ago committed by Peter Barker
parent
commit
f430fd14f6
  1. 2
      ArduPlane/ArduPlane.cpp
  2. 2
      ArduPlane/altitude.cpp
  3. 2
      ArduPlane/avoidance_adsb.cpp
  4. 14
      ArduPlane/commands_logic.cpp
  5. 2
      ArduPlane/is_flying.cpp
  6. 6
      ArduPlane/navigation.cpp

2
ArduPlane/ArduPlane.cpp

@ -826,7 +826,7 @@ void Plane::update_alt() @@ -826,7 +826,7 @@ void Plane::update_alt()
float distance_beyond_land_wp = 0;
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND && location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
distance_beyond_land_wp = get_distance(current_loc, next_WP_loc);
distance_beyond_land_wp = current_loc.get_distance(next_WP_loc);
}
bool soaring_active = false;

2
ArduPlane/altitude.cpp

@ -65,7 +65,7 @@ void Plane::setup_glide_slope(void) @@ -65,7 +65,7 @@ void Plane::setup_glide_slope(void)
{
// establish the distance we are travelling to the next waypoint,
// for calculating out rate of change of altitude
auto_state.wp_distance = get_distance(current_loc, next_WP_loc);
auto_state.wp_distance = current_loc.get_distance(next_WP_loc);
auto_state.wp_proportion = location_path_proportion(current_loc,
prev_WP_loc, next_WP_loc);
SpdHgt_Controller->set_path_proportion(auto_state.wp_proportion);

2
ArduPlane/avoidance_adsb.cpp

@ -194,7 +194,7 @@ bool AP_Avoidance_Plane::handle_avoidance_horizontal(const AP_Avoidance::Obstacl @@ -194,7 +194,7 @@ bool AP_Avoidance_Plane::handle_avoidance_horizontal(const AP_Avoidance::Obstacl
velocity_neu *= 10000;
// set target
location_offset(plane.guided_WP_loc, velocity_neu.x, velocity_neu.y);
plane.guided_WP_loc.offset(velocity_neu.x, velocity_neu.y);
return true;
}

14
ArduPlane/commands_logic.cpp

@ -582,7 +582,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd) @@ -582,7 +582,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
uint8_t cmd_acceptance_distance = LOWBYTE(cmd.p1); // radius in meters to accept reaching the wp
if (cmd_passby > 0) {
float dist = get_distance(prev_WP_loc, flex_next_WP_loc);
float dist = prev_WP_loc.get_distance(flex_next_WP_loc);
if (!is_zero(dist)) {
float factor = (dist + cmd_passby) / dist;
@ -624,7 +624,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd) @@ -624,7 +624,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
if (auto_state.wp_distance <= acceptance_distance_m) {
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%i dist %um",
(unsigned)mission.get_current_nav_cmd().index,
(unsigned)get_distance(current_loc, flex_next_WP_loc));
(unsigned)current_loc.get_distance(flex_next_WP_loc));
return true;
}
@ -632,7 +632,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd) @@ -632,7 +632,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
if (location_passed_point(current_loc, prev_WP_loc, flex_next_WP_loc)) {
gcs().send_text(MAV_SEVERITY_INFO, "Passed waypoint #%i dist %um",
(unsigned)mission.get_current_nav_cmd().index,
(unsigned)get_distance(current_loc, flex_next_WP_loc));
(unsigned)current_loc.get_distance(flex_next_WP_loc));
return true;
}
@ -770,7 +770,7 @@ bool Plane::verify_continue_and_change_alt() @@ -770,7 +770,7 @@ bool Plane::verify_continue_and_change_alt()
}
else {
// Is the next_WP less than 200 m away?
if (get_distance(current_loc, next_WP_loc) < 200.0f) {
if (current_loc.get_distance(next_WP_loc) < 200.0f) {
//push another 300 m down the line
int32_t next_wp_bearing_cd = get_bearing_cd(prev_WP_loc, next_WP_loc);
location_update(next_WP_loc, next_wp_bearing_cd * 0.01f, 300.0f);
@ -976,8 +976,8 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) @@ -976,8 +976,8 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)
// validate that the vehicle is at least the expected distance away from the loiter point
// require an angle total of at least 2 centidegrees, due to special casing of 1 centidegree
if (((fabsf(get_distance(cmd.content.location, current_loc) - radius) > 5.0f) &&
(get_distance(cmd.content.location, current_loc) < radius)) ||
if (((fabsf(cmd.content.location.get_distance(current_loc) - radius) > 5.0f) &&
(cmd.content.location.get_distance(current_loc) < radius)) ||
(loiter.sum_cd < 2)) {
nav_controller->update_loiter(cmd.content.location, radius, direction);
break;
@ -1055,7 +1055,7 @@ bool Plane::verify_loiter_heading(bool init) @@ -1055,7 +1055,7 @@ bool Plane::verify_loiter_heading(bool init)
return true;
}
if (get_distance(next_WP_loc, next_nav_cmd.content.location) < abs(aparm.loiter_radius)) {
if (next_WP_loc.get_distance(next_nav_cmd.content.location) < abs(aparm.loiter_radius)) {
/* Whenever next waypoint is within the loiter radius,
maintaining loiter would prevent us from ever pointing toward the next waypoint.
Hence break out of loiter immediately

2
ArduPlane/is_flying.cpp

@ -223,7 +223,7 @@ void Plane::crash_detection_update(void) @@ -223,7 +223,7 @@ void Plane::crash_detection_update(void)
// did we "crash" within 75m of the landing location? Probably just a hard landing
crashed_near_land_waypoint =
get_distance(current_loc, mission.get_current_nav_cmd().content.location) < 75;
current_loc.get_distance(mission.get_current_nav_cmd().content.location) < 75;
// trigger hard landing event right away, or never again. This inhibits a false hard landing
// event when, for example, a minute after a good landing you pick the plane up and

6
ArduPlane/navigation.cpp

@ -86,7 +86,7 @@ void Plane::navigate() @@ -86,7 +86,7 @@ void Plane::navigate()
// waypoint distance from plane
// ----------------------------
auto_state.wp_distance = get_distance(current_loc, next_WP_loc);
auto_state.wp_distance = current_loc.get_distance(next_WP_loc);
auto_state.wp_proportion = location_path_proportion(current_loc,
prev_WP_loc, next_WP_loc);
SpdHgt_Controller->set_path_proportion(auto_state.wp_proportion);
@ -225,7 +225,7 @@ void Plane::update_loiter(uint16_t radius) @@ -225,7 +225,7 @@ void Plane::update_loiter(uint16_t radius)
} else if ((loiter.start_time_ms == 0 &&
(control_mode == AUTO || control_mode == GUIDED) &&
auto_state.crosstrack &&
get_distance(current_loc, next_WP_loc) > radius*3) ||
current_loc.get_distance(next_WP_loc) > radius*3) ||
(control_mode == RTL && quadplane.available() && quadplane.rtl_mode == 1)) {
/*
if never reached loiter point and using crosstrack and somewhat far away from loiter point
@ -285,7 +285,7 @@ void Plane::update_cruise() @@ -285,7 +285,7 @@ void Plane::update_cruise()
// always look 1km ahead
location_update(next_WP_loc,
cruise_state.locked_heading_cd*0.01f,
get_distance(prev_WP_loc, current_loc) + 1000);
prev_WP_loc.get_distance(current_loc) + 1000);
nav_controller->update_waypoint(prev_WP_loc, next_WP_loc);
}
}

Loading…
Cancel
Save