Browse Source

Rover: eliminate global static GCS_MAVLINK::send_home_all

mission-4.1.18
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
aeed1f0ff4
  1. 2
      APMrover2/GCS_Rover.h
  2. 4
      APMrover2/commands.cpp

2
APMrover2/GCS_Rover.h

@ -14,6 +14,8 @@ public:
// return GCS link at offset ofs // return GCS link at offset ofs
GCS_MAVLINK_Rover &chan(const uint8_t ofs) override { return _chan[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: private:

4
APMrover2/commands.cpp

@ -136,7 +136,7 @@ bool Rover::set_home(const Location& loc, bool lock)
Log_Write_Home_And_Origin(); Log_Write_Home_And_Origin();
// send new home location to GCS // send new home location to GCS
GCS_MAVLINK::send_home_all(loc); gcs().send_home(loc);
// send text of home position to ground stations // send text of home position to ground stations
gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %.2fm", 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) { if (get_distance(loc, ahrs.get_home()) > DISTANCE_HOME_MAX) {
ahrs.set_home(loc); ahrs.set_home(loc);
Log_Write_Home_And_Origin(); Log_Write_Home_And_Origin();
GCS_MAVLINK::send_home_all(gps.location()); gcs().send_home(gps.location());
} }
} }
} }

Loading…
Cancel
Save