Browse Source

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

This allows removing duplicated code
master
Dr.-Ing. Amilcar do Carmo Lucas 6 years ago committed by Peter Barker
parent
commit
36d755a48a
  1. 6
      APMrover2/GCS_Mavlink.cpp
  2. 2
      APMrover2/commands.cpp
  3. 6
      APMrover2/mode.cpp
  4. 2
      APMrover2/mode_auto.cpp
  5. 2
      APMrover2/mode_guided.cpp
  6. 2
      APMrover2/mode_loiter.cpp
  7. 2
      APMrover2/mode_rtl.cpp
  8. 2
      APMrover2/mode_smart_rtl.cpp

6
APMrover2/GCS_Mavlink.cpp

@ -810,19 +810,19 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) @@ -810,19 +810,19 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
const float ne_x = packet.x * rover.ahrs.cos_yaw() - packet.y * rover.ahrs.sin_yaw();
const float ne_y = packet.x * rover.ahrs.sin_yaw() + packet.y * rover.ahrs.cos_yaw();
// add offset to current location
location_offset(target_loc, ne_x, ne_y);
target_loc.offset(ne_x, ne_y);
}
break;
case MAV_FRAME_LOCAL_OFFSET_NED:
// add offset to current location
location_offset(target_loc, packet.x, packet.y);
target_loc.offset(packet.x, packet.y);
break;
default:
// MAV_FRAME_LOCAL_NED interpret as an offset from home
target_loc = rover.ahrs.get_home();
location_offset(target_loc, packet.x, packet.y);
target_loc.offset(packet.x, packet.y);
break;
}
}

2
APMrover2/commands.cpp

@ -71,7 +71,7 @@ void Rover::update_home() @@ -71,7 +71,7 @@ void Rover::update_home()
barometer.update_calibration();
if (ahrs.home_is_set() &&
get_distance(loc, ahrs.get_home()) < DISTANCE_HOME_MINCHANGE) {
loc.get_distance(ahrs.get_home()) < DISTANCE_HOME_MINCHANGE) {
// insufficiently moved from current home - don't change it
return;
}

6
APMrover2/mode.cpp

@ -199,7 +199,7 @@ void Mode::set_desired_location(const struct Location& destination, float next_l @@ -199,7 +199,7 @@ void Mode::set_desired_location(const struct Location& destination, float next_l
_destination = destination;
// initialise distance
_distance_to_destination = get_distance(_origin, _destination);
_distance_to_destination = _origin.get_distance(_destination);
_reached_destination = false;
// set final desired speed
@ -231,7 +231,7 @@ bool Mode::set_desired_location_NED(const Vector3f& destination, float next_leg_ @@ -231,7 +231,7 @@ bool Mode::set_desired_location_NED(const Vector3f& destination, float next_leg_
return false;
}
// apply offset
location_offset(destination_ned, destination.x, destination.y);
destination_ned.offset(destination.x, destination.y);
set_desired_location(destination_ned, next_leg_bearing_cd);
return true;
}
@ -552,7 +552,7 @@ void Mode::calc_stopping_location(Location& stopping_loc) @@ -552,7 +552,7 @@ void Mode::calc_stopping_location(Location& stopping_loc)
// calculate stopping position from current location in meters
const Vector2f stopping_offset = velocity.normalized() * stopping_dist;
location_offset(stopping_loc, stopping_offset.x, stopping_offset.y);
stopping_loc.offset(stopping_offset.x, stopping_offset.y);
}
Mode *Rover::mode_from_mode_num(const enum Mode::Number num)

2
APMrover2/mode_auto.cpp

@ -36,7 +36,7 @@ void ModeAuto::update() @@ -36,7 +36,7 @@ void ModeAuto::update()
switch (_submode) {
case Auto_WP:
{
_distance_to_destination = get_distance(rover.current_loc, _destination);
_distance_to_destination = rover.current_loc.get_distance(_destination);
const bool near_wp = _distance_to_destination <= rover.g.waypoint_radius;
// check if we've reached the destination
if (!_reached_destination && (near_wp || location_passed_point(rover.current_loc, _origin, _destination))) {

2
APMrover2/mode_guided.cpp

@ -18,7 +18,7 @@ void ModeGuided::update() @@ -18,7 +18,7 @@ void ModeGuided::update()
switch (_guided_mode) {
case Guided_WP:
{
_distance_to_destination = get_distance(rover.current_loc, _destination);
_distance_to_destination = rover.current_loc.get_distance(_destination);
const bool near_wp = _distance_to_destination <= rover.g.waypoint_radius;
// check if we've reached the destination
if (!_reached_destination && (near_wp || location_passed_point(rover.current_loc, _origin, _destination))) {

2
APMrover2/mode_loiter.cpp

@ -21,7 +21,7 @@ bool ModeLoiter::_enter() @@ -21,7 +21,7 @@ bool ModeLoiter::_enter()
void ModeLoiter::update()
{
// get distance (in meters) to destination
_distance_to_destination = get_distance(rover.current_loc, _destination);
_distance_to_destination = rover.current_loc.get_distance(_destination);
// if within loiter radius slew desired speed towards zero and use existing desired heading
if (_distance_to_destination <= g2.loit_radius) {

2
APMrover2/mode_rtl.cpp

@ -25,7 +25,7 @@ bool ModeRTL::_enter() @@ -25,7 +25,7 @@ bool ModeRTL::_enter()
void ModeRTL::update()
{
// calculate distance to home
_distance_to_destination = get_distance(rover.current_loc, _destination);
_distance_to_destination = rover.current_loc.get_distance(_destination);
const bool near_wp = _distance_to_destination <= rover.g.waypoint_radius;
// check if we've reached the destination
if (!_reached_destination && (near_wp || location_passed_point(rover.current_loc, _origin, _destination))) {

2
APMrover2/mode_smart_rtl.cpp

@ -59,7 +59,7 @@ void ModeSmartRTL::update() @@ -59,7 +59,7 @@ void ModeSmartRTL::update()
}
}
// check if we've reached the next point
_distance_to_destination = get_distance(rover.current_loc, _destination);
_distance_to_destination = rover.current_loc.get_distance(_destination);
if (_distance_to_destination <= rover.g.waypoint_radius || location_passed_point(rover.current_loc, _origin, _destination)) {
_load_point = true;
}

Loading…
Cancel
Save