Browse Source

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

mission-4.1.18
Peter Barker 6 years ago committed by Peter Barker
parent
commit
6331efcc12
  1. 2
      APMrover2/GCS_Mavlink.cpp
  2. 2
      APMrover2/GCS_Mavlink.h
  3. 2
      APMrover2/GCS_Rover.h

2
APMrover2/GCS_Mavlink.cpp

@ -75,7 +75,7 @@ MAV_STATE GCS_MAVLINK_Rover::system_status() const @@ -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)
{

2
APMrover2/GCS_Mavlink.h

@ -30,8 +30,6 @@ protected: @@ -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;

2
APMrover2/GCS_Rover.h

@ -17,6 +17,8 @@ public: @@ -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];

Loading…
Cancel
Save