diff --git a/APMrover2/mode.cpp b/APMrover2/mode.cpp index 5495b3f066..975b038d34 100644 --- a/APMrover2/mode.cpp +++ b/APMrover2/mode.cpp @@ -34,7 +34,7 @@ void Mode::set_desired_location(const struct Location& destination) _desired_speed = g.speed_cruise; // initialise distance - _distance_to_destination = get_distance(rover.current_loc, _destination); + _distance_to_destination = get_distance(_origin, _destination); _reached_destination = false; } diff --git a/APMrover2/mode.h b/APMrover2/mode.h index f85411f484..4cfe843e1a 100644 --- a/APMrover2/mode.h +++ b/APMrover2/mode.h @@ -106,7 +106,7 @@ protected: class AP_AHRS &ahrs; class Parameters &g; class ParametersG2 &g2; - class RC_Channel *&channel_steer; // TODO : Pointer reference ? + class RC_Channel *&channel_steer; class RC_Channel *&channel_throttle; class AP_Mission &mission; diff --git a/APMrover2/mode_guided.cpp b/APMrover2/mode_guided.cpp index a9cb495bc7..a093123551 100644 --- a/APMrover2/mode_guided.cpp +++ b/APMrover2/mode_guided.cpp @@ -133,7 +133,7 @@ void ModeGuided::set_desired_heading_delta_and_speed(float yaw_delta_cd, float t _guided_mode = ModeGuided::Guided_HeadingAndSpeed; _desired_yaw_cd = ahrs.yaw_sensor; } - set_desired_heading_and_speed(wrap_180_cd(_desired_yaw_cd+yaw_delta_cd), target_speed); + set_desired_heading_and_speed(wrap_180_cd(_desired_yaw_cd + yaw_delta_cd), target_speed); } // set desired velocity