From 95d68b0cf52bcc4cee5622415cfdbe69a8eb657d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 15 Mar 2019 13:26:01 +0900 Subject: [PATCH] Rover: reached_destination becomes const --- APMrover2/mode.h | 10 +++++----- APMrover2/mode_auto.cpp | 2 +- APMrover2/mode_guided.cpp | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/APMrover2/mode.h b/APMrover2/mode.h index 2dffe06bc3..906b5c2ea6 100644 --- a/APMrover2/mode.h +++ b/APMrover2/mode.h @@ -107,7 +107,7 @@ public: bool set_desired_location_NED(const Vector3f& destination, float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN); // true if vehicle has reached desired location. defaults to true because this is normally used by missions and we do not want the mission to become stuck - virtual bool reached_destination() { return true; } + virtual bool reached_destination() const { return true; } // set desired heading and speed - supported in Auto and Guided modes virtual void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed); @@ -265,7 +265,7 @@ public: // set desired location, heading and speed void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN) override; - bool reached_destination() override; + bool reached_destination() const override; // heading and speed control void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed) override; @@ -378,7 +378,7 @@ public: float get_distance_to_destination() const override; // return true if vehicle has reached destination - bool reached_destination() override; + bool reached_destination() const override; // set desired location, heading and speed void set_desired_location(const struct Location& destination, float next_leg_bearing_cd = MODE_NEXT_HEADING_UNKNOWN) override; @@ -507,7 +507,7 @@ public: bool is_autopilot_mode() const override { return true; } float get_distance_to_destination() const override { return _distance_to_destination; } - bool reached_destination() override { return _reached_destination; } + bool reached_destination() const override { return _reached_destination; } protected: @@ -528,7 +528,7 @@ public: bool is_autopilot_mode() const override { return true; } float get_distance_to_destination() const override { return _distance_to_destination; } - bool reached_destination() override { return smart_rtl_state == SmartRTL_StopAtHome; } + bool reached_destination() const override { return smart_rtl_state == SmartRTL_StopAtHome; } // save current position for use by the smart_rtl flight mode void save_position(); diff --git a/APMrover2/mode_auto.cpp b/APMrover2/mode_auto.cpp index 902522a11e..01af642c98 100644 --- a/APMrover2/mode_auto.cpp +++ b/APMrover2/mode_auto.cpp @@ -124,7 +124,7 @@ void ModeAuto::set_desired_location(const struct Location& destination, float ne } // return true if vehicle has reached or even passed destination -bool ModeAuto::reached_destination() +bool ModeAuto::reached_destination() const { switch (_submode) { case Auto_WP: diff --git a/APMrover2/mode_guided.cpp b/APMrover2/mode_guided.cpp index 40c8dda32b..429b7d720c 100644 --- a/APMrover2/mode_guided.cpp +++ b/APMrover2/mode_guided.cpp @@ -117,7 +117,7 @@ float ModeGuided::get_distance_to_destination() const } // return true if vehicle has reached or even passed destination -bool ModeGuided::reached_destination() +bool ModeGuided::reached_destination() const { switch (_guided_mode) { case Guided_WP: