Plane: use sanitize method rather than location_sanitize function

This commit is contained in:
Peter Barker 2019-03-27 11:34:40 +11:00 committed by Andrew Tridgell
parent dabf92f5b6
commit a372428ec5
2 changed files with 6 additions and 6 deletions

View File

@ -776,7 +776,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
requested_position.loiter_ccw = 1;
}
if (location_sanitize(plane.current_loc, requested_position)) {
if (requested_position.sanitize(plane.current_loc)) {
// if the location wasn't already sane don't load it
return MAV_RESULT_FAILED; // failed as the location is not valid
}

View File

@ -408,7 +408,7 @@ void Plane::do_landing_vtol_approach(const AP_Mission::Mission_Command& cmd)
{
//set target alt
Location loc = cmd.content.location;
location_sanitize(current_loc, loc);
loc.sanitize(current_loc);
set_next_WP(loc);
// only set the direction if the quadplane landing radius override is not 0
@ -435,7 +435,7 @@ void Plane::loiter_set_direction_wp(const AP_Mission::Mission_Command& cmd)
void Plane::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
{
Location cmdloc = cmd.content.location;
location_sanitize(current_loc, cmdloc);
cmdloc.sanitize(current_loc);
set_next_WP(cmdloc);
loiter_set_direction_wp(cmd);
}
@ -443,7 +443,7 @@ void Plane::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
void Plane::do_loiter_turns(const AP_Mission::Mission_Command& cmd)
{
Location cmdloc = cmd.content.location;
location_sanitize(current_loc, cmdloc);
cmdloc.sanitize(current_loc);
set_next_WP(cmdloc);
loiter_set_direction_wp(cmd);
@ -454,7 +454,7 @@ void Plane::do_loiter_turns(const AP_Mission::Mission_Command& cmd)
void Plane::do_loiter_time(const AP_Mission::Mission_Command& cmd)
{
Location cmdloc = cmd.content.location;
location_sanitize(current_loc, cmdloc);
cmdloc.sanitize(current_loc);
set_next_WP(cmdloc);
loiter_set_direction_wp(cmd);
@ -500,7 +500,7 @@ void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd)
{
//set target alt
Location loc = cmd.content.location;
location_sanitize(current_loc, loc);
loc.sanitize(current_loc);
set_next_WP(loc);
loiter_set_direction_wp(cmd);