From aeed1f0ff4ac87dbb07c5f916f7f4168b733a44f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 8 Jul 2017 14:41:53 +1000 Subject: [PATCH] Rover: eliminate global static GCS_MAVLINK::send_home_all --- APMrover2/GCS_Rover.h | 2 ++ APMrover2/commands.cpp | 4 ++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/APMrover2/GCS_Rover.h b/APMrover2/GCS_Rover.h index a66e2f6b40..8c0fdfa0d2 100644 --- a/APMrover2/GCS_Rover.h +++ b/APMrover2/GCS_Rover.h @@ -14,6 +14,8 @@ public: // return GCS link at offset ofs GCS_MAVLINK_Rover &chan(const uint8_t ofs) override { return _chan[ofs]; }; + // return GCS link at offset ofs + const GCS_MAVLINK_Rover &chan(const uint8_t ofs) const override { return _chan[ofs]; }; private: diff --git a/APMrover2/commands.cpp b/APMrover2/commands.cpp index 8ab5e8b047..ce8c550390 100644 --- a/APMrover2/commands.cpp +++ b/APMrover2/commands.cpp @@ -136,7 +136,7 @@ bool Rover::set_home(const Location& loc, bool lock) Log_Write_Home_And_Origin(); // send new home location to GCS - GCS_MAVLINK::send_home_all(loc); + gcs().send_home(loc); // send text of home position to ground stations gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %.2fm", @@ -190,7 +190,7 @@ void Rover::update_home() if (get_distance(loc, ahrs.get_home()) > DISTANCE_HOME_MAX) { ahrs.set_home(loc); Log_Write_Home_And_Origin(); - GCS_MAVLINK::send_home_all(gps.location()); + gcs().send_home(gps.location()); } } }