2017-02-13 21:30:32 -04:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
#include "GCS_Mavlink.h"
|
|
|
|
|
|
|
|
class GCS_Tracker : public GCS
|
|
|
|
{
|
|
|
|
friend class Tracker; // for access to _chan in parameter declarations
|
2018-03-17 03:38:43 -03:00
|
|
|
friend class GCS_MAVLINK_Tracker;
|
2017-02-13 21:30:32 -04:00
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
// return the number of valid GCS objects
|
|
|
|
uint8_t num_gcs() const override { return ARRAY_SIZE(_chan); };
|
|
|
|
|
|
|
|
// return GCS link at offset ofs
|
2019-06-24 23:56:55 -03:00
|
|
|
GCS_MAVLINK_Tracker &chan(uint8_t ofs) override {
|
|
|
|
if (ofs >= num_gcs()) {
|
|
|
|
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
|
|
|
|
ofs = 0;
|
|
|
|
}
|
|
|
|
return _chan[ofs];
|
|
|
|
}
|
|
|
|
const GCS_MAVLINK_Tracker &chan(uint8_t ofs) const override {
|
|
|
|
if (ofs >= num_gcs()) {
|
|
|
|
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
|
|
|
|
ofs = 0;
|
|
|
|
}
|
|
|
|
return _chan[ofs];
|
|
|
|
}
|
2017-02-13 21:30:32 -04:00
|
|
|
|
2019-02-19 20:18:12 -04:00
|
|
|
void update_vehicle_sensor_status_flags() override;
|
2019-02-13 20:42:43 -04:00
|
|
|
|
2019-03-01 20:08:01 -04:00
|
|
|
uint32_t custom_mode() const override;
|
|
|
|
MAV_TYPE frame_type() const override;
|
|
|
|
|
2017-02-13 21:30:32 -04:00
|
|
|
private:
|
|
|
|
|
|
|
|
void request_datastream_position(uint8_t sysid, uint8_t compid);
|
|
|
|
void request_datastream_airpressure(uint8_t sysid, uint8_t compid);
|
|
|
|
|
|
|
|
GCS_MAVLINK_Tracker _chan[MAVLINK_COMM_NUM_BUFFERS];
|
|
|
|
|
|
|
|
};
|