GCS_MAVLink: move sensor flags to be a GCS thing rather than a GCS_MAVLINK thing
These are a per-vehicle thing, not a per-mavlink-backend thing.
This commit is contained in:
parent
624f196fb3
commit
cb33f290a7
@ -301,7 +301,6 @@ protected:
|
||||
virtual MAV_MODE base_mode() const = 0;
|
||||
virtual uint32_t custom_mode() const = 0;
|
||||
virtual MAV_STATE system_status() const = 0;
|
||||
virtual void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health) = 0;
|
||||
|
||||
bool waypoint_receiving; // currently receiving
|
||||
// the following two variables are only here because of Tracker
|
||||
@ -775,6 +774,8 @@ public:
|
||||
// update uart pass-thru
|
||||
void update_passthru();
|
||||
|
||||
virtual void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health) = 0;
|
||||
|
||||
private:
|
||||
|
||||
static GCS *_singleton;
|
||||
|
@ -3804,7 +3804,7 @@ void GCS_MAVLINK::send_sys_status()
|
||||
uint32_t control_sensors_enabled;
|
||||
uint32_t control_sensors_health;
|
||||
|
||||
get_sensor_status_flags(control_sensors_present, control_sensors_enabled, control_sensors_health);
|
||||
gcs().get_sensor_status_flags(control_sensors_present, control_sensors_enabled, control_sensors_health);
|
||||
|
||||
mavlink_msg_sys_status_send(
|
||||
chan,
|
||||
|
@ -32,7 +32,6 @@ protected:
|
||||
MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
|
||||
uint32_t custom_mode() const override { return 3; } // magic number
|
||||
MAV_STATE system_status() const override { return MAV_STATE_CALIBRATING; }
|
||||
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health) override { present = 0; enabled = 0; health = 0; }
|
||||
|
||||
bool set_home_to_current_location(bool lock) override { return false; }
|
||||
bool set_home(const Location& loc, bool lock) override { return false; }
|
||||
@ -54,4 +53,6 @@ class GCS_Dummy : public GCS
|
||||
const GCS_MAVLINK_Dummy &chan(const uint8_t ofs) const override { return dummy_backend; };
|
||||
|
||||
void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text) { hal.console->printf("TOGCS: %s\n", text); }
|
||||
|
||||
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health) override { present = 0; enabled = 0; health = 0; }
|
||||
};
|
||||
|
@ -38,7 +38,6 @@ protected:
|
||||
MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
|
||||
uint32_t custom_mode() const override { return 3; } // magic number
|
||||
MAV_STATE system_status() const override { return MAV_STATE_CALIBRATING; }
|
||||
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health) override { present = 0; enabled = 0; health = 0; }
|
||||
void send_nav_controller_output() const override {};
|
||||
|
||||
bool set_home_to_current_location(bool lock) override { return false; }
|
||||
|
Loading…
Reference in New Issue
Block a user