Sub: move sensor flags to be a GCS thing rather than a GCS_MAVLINK thing
This commit is contained in:
parent
a3c13fc028
commit
bb706305d0
@ -206,7 +206,7 @@ void Sub::get_sensor_status_flags(uint32_t &control_sensors_present,
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCS_MAVLINK_Sub::get_sensor_status_flags(uint32_t &control_sensors_present,
|
void GCS_Sub::get_sensor_status_flags(uint32_t &control_sensors_present,
|
||||||
uint32_t &control_sensors_enabled,
|
uint32_t &control_sensors_enabled,
|
||||||
uint32_t &control_sensors_health)
|
uint32_t &control_sensors_health)
|
||||||
{
|
{
|
||||||
|
@ -52,7 +52,6 @@ private:
|
|||||||
MAV_MODE base_mode() const override;
|
MAV_MODE base_mode() const override;
|
||||||
uint32_t custom_mode() const override;
|
uint32_t custom_mode() const override;
|
||||||
MAV_STATE system_status() const override;
|
MAV_STATE system_status() const override;
|
||||||
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health);
|
|
||||||
|
|
||||||
int16_t vfr_hud_throttle() const override;
|
int16_t vfr_hud_throttle() const override;
|
||||||
|
|
||||||
|
@ -20,6 +20,8 @@ public:
|
|||||||
return _chan[ofs];
|
return _chan[ofs];
|
||||||
};
|
};
|
||||||
|
|
||||||
|
void get_sensor_status_flags(uint32_t &present, uint32_t &enabled, uint32_t &health);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
GCS_MAVLINK_Sub _chan[MAVLINK_COMM_NUM_BUFFERS];
|
GCS_MAVLINK_Sub _chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||||
|
Loading…
Reference in New Issue
Block a user