Rover: move sensor flags to be a GCS thing rather than a GCS_MAVLINK thing

This commit is contained in:
Peter Barker 2019-02-14 11:42:31 +11:00 committed by Peter Barker
parent cb33f290a7
commit 6331efcc12
3 changed files with 3 additions and 3 deletions

View File

@ -75,7 +75,7 @@ MAV_STATE GCS_MAVLINK_Rover::system_status() const
return MAV_STATE_ACTIVE;
}
void GCS_MAVLINK_Rover::get_sensor_status_flags(uint32_t &present,
void GCS_Rover::get_sensor_status_flags(uint32_t &present,
uint32_t &enabled,
uint32_t &health)
{

View File

@ -30,8 +30,6 @@ protected:
bool vehicle_initialised() const override;
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health);
bool set_home_to_current_location(bool lock) override;
bool set_home(const Location& loc, bool lock) override;
uint64_t capabilities() const override;

View File

@ -17,6 +17,8 @@ public:
// return GCS link at offset ofs
const GCS_MAVLINK_Rover &chan(const uint8_t ofs) const override { return _chan[ofs]; };
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health);
private:
GCS_MAVLINK_Rover _chan[MAVLINK_COMM_NUM_BUFFERS];