all: use CLASS_NO_COPY() macro

This commit is contained in:
jackhong12 2022-09-30 17:50:43 +08:00 committed by Andrew Tridgell
parent 0f359c6a4e
commit 4a4f361a17
108 changed files with 114 additions and 220 deletions

View File

@ -18,8 +18,7 @@ public:
Mode() {}
// do not allow copying
Mode(const Mode &other) = delete;
Mode &operator=(const Mode&) = delete;
CLASS_NO_COPY(Mode);
// returns a unique number specific to this mode
virtual Mode::Number number() const = 0;

View File

@ -16,8 +16,7 @@ public:
}
/* Do not allow copies */
AP_Arming_Copter(const AP_Arming_Copter &other) = delete;
AP_Arming_Copter &operator=(const AP_Arming_Copter&) = delete;
CLASS_NO_COPY(AP_Arming_Copter);
bool rc_calibration_checks(bool display_failure) override;

View File

@ -23,8 +23,7 @@ public:
AP_Rally_Copter() : AP_Rally() { }
/* Do not allow copies */
AP_Rally_Copter(const AP_Rally_Copter &other) = delete;
AP_Rally_Copter &operator=(const AP_Rally_Copter&) = delete;
CLASS_NO_COPY(AP_Rally_Copter);
private:
bool is_valid(const Location &rally_point) const override;

View File

@ -12,8 +12,7 @@ public:
using AP_Avoidance::AP_Avoidance;
/* Do not allow copies */
AP_Avoidance_Copter(const AP_Avoidance_Copter &other) = delete;
AP_Avoidance_Copter &operator=(const AP_Avoidance_Copter&) = delete;
CLASS_NO_COPY(AP_Avoidance_Copter);
private:
// helper function to set modes and always succeed

View File

@ -48,8 +48,7 @@ public:
Mode(void);
// do not allow copying
Mode(const Mode &other) = delete;
Mode &operator=(const Mode&) = delete;
CLASS_NO_COPY(Mode);
// returns a unique number specific to this mode
virtual Number mode_number() const = 0;

View File

@ -15,8 +15,7 @@ public:
}
/* Do not allow copies */
AP_Arming_Plane(const AP_Arming_Plane &other) = delete;
AP_Arming_Plane &operator=(const AP_Arming_Plane&) = delete;
CLASS_NO_COPY(AP_Arming_Plane);
bool pre_arm_checks(bool report) override;
bool arm_checks(AP_Arming::Method method) override;

View File

@ -12,8 +12,7 @@ public:
using AP_Avoidance::AP_Avoidance;
/* Do not allow copies */
AP_Avoidance_Plane(const AP_Avoidance_Plane &other) = delete;
AP_Avoidance_Plane &operator=(const AP_Avoidance_Plane&) = delete;
CLASS_NO_COPY(AP_Avoidance_Plane);
protected:
// override avoidance handler

View File

@ -16,8 +16,7 @@ class Mode
public:
/* Do not allow copies */
Mode(const Mode &other) = delete;
Mode &operator=(const Mode&) = delete;
CLASS_NO_COPY(Mode);
// Auto Pilot modes
// ----------------

View File

@ -8,8 +8,7 @@ public:
AP_Arming_Sub() : AP_Arming() { }
/* Do not allow copies */
AP_Arming_Sub(const AP_Arming_Sub &other) = delete;
AP_Arming_Sub &operator=(const AP_Arming_Sub&) = delete;
CLASS_NO_COPY(AP_Arming_Sub);
bool rc_calibration_checks(bool display_failure) override;
bool pre_arm_checks(bool display_failure) override;

View File

@ -16,8 +16,7 @@ public:
}
/* Do not allow copies */
AP_Arming_Blimp(const AP_Arming_Blimp &other) = delete;
AP_Arming_Blimp &operator=(const AP_Arming_Blimp&) = delete;
CLASS_NO_COPY(AP_Arming_Blimp);
bool rc_calibration_checks(bool display_failure) override;

View File

@ -23,8 +23,7 @@ public:
Mode(void);
// do not allow copying
Mode(const Mode &other) = delete;
Mode &operator=(const Mode&) = delete;
CLASS_NO_COPY(Mode);
// child classes should override these methods
virtual bool init(bool ignore_checks)

View File

@ -13,8 +13,7 @@ public:
AP_Arming_Rover() : AP_Arming() { }
/* Do not allow copies */
AP_Arming_Rover(const AP_Arming_Rover &other) = delete;
AP_Arming_Rover &operator=(const AP_Arming_Rover&) = delete;
CLASS_NO_COPY(AP_Arming_Rover);
bool pre_arm_checks(bool report) override;
bool arm_checks(AP_Arming::Method method) override;

View File

@ -23,8 +23,7 @@ public:
AP_Rally_Rover() : AP_Rally() { }
/* Do not allow copies */
AP_Rally_Rover(const AP_Rally_Rover &other) = delete;
AP_Rally_Rover &operator=(const AP_Rally_Rover&) = delete;
CLASS_NO_COPY(AP_Rally_Rover);
private:
bool is_valid(const Location &rally_point) const override;

View File

@ -33,8 +33,7 @@ public:
Mode();
// do not allow copying
Mode(const Mode &other) = delete;
Mode &operator=(const Mode&) = delete;
CLASS_NO_COPY(Mode);
// enter this mode, returns false if we failed to enter
bool enter();

View File

@ -30,8 +30,7 @@ public:
AC_Avoid();
/* Do not allow copies */
AC_Avoid(const AC_Avoid &other) = delete;
AC_Avoid &operator=(const AC_Avoid&) = delete;
CLASS_NO_COPY(AC_Avoid);
// get singleton instance
static AC_Avoid *get_singleton() {

View File

@ -18,8 +18,7 @@ public:
AP_OAPathPlanner();
/* Do not allow copies */
AP_OAPathPlanner(const AP_OAPathPlanner &other) = delete;
AP_OAPathPlanner &operator=(const AP_OAPathPlanner&) = delete;
CLASS_NO_COPY(AP_OAPathPlanner);
// get singleton instance
static AP_OAPathPlanner *get_singleton() {

View File

@ -44,8 +44,7 @@ public:
AC_Fence();
/* Do not allow copies */
AC_Fence(const AC_Fence &other) = delete;
AC_Fence &operator=(const AC_Fence&) = delete;
CLASS_NO_COPY(AC_Fence);
void init() {
_poly_loader.init();

View File

@ -49,8 +49,8 @@ public:
AC_PolyFence_loader(AP_Int8 &total) :
_total(total) {}
AC_PolyFence_loader(const AC_PolyFence_loader &other) = delete;
AC_PolyFence_loader &operator=(const AC_PolyFence_loader&) = delete;
/* Do not allow copies */
CLASS_NO_COPY(AC_PolyFence_loader);
void init();

View File

@ -17,8 +17,7 @@ public:
}
/* Do not allow copies */
AC_InputManager(const AC_InputManager &other) = delete;
AC_InputManager &operator=(const AC_InputManager&) = delete;
CLASS_NO_COPY(AC_InputManager);
static const struct AP_Param::GroupInfo var_info[];
void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; }

View File

@ -25,8 +25,7 @@ public:
}
/* Do not allow copies */
AC_InputManager_Heli(const AC_InputManager_Heli &other) = delete;
AC_InputManager_Heli &operator=(const AC_InputManager_Heli&) = delete;
CLASS_NO_COPY(AC_InputManager_Heli);
// get_pilot_desired_collective - rescale's pilot collective pitch input in Stabilize and Acro modes
float get_pilot_desired_collective(int16_t control_in);

View File

@ -27,8 +27,7 @@ public:
AC_PrecLand();
/* Do not allow copies */
AC_PrecLand(const AC_PrecLand &other) = delete;
AC_PrecLand &operator=(const AC_PrecLand&) = delete;
CLASS_NO_COPY(AC_PrecLand);
// return singleton
static AC_PrecLand *get_singleton() {

View File

@ -38,8 +38,7 @@ public:
AC_Sprayer();
/* Do not allow copies */
AC_Sprayer(const AC_Sprayer &other) = delete;
AC_Sprayer &operator=(const AC_Sprayer&) = delete;
CLASS_NO_COPY(AC_Sprayer);
static AC_Sprayer *get_singleton();
static AC_Sprayer *_singleton;

View File

@ -12,8 +12,7 @@ public:
AP_PitchController(const AP_Vehicle::FixedWing &parms);
/* Do not allow copies */
AP_PitchController(const AP_PitchController &other) = delete;
AP_PitchController &operator=(const AP_PitchController&) = delete;
CLASS_NO_COPY(AP_PitchController);
float get_rate_out(float desired_rate, float scaler);
float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode);

View File

@ -12,8 +12,7 @@ public:
AP_RollController(const AP_Vehicle::FixedWing &parms);
/* Do not allow copies */
AP_RollController(const AP_RollController &other) = delete;
AP_RollController &operator=(const AP_RollController&) = delete;
CLASS_NO_COPY(AP_RollController);
float get_rate_out(float desired_rate, float scaler);
float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode);

View File

@ -12,8 +12,7 @@ public:
}
/* Do not allow copies */
AP_SteerController(const AP_SteerController &other) = delete;
AP_SteerController &operator=(const AP_SteerController&) = delete;
CLASS_NO_COPY(AP_SteerController);
/*
return a steering servo output from -4500 to 4500 given a

View File

@ -11,8 +11,7 @@ public:
AP_YawController(const AP_Vehicle::FixedWing &parms);
/* Do not allow copies */
AP_YawController(const AP_YawController &other) = delete;
AP_YawController &operator=(const AP_YawController&) = delete;
CLASS_NO_COPY(AP_YawController);
// return true if rate control or damping is enabled
bool enabled() const { return rate_control_enabled() || (_K_D > 0.0); }

View File

@ -54,8 +54,7 @@ public:
AP_ADSB();
/* Do not allow copies */
AP_ADSB(const AP_ADSB &other) = delete;
AP_ADSB &operator=(const AP_ADSB&) = delete;
CLASS_NO_COPY(AP_ADSB);
// get singleton instance
static AP_ADSB *get_singleton(void) {

View File

@ -44,8 +44,7 @@ public:
}
/* Do not allow copies */
AP_AHRS_DCM(const AP_AHRS_DCM &other) = delete;
AP_AHRS_DCM &operator=(const AP_AHRS_DCM&) = delete;
CLASS_NO_COPY(AP_AHRS_DCM);
// reset the current gyro drift estimate
// should be called if gyro offsets are recalculated

View File

@ -47,8 +47,7 @@ public:
};
/* Do not allow copies */
AP_AdvancedFailsafe(const AP_AdvancedFailsafe &other) = delete;
AP_AdvancedFailsafe &operator=(const AP_AdvancedFailsafe&) = delete;
CLASS_NO_COPY(AP_AdvancedFailsafe);
// Constructor
AP_AdvancedFailsafe()

View File

@ -40,8 +40,7 @@ public:
AP_Avoidance(class AP_ADSB &adsb);
/* Do not allow copies */
AP_Avoidance(const AP_Avoidance &other) = delete;
AP_Avoidance &operator=(const AP_Avoidance&) = delete;
CLASS_NO_COPY(AP_Avoidance);
// get singleton instance
static AP_Avoidance *get_singleton() {

View File

@ -46,8 +46,7 @@ public:
AP_Baro();
/* Do not allow copies */
AP_Baro(const AP_Baro &other) = delete;
AP_Baro &operator=(const AP_Baro&) = delete;
CLASS_NO_COPY(AP_Baro);
// get singleton
static AP_Baro *get_singleton(void) {

View File

@ -119,8 +119,7 @@ public:
AP_BattMonitor(uint32_t log_battery_bit, battery_failsafe_handler_fn_t battery_failsafe_handler_fn, const int8_t *failsafe_priorities);
/* Do not allow copies */
AP_BattMonitor(const AP_BattMonitor &other) = delete;
AP_BattMonitor &operator=(const AP_BattMonitor&) = delete;
CLASS_NO_COPY(AP_BattMonitor);
static AP_BattMonitor *get_singleton() {
return _singleton;

View File

@ -9,8 +9,7 @@ public:
AP_BattMonitor_Params(void);
/* Do not allow copies */
AP_BattMonitor_Params(const AP_BattMonitor_Params &other) = delete;
AP_BattMonitor_Params &operator=(const AP_BattMonitor_Params&) = delete;
CLASS_NO_COPY(AP_BattMonitor_Params);
// low voltage sources (used for BATT_LOW_TYPE parameter)
enum BattMonitor_LowVoltage_Source {

View File

@ -47,8 +47,7 @@ public:
AP_BoardConfig();
/* Do not allow copies */
AP_BoardConfig(const AP_BoardConfig &other) = delete;
AP_BoardConfig &operator=(const AP_BoardConfig&) = delete;
CLASS_NO_COPY(AP_BoardConfig);
// singleton support
static AP_BoardConfig *get_singleton(void) {

View File

@ -37,8 +37,7 @@ public:
AP_Button(void);
/* Do not allow copies */
AP_Button(const AP_Button &other) = delete;
AP_Button &operator=(const AP_Button&) = delete;
CLASS_NO_COPY(AP_Button);
static const struct AP_Param::GroupInfo var_info[];

View File

@ -32,8 +32,7 @@ public:
AP_CANManager();
/* Do not allow copies */
AP_CANManager(const AP_CANManager &other) = delete;
AP_CANManager &operator=(const AP_CANManager&) = delete;
CLASS_NO_COPY(AP_CANManager);
static AP_CANManager* get_singleton()
{

View File

@ -27,8 +27,7 @@ public:
CANSensor(const char *driver_name, uint16_t stack_size=2048);
/* Do not allow copies */
CANSensor(const CANSensor &other) = delete;
CANSensor &operator=(const CANSensor&) = delete;
CLASS_NO_COPY(CANSensor);
void init(uint8_t driver_index, bool enable_filters) override;
bool add_interface(AP_HAL::CANIface* can_iface) override;

View File

@ -36,8 +36,7 @@ public:
static const struct AP_Param::GroupInfo var_info[];
/* Do not allow copies */
CANTester(const CANTester &other) = delete;
CANTester &operator=(const CANTester&) = delete;
CLASS_NO_COPY(CANTester);
void init(uint8_t driver_index, bool enable_filters) override;
bool add_interface(AP_HAL::CANIface* can_iface) override;

View File

@ -31,8 +31,7 @@ public:
}
/* Do not allow copies */
AP_Camera(const AP_Camera &other) = delete;
AP_Camera &operator=(const AP_Camera&) = delete;
CLASS_NO_COPY(AP_Camera);
// get singleton instance
static AP_Camera *get_singleton()

View File

@ -50,8 +50,7 @@ public:
AP_RunCam();
// do not allow copies
AP_RunCam(const AP_RunCam &other) = delete;
AP_RunCam &operator=(const AP_RunCam &) = delete;
CLASS_NO_COPY(AP_RunCam);
// get singleton instance
static AP_RunCam *get_singleton() {

View File

@ -53,8 +53,7 @@ public:
~AP_ExpandingArrayGeneric(void);
/* Do not allow copies */
AP_ExpandingArrayGeneric(const AP_ExpandingArrayGeneric &other) = delete;
AP_ExpandingArrayGeneric &operator=(const AP_ExpandingArrayGeneric&) = delete;
CLASS_NO_COPY(AP_ExpandingArrayGeneric);
// current maximum number of items (using expand may increase this)
uint16_t max_items() const { return chunk_size * chunk_count; }
@ -88,8 +87,7 @@ public:
{}
/* Do not allow copies */
AP_ExpandingArray(const AP_ExpandingArray<T> &other) = delete;
AP_ExpandingArray<T> &operator=(const AP_ExpandingArray<T>&) = delete;
CLASS_NO_COPY(AP_ExpandingArray);
// allow use as an array for assigning to elements. no bounds checking is performed
T &operator[](uint16_t i)

View File

@ -85,8 +85,7 @@ public:
Compass();
/* Do not allow copies */
Compass(const Compass &other) = delete;
Compass &operator=(const Compass&) = delete;
CLASS_NO_COPY(Compass);
// get singleton instance
static Compass *get_singleton() {

View File

@ -29,8 +29,7 @@ public:
AP_DEVO_Telem() {}
/* Do not allow copies */
AP_DEVO_Telem(const AP_DEVO_Telem &other) = delete;
AP_DEVO_Telem &operator=(const AP_DEVO_Telem&) = delete;
CLASS_NO_COPY(AP_DEVO_Telem);
void init();

View File

@ -48,8 +48,7 @@ public:
AP_ESC_Telem_Backend();
/* Do not allow copies */
AP_ESC_Telem_Backend(const AP_ESC_Telem_Backend &other) = delete;
AP_ESC_Telem_Backend &operator=(const AP_ESC_Telem_Backend&) = delete;
CLASS_NO_COPY(AP_ESC_Telem_Backend);
protected:
// callback to update the rpm in the frontend, should be called by the driver when new data is available

View File

@ -67,8 +67,7 @@ public:
AP_FETtecOneWire();
/// Do not allow copies
AP_FETtecOneWire(const AP_FETtecOneWire &other) = delete;
AP_FETtecOneWire &operator=(const AP_FETtecOneWire&) = delete;
CLASS_NO_COPY(AP_FETtecOneWire);
static const struct AP_Param::GroupInfo var_info[];

View File

@ -12,8 +12,7 @@ public:
}
/* Do not allow copies */
AP_Frsky_SPort(const AP_Frsky_SPort &other) = delete;
AP_Frsky_SPort &operator=(const AP_Frsky_SPort&) = delete;
CLASS_NO_COPY(AP_Frsky_SPort);
void send() override;
// send an sport packet by responding to the specified polled sensor

View File

@ -27,8 +27,7 @@ public:
~AP_Frsky_Telem();
/* Do not allow copies */
AP_Frsky_Telem(const AP_Frsky_Telem &other) = delete;
AP_Frsky_Telem &operator=(const AP_Frsky_Telem&) = delete;
CLASS_NO_COPY(AP_Frsky_Telem);
// init - perform required initialisation
bool init(bool use_external_data=false);

View File

@ -92,8 +92,7 @@ public:
AP_GPS();
/* Do not allow copies */
AP_GPS(const AP_GPS &other) = delete;
AP_GPS &operator=(const AP_GPS&) = delete;
CLASS_NO_COPY(AP_GPS);
static AP_GPS *get_singleton() {
return _singleton;

View File

@ -10,8 +10,7 @@ public:
MovingBase(void);
/* Do not allow copies */
MovingBase(const MovingBase &other) = delete;
MovingBase &operator=(const MovingBase&) = delete;
CLASS_NO_COPY(MovingBase);
enum class Type : int8_t {
RelativeToAlternateInstance = 0,

View File

@ -28,8 +28,7 @@ public:
AP_Generator();
// Do not allow copies
AP_Generator(const AP_Generator &other) = delete;
AP_Generator &operator=(const AP_Generator&) = delete;
CLASS_NO_COPY(AP_Generator);
static AP_Generator* get_singleton();

View File

@ -27,8 +27,8 @@ class AP_Gripper {
public:
AP_Gripper();
AP_Gripper(const AP_Gripper &other) = delete;
AP_Gripper &operator=(const AP_Gripper&) = delete;
/* Do not allow copies */
CLASS_NO_COPY(AP_Gripper);
static AP_Gripper *get_singleton();
static AP_Gripper *_singleton;

View File

@ -44,8 +44,7 @@ public:
AP_GyroFFT();
// Do not allow copies
AP_GyroFFT(const AP_GyroFFT &other) = delete;
AP_GyroFFT &operator=(const AP_GyroFFT&) = delete;
CLASS_NO_COPY(AP_GyroFFT);
void init(uint16_t loop_rate_hz);

View File

@ -12,8 +12,7 @@ public:
Semaphore() {}
// do not allow copying
Semaphore(const Semaphore &other) = delete;
Semaphore &operator=(const Semaphore&) = delete;
CLASS_NO_COPY(Semaphore);
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED = 0 ;
virtual bool take_nonblocking() WARN_IF_UNUSED = 0;

View File

@ -21,8 +21,7 @@ private:
public:
UARTDriver() {}
/* Do not allow copies */
UARTDriver(const UARTDriver &other) = delete;
UARTDriver &operator=(const UARTDriver&) = delete;
CLASS_NO_COPY(UARTDriver);
// begin() implicitly clears rx/tx buffers, even if the port was already open (unless the UART is the console UART)
virtual void begin(uint32_t baud) = 0;

View File

@ -31,8 +31,7 @@ class ChibiOS::SoftSigReaderInt {
public:
SoftSigReaderInt();
/* Do not allow copies */
SoftSigReaderInt(const SoftSigReaderInt &other) = delete;
SoftSigReaderInt &operator=(const SoftSigReaderInt&) = delete;
CLASS_NO_COPY(SoftSigReaderInt);
// get singleton
static SoftSigReaderInt *get_singleton(void)

View File

@ -33,8 +33,7 @@ public:
UARTDriver(uint8_t serial_num);
/* Do not allow copies */
UARTDriver(const UARTDriver &other) = delete;
UARTDriver &operator=(const UARTDriver&) = delete;
CLASS_NO_COPY(UARTDriver);
void begin(uint32_t b) override;
void begin_locked(uint32_t b, uint32_t write_key) override;

View File

@ -41,9 +41,9 @@ class SoftSigReaderInt
public:
SoftSigReaderInt();
~SoftSigReaderInt();
/* Do not allow copies */
SoftSigReaderInt(const SoftSigReaderInt &other) = delete;
SoftSigReaderInt &operator=(const SoftSigReaderInt&) = delete;
CLASS_NO_COPY(SoftSigReaderInt);
// get singleton
static SoftSigReaderInt *get_instance(void)

View File

@ -26,8 +26,7 @@ public:
AP_Hott_Telem();
/* Do not allow copies */
AP_Hott_Telem(const AP_Hott_Telem &other) = delete;
AP_Hott_Telem &operator=(const AP_Hott_Telem&) = delete;
CLASS_NO_COPY(AP_Hott_Telem);
static AP_Hott_Telem *get_singleton(void) {
return singleton;

View File

@ -84,8 +84,7 @@ public:
AP_InertialSensor();
/* Do not allow copies */
AP_InertialSensor(const AP_InertialSensor &other) = delete;
AP_InertialSensor &operator=(const AP_InertialSensor&) = delete;
CLASS_NO_COPY(AP_InertialSensor);
static AP_InertialSensor *get_singleton();

View File

@ -39,8 +39,7 @@ public:
AP_KDECAN();
/* Do not allow copies */
AP_KDECAN(const AP_KDECAN &other) = delete;
AP_KDECAN &operator=(const AP_KDECAN&) = delete;
CLASS_NO_COPY(AP_KDECAN);
static const struct AP_Param::GroupInfo var_info[];

View File

@ -30,8 +30,7 @@ public:
}
/* Do not allow copies */
AP_L1_Control(const AP_L1_Control &other) = delete;
AP_L1_Control &operator=(const AP_L1_Control&) = delete;
CLASS_NO_COPY(AP_L1_Control);
/* see AP_Navigation.h for the definitions and units of these
* functions */

View File

@ -32,8 +32,7 @@ public:
AP_LTM_Telem() {}
/* Do not allow copies */
AP_LTM_Telem(const AP_LTM_Telem &other) = delete;
AP_LTM_Telem &operator=(const AP_LTM_Telem&) = delete;
CLASS_NO_COPY(AP_LTM_Telem);
// init - perform required initialisation
void init();

View File

@ -45,8 +45,7 @@ public:
update_flight_stage_fn_t _update_flight_stage_fn);
/* Do not allow copies */
AP_Landing(const AP_Landing &other) = delete;
AP_Landing &operator=(const AP_Landing&) = delete;
CLASS_NO_COPY(AP_Landing);
// NOTE: make sure to update is_type_valid()

View File

@ -20,8 +20,7 @@ public:
}
/* Do not allow copies */
AP_LandingGear(const AP_LandingGear &other) = delete;
AP_LandingGear &operator=(const AP_LandingGear&) = delete;
CLASS_NO_COPY(AP_LandingGear);
// get singleton instance
static AP_LandingGear *get_singleton(void) {

View File

@ -17,8 +17,7 @@ public:
AP_LeakDetector();
/* Do not allow copies */
AP_LeakDetector(const AP_LeakDetector &other) = delete;
AP_LeakDetector &operator=(const AP_LeakDetector&) = delete;
CLASS_NO_COPY(AP_LeakDetector);
struct LeakDetector_State {
uint8_t instance;

View File

@ -244,8 +244,7 @@ public:
AP_Logger(const AP_Int32 &log_bitmask);
/* Do not allow copies */
AP_Logger(const AP_Logger &other) = delete;
AP_Logger &operator=(const AP_Logger&) = delete;
CLASS_NO_COPY(AP_Logger);
// get singleton instance
static AP_Logger *get_singleton(void) {

View File

@ -44,8 +44,7 @@ public:
AP_MSP();
/* Do not allow copies */
AP_MSP(const AP_MSP &other) = delete;
AP_MSP &operator=(const AP_MSP&) = delete;
CLASS_NO_COPY(AP_MSP);
// User settable parameters
static const struct AP_Param::GroupInfo var_info[];

View File

@ -383,8 +383,7 @@ public:
}
/* Do not allow copies */
AP_Mission(const AP_Mission &other) = delete;
AP_Mission &operator=(const AP_Mission&) = delete;
CLASS_NO_COPY(AP_Mission);
// mission state enumeration
enum mission_state {

View File

@ -71,8 +71,7 @@ public:
AP_Mount();
/* Do not allow copies */
AP_Mount(const AP_Mount &other) = delete;
AP_Mount &operator=(const AP_Mount&) = delete;
CLASS_NO_COPY(AP_Mount);
// get singleton instance
static AP_Mount *get_singleton() {

View File

@ -12,8 +12,7 @@ public:
AP_Mount_Params(void);
/* Do not allow copies */
AP_Mount_Params(const AP_Mount_Params &other) = delete;
AP_Mount_Params &operator=(const AP_Mount_Params&) = delete;
CLASS_NO_COPY(AP_Mount_Params);
AP_Int8 type; // mount type (see MountType enum)
AP_Int8 default_mode; // default mode on startup and when control is returned from autopilot

View File

@ -12,8 +12,7 @@ public:
AP_NavEKF_Source();
/* Do not allow copies */
AP_NavEKF_Source(const AP_NavEKF_Source &other) = delete;
AP_NavEKF_Source &operator=(const AP_NavEKF_Source&) = delete;
CLASS_NO_COPY(AP_NavEKF_Source);
enum class SourceXY : uint8_t {
NONE = 0,

View File

@ -37,8 +37,7 @@ public:
NavEKF2();
/* Do not allow copies */
NavEKF2(const NavEKF2 &other) = delete;
NavEKF2 &operator=(const NavEKF2&) = delete;
CLASS_NO_COPY(NavEKF2);
static const struct AP_Param::GroupInfo var_info[];

View File

@ -35,8 +35,7 @@ public:
NavEKF3();
/* Do not allow copies */
NavEKF3(const NavEKF3 &other) = delete;
NavEKF3 &operator=(const NavEKF3&) = delete;
CLASS_NO_COPY(NavEKF3);
static const struct AP_Param::GroupInfo var_info[];
static const struct AP_Param::GroupInfo var_info2[];

View File

@ -44,8 +44,7 @@ public:
AP_Notify();
/* Do not allow copies */
AP_Notify(const AP_Notify &other) = delete;
AP_Notify &operator=(const AP_Notify&) = delete;
CLASS_NO_COPY(AP_Notify);
// get singleton instance
static AP_Notify *get_singleton(void) {

View File

@ -24,8 +24,7 @@ public:
ScriptingLED();
/* Do not allow copies */
ScriptingLED(const AP_Notify &other) = delete;
ScriptingLED &operator=(const AP_Notify&) = delete;
CLASS_NO_COPY(ScriptingLED);
// get singleton instance
static ScriptingLED *get_singleton(void) {

View File

@ -34,8 +34,7 @@ public:
AP_ONVIF();
/* Do not allow copies */
AP_ONVIF(const AP_ONVIF &other) = delete;
AP_ONVIF &operator=(const AP_ONVIF&) = delete;
CLASS_NO_COPY(AP_ONVIF);
// Start ONVIF client with username, password and service host url
bool start(const char *user, const char *pass, const char *httphostname);

View File

@ -460,8 +460,7 @@ public:
AP_OSD();
/* Do not allow copies */
AP_OSD(const AP_OSD &other) = delete;
AP_OSD &operator=(const AP_OSD&) = delete;
CLASS_NO_COPY(AP_OSD);
// get singleton instance
static AP_OSD *get_singleton()

View File

@ -49,8 +49,7 @@ public:
}
/* Do not allow copies */
AP_Parachute(const AP_Parachute &other) = delete;
AP_Parachute &operator=(const AP_Parachute&) = delete;
CLASS_NO_COPY(AP_Parachute);
/// enabled - enable or disable parachute release
void enabled(bool on_off);

View File

@ -73,8 +73,7 @@ public:
};
/* Do not allow copies */
AP_PiccoloCAN(const AP_PiccoloCAN &other) = delete;
AP_PiccoloCAN &operator=(const AP_PiccoloCAN&) = delete;
CLASS_NO_COPY(AP_PiccoloCAN);
static const struct AP_Param::GroupInfo var_info[];

View File

@ -37,8 +37,8 @@ public:
AP_Proximity();
AP_Proximity(const AP_Proximity &other) = delete;
AP_Proximity &operator=(const AP_Proximity) = delete;
/* Do not allow copies */
CLASS_NO_COPY(AP_Proximity);
// Proximity driver types
enum class Type {

View File

@ -14,8 +14,7 @@ public:
AP_Proximity_Params(void);
/* Do not allow copies */
AP_Proximity_Params(const AP_Proximity_Params &other) = delete;
AP_Proximity_Params &operator=(const AP_Proximity_Params&) = delete;
CLASS_NO_COPY(AP_Proximity_Params);
AP_Int8 type; // type of sensor
AP_Int8 orientation; // orientation (e.g. right-side-up or upside-down)

View File

@ -9,8 +9,7 @@ public:
RCMapper();
/* Do not allow copies */
RCMapper(const RCMapper &other) = delete;
RCMapper &operator=(const RCMapper&) = delete;
CLASS_NO_COPY(RCMapper);
// get singleton instance
static RCMapper *get_singleton()

View File

@ -39,8 +39,7 @@ public:
~AP_CRSF_Telem() override;
/* Do not allow copies */
AP_CRSF_Telem(const AP_CRSF_Telem &other) = delete;
AP_CRSF_Telem &operator=(const AP_CRSF_Telem&) = delete;
CLASS_NO_COPY(AP_CRSF_Telem);
// init - perform required initialisation
virtual bool init() override;

View File

@ -31,8 +31,7 @@ public:
virtual ~AP_RCTelemetry() {};
/* Do not allow copies */
AP_RCTelemetry(const AP_RCTelemetry &other) = delete;
AP_RCTelemetry &operator=(const AP_RCTelemetry&) = delete;
CLASS_NO_COPY(AP_RCTelemetry);
// add statustext message to message queue
virtual void queue_message(MAV_SEVERITY severity, const char *text);

View File

@ -50,8 +50,7 @@ public:
~AP_Spektrum_Telem() override;
/* Do not allow copies */
AP_Spektrum_Telem(const AP_Spektrum_Telem &other) = delete;
AP_Spektrum_Telem &operator=(const AP_Spektrum_Telem&) = delete;
CLASS_NO_COPY(AP_Spektrum_Telem);
// init - perform required initialisation
virtual bool init() override;

View File

@ -33,8 +33,7 @@ public:
AP_RSSI();
/* Do not allow copies */
AP_RSSI(const AP_RSSI &other) = delete;
AP_RSSI &operator=(const AP_RSSI&) = delete;
CLASS_NO_COPY(AP_RSSI);
// destructor
~AP_RSSI(void);

View File

@ -42,8 +42,7 @@ public:
AP_Rally();
/* Do not allow copies */
AP_Rally(const AP_Rally &other) = delete;
AP_Rally &operator=(const AP_Rally&) = delete;
CLASS_NO_COPY(AP_Rally);
// data handling
bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const;

View File

@ -62,8 +62,7 @@ public:
RangeFinder();
/* Do not allow copies */
RangeFinder(const RangeFinder &other) = delete;
RangeFinder &operator=(const RangeFinder&) = delete;
CLASS_NO_COPY(RangeFinder);
// RangeFinder driver types
enum class Type {

View File

@ -10,8 +10,7 @@ public:
AP_RangeFinder_Params(void);
/* Do not allow copies */
AP_RangeFinder_Params(const AP_RangeFinder_Params &other) = delete;
AP_RangeFinder_Params &operator=(const AP_RangeFinder_Params&) = delete;
CLASS_NO_COPY(AP_RangeFinder_Params);
AP_Vector3f pos_offset; // position offset in body frame
AP_Float scaling;

View File

@ -20,8 +20,7 @@ public:
AP_Relay();
/* Do not allow copies */
AP_Relay(const AP_Relay &other) = delete;
AP_Relay &operator=(const AP_Relay&) = delete;
CLASS_NO_COPY(AP_Relay);
// setup the relay pin
void init();

View File

@ -34,8 +34,7 @@ public:
AP_RobotisServo();
/* Do not allow copies */
AP_RobotisServo(const AP_RobotisServo &other) = delete;
AP_RobotisServo &operator=(const AP_RobotisServo&) = delete;
CLASS_NO_COPY(AP_RobotisServo);
static const struct AP_Param::GroupInfo var_info[];

View File

@ -15,8 +15,7 @@ public:
AP_SBusOut();
/* Do not allow copies */
AP_SBusOut(const AP_SBusOut &other) = delete;
AP_SBusOut &operator=(const AP_SBusOut&) = delete;
CLASS_NO_COPY(AP_SBusOut);
static const struct AP_Param::GroupInfo var_info[];

View File

@ -79,8 +79,7 @@ public:
AP_Scheduler();
/* Do not allow copies */
AP_Scheduler(const AP_Scheduler &other) = delete;
AP_Scheduler &operator=(const AP_Scheduler&) = delete;
CLASS_NO_COPY(AP_Scheduler);
static AP_Scheduler *get_singleton();
static AP_Scheduler *_singleton;

View File

@ -23,8 +23,7 @@ public:
};
/* Do not allow copies */
PerfInfo(const PerfInfo &other) = delete;
PerfInfo &operator=(const PerfInfo&) = delete;
CLASS_NO_COPY(PerfInfo);
void reset();
void ignore_this_loop();

View File

@ -34,8 +34,7 @@ public:
AP_Scripting();
/* Do not allow copies */
AP_Scripting(const AP_Scripting &other) = delete;
AP_Scripting &operator=(const AP_Scripting&) = delete;
CLASS_NO_COPY(AP_Scripting);
void init(void);

View File

@ -120,8 +120,7 @@ public:
AP_SerialManager();
/* Do not allow copies */
AP_SerialManager(const AP_SerialManager &other) = delete;
AP_SerialManager &operator=(const AP_SerialManager&) = delete;
CLASS_NO_COPY(AP_SerialManager);
enum SerialProtocol {
SerialProtocol_None = -1,

View File

@ -18,8 +18,7 @@ public:
}
/* Do not allow copies */
AP_ServoRelayEvents(const AP_ServoRelayEvents &other) = delete;
AP_ServoRelayEvents &operator=(const AP_ServoRelayEvents&) = delete;
CLASS_NO_COPY(AP_ServoRelayEvents);
// get singleton instance
static AP_ServoRelayEvents *get_singleton() {

View File

@ -36,8 +36,7 @@ public:
}
/* Do not allow copies */
AP_TECS(const AP_TECS &other) = delete;
AP_TECS &operator=(const AP_TECS&) = delete;
CLASS_NO_COPY(AP_TECS);
// Update of the estimated height and height rate internal state
// Update of the inertial speed rate internal state

View File

@ -36,8 +36,7 @@ public:
void update(void);
/* Do not allow copies */
AP_TempCalibration(const AP_TempCalibration &other) = delete;
AP_TempCalibration &operator=(const AP_TempCalibration&) = delete;
CLASS_NO_COPY(AP_TempCalibration);
enum {
TC_DISABLED = 0,

View File

@ -103,8 +103,7 @@ public:
// Do not allow copies
AP_UAVCAN_DNA_Server(const AP_UAVCAN_DNA_Server &other) = delete;
AP_UAVCAN_DNA_Server &operator=(const AP_UAVCAN_DNA_Server&) = delete;
CLASS_NO_COPY(AP_UAVCAN_DNA_Server);
//Initialises publisher and Server Record for specified uavcan driver
bool init();

Some files were not shown because too many files have changed in this diff Show More