2017-02-13 07:00:19 -04:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
#include "GCS_Mavlink.h"
|
|
|
|
|
|
|
|
class GCS_Rover : public GCS
|
|
|
|
{
|
|
|
|
friend class Rover; // for access to _chan in parameter declarations
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
// return GCS link at offset ofs
|
2019-06-19 08:26:19 -03:00
|
|
|
GCS_MAVLINK_Rover *chan(const uint8_t ofs) override {
|
|
|
|
if (ofs > _num_gcs) {
|
2019-06-24 23:56:48 -03:00
|
|
|
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
|
2019-06-19 08:26:19 -03:00
|
|
|
return nullptr;
|
2019-06-24 23:56:48 -03:00
|
|
|
}
|
2019-06-19 08:26:19 -03:00
|
|
|
return (GCS_MAVLINK_Rover*)_chan[ofs];
|
2019-06-24 23:56:48 -03:00
|
|
|
}
|
2017-07-08 01:41:53 -03:00
|
|
|
// return GCS link at offset ofs
|
2019-06-19 08:26:19 -03:00
|
|
|
const GCS_MAVLINK_Rover *chan(const uint8_t ofs) const override {
|
|
|
|
if (ofs > _num_gcs) {
|
2019-06-24 23:56:48 -03:00
|
|
|
AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
|
2019-06-19 08:26:19 -03:00
|
|
|
return nullptr;
|
2019-06-24 23:56:48 -03:00
|
|
|
}
|
2019-06-19 08:26:19 -03:00
|
|
|
return (GCS_MAVLINK_Rover*)_chan[ofs];
|
2019-06-24 23:56:48 -03:00
|
|
|
}
|
2017-02-13 07:00:19 -04:00
|
|
|
|
2019-02-12 07:55:31 -04:00
|
|
|
uint32_t custom_mode() const override;
|
|
|
|
MAV_TYPE frame_type() const override;
|
|
|
|
|
2019-03-01 07:50:14 -04:00
|
|
|
bool vehicle_initialised() const override;
|
|
|
|
|
2019-02-19 19:16:12 -04:00
|
|
|
void update_vehicle_sensor_status_flags(void) override;
|
2019-02-13 20:42:31 -04:00
|
|
|
|
2019-03-01 19:25:26 -04:00
|
|
|
bool simple_input_active() const override;
|
|
|
|
bool supersimple_input_active() const override;
|
|
|
|
|
2019-06-19 08:26:19 -03:00
|
|
|
protected:
|
2017-02-13 07:00:19 -04:00
|
|
|
|
2020-02-11 21:01:17 -04:00
|
|
|
uint8_t sysid_this_mav() const override;
|
|
|
|
|
2019-06-19 08:26:19 -03:00
|
|
|
GCS_MAVLINK_Rover *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
|
|
|
AP_HAL::UARTDriver &uart) override {
|
|
|
|
return new GCS_MAVLINK_Rover(params, uart);
|
|
|
|
}
|
2017-02-13 07:00:19 -04:00
|
|
|
|
|
|
|
};
|