AP_AIS: remove incorrect use of strncat
[ardupilot.git] / ArduCopter / GCS_Copter.h
blob4b5e9ee21a7202d8299e7b4bc287734b23085f34
1 #pragma once
3 #include <GCS_MAVLink/GCS.h>
4 #include "GCS_MAVLink_Copter.h"
6 class GCS_Copter : public GCS
8 friend class Copter; // for access to _chan in parameter declarations
10 public:
12 // the following define expands to a pair of methods to retrieve a
13 // pointer to an object of the correct subclass for the link at
14 // offset ofs. These are of the form:
15 // GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override;
16 // const GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override const;
17 GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(GCS_MAVLINK_Copter);
19 void update_vehicle_sensor_status_flags(void) override;
21 uint32_t custom_mode() const override;
22 MAV_TYPE frame_type() const override;
24 const char* frame_string() const override;
26 bool vehicle_initialised() const override;
28 bool simple_input_active() const override;
29 bool supersimple_input_active() const override;
31 uint8_t sysid_this_mav() const override;
33 protected:
36 // minimum amount of time (in microseconds) that must remain in
37 // the main scheduler loop before we are allowed to send any
38 // mavlink messages. We want to prioritise the main flight
39 // control loop over communications
40 uint16_t min_loop_time_remaining_for_message_send_us() const override {
41 return 250;
44 GCS_MAVLINK_Copter *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
45 AP_HAL::UARTDriver &uart) override {
46 return NEW_NOTHROW GCS_MAVLINK_Copter(params, uart);