Browse Source

clang-tidy: partially fix hicpp-use-equals-delete

sbg
Daniel Agar 5 years ago
parent
commit
279df3b1b8
  1. 9
      platforms/common/include/px4_platform_common/px4_work_queue/WorkItem.hpp
  2. 11
      src/lib/cdev/CDev.hpp
  3. 13
      src/lib/drivers/device/Device.hpp
  4. 8
      src/lib/drivers/device/nuttx/I2C.hpp
  5. 11
      src/lib/drivers/device/nuttx/SPI.hpp
  6. 12
      src/lib/drivers/device/posix/I2C.hpp
  7. 36
      src/lib/drivers/device/posix/SPI.hpp
  8. 5
      src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp
  9. 8
      src/modules/uORB/uORB_tests/uORBTest_UnitTest.hpp

9
platforms/common/include/px4_platform_common/px4_work_queue/WorkItem.hpp

@ -49,6 +49,14 @@ class WorkItem : public ListNode<WorkItem *>, public IntrusiveQueueNode<WorkItem
{ {
public: public:
WorkItem() = delete;
// no copy, assignment, move, move assignment
WorkItem(const WorkItem &) = delete;
WorkItem &operator=(const WorkItem &) = delete;
WorkItem(WorkItem &&) = delete;
WorkItem &operator=(WorkItem &&) = delete;
inline void ScheduleNow() inline void ScheduleNow()
{ {
if (_wq != nullptr) { if (_wq != nullptr) {
@ -70,7 +78,6 @@ public:
protected: protected:
explicit WorkItem(const char *name, const wq_config_t &config); explicit WorkItem(const char *name, const wq_config_t &config);
WorkItem() = delete;
virtual ~WorkItem(); virtual ~WorkItem();

11
src/lib/cdev/CDev.hpp

@ -64,7 +64,13 @@ public:
* @param name Driver name * @param name Driver name
* @param devname Device node name * @param devname Device node name
*/ */
CDev(const char *devname); explicit CDev(const char *devname);
// no copy, assignment, move, move assignment
CDev(const CDev &) = delete;
CDev &operator=(const CDev &) = delete;
CDev(CDev &&) = delete;
CDev &operator=(CDev &&) = delete;
virtual ~CDev(); virtual ~CDev();
@ -301,9 +307,6 @@ private:
*/ */
inline int remove_poll_waiter(px4_pollfd_struct_t *fds); inline int remove_poll_waiter(px4_pollfd_struct_t *fds);
/* do not allow copying this class */
CDev(const CDev &);
CDev operator=(const CDev &);
}; };
} // namespace cdev } // namespace cdev

13
src/lib/drivers/device/Device.hpp

@ -65,6 +65,13 @@ namespace device
class __EXPORT Device class __EXPORT Device
{ {
public: public:
// no copy, assignment, move, move assignment
Device(const Device &) = delete;
Device &operator=(const Device &) = delete;
Device(Device &&) = delete;
Device &operator=(Device &&) = delete;
/** /**
* Destructor. * Destructor.
* *
@ -253,12 +260,6 @@ protected:
_device_id.devid_s.devtype = devtype; _device_id.devid_s.devtype = devtype;
} }
// no copy, assignment, move, move assignment
Device(const Device &) = delete;
Device &operator=(const Device &) = delete;
Device(Device &&) = delete;
Device &operator=(Device &&) = delete;
}; };
} // namespace device } // namespace device

8
src/lib/drivers/device/nuttx/I2C.hpp

@ -59,6 +59,12 @@ class __EXPORT I2C : public CDev
public: public:
// no copy, assignment, move, move assignment
I2C(const I2C &) = delete;
I2C &operator=(const I2C &) = delete;
I2C(I2C &&) = delete;
I2C &operator=(I2C &&) = delete;
virtual int init(); virtual int init();
static int set_bus_clock(unsigned bus, unsigned clock_hz); static int set_bus_clock(unsigned bus, unsigned clock_hz);
@ -109,8 +115,6 @@ private:
uint32_t _frequency{0}; uint32_t _frequency{0};
px4_i2c_dev_t *_dev{nullptr}; px4_i2c_dev_t *_dev{nullptr};
I2C(const device::I2C &);
I2C operator=(const device::I2C &);
}; };
} // namespace device } // namespace device

11
src/lib/drivers/device/nuttx/SPI.hpp

@ -50,6 +50,13 @@ namespace device __EXPORT
*/ */
class __EXPORT SPI : public CDev class __EXPORT SPI : public CDev
{ {
public:
// no copy, assignment, move, move assignment
SPI(const SPI &) = delete;
SPI &operator=(const SPI &) = delete;
SPI(SPI &&) = delete;
SPI &operator=(SPI &&) = delete;
protected: protected:
/** /**
* Constructor * Constructor
@ -152,10 +159,6 @@ private:
LockMode _locking_mode{LOCK_THREADS}; /**< selected locking mode */ LockMode _locking_mode{LOCK_THREADS}; /**< selected locking mode */
/* this class does not allow copying */
SPI(const SPI &);
SPI operator=(const SPI &);
protected: protected:
int _transfer(uint8_t *send, uint8_t *recv, unsigned len); int _transfer(uint8_t *send, uint8_t *recv, unsigned len);

12
src/lib/drivers/device/posix/I2C.hpp

@ -60,6 +60,12 @@ class __EXPORT I2C : public CDev
public: public:
// no copy, assignment, move, move assignment
I2C(const I2C &) = delete;
I2C &operator=(const I2C &) = delete;
I2C(I2C &&) = delete;
I2C &operator=(I2C &&) = delete;
virtual int init(); virtual int init();
protected: protected:
@ -78,7 +84,7 @@ protected:
* @param address I2C bus address, or zero if set_address will be used * @param address I2C bus address, or zero if set_address will be used
* @param frequency I2C bus frequency for the device (currently not used) * @param frequency I2C bus frequency for the device (currently not used)
*/ */
I2C(const char *name, const char *devname, const int bus, const uint16_t address, const uint32_t frequency = 0); I2C(const char *name, const char *devname, const int bus, const uint16_t address, const uint32_t frequency);
virtual ~I2C(); virtual ~I2C();
/** /**
@ -103,10 +109,8 @@ protected:
bool external() { return px4_i2c_bus_external(_device_id.devid_s.bus); } bool external() { return px4_i2c_bus_external(_device_id.devid_s.bus); }
private: private:
int _fd{-1}; int _fd{-1};
I2C(const device::I2C &);
I2C operator=(const device::I2C &);
}; };
} // namespace device } // namespace device

36
src/lib/drivers/device/posix/SPI.hpp

@ -65,6 +65,13 @@ namespace device __EXPORT
*/ */
class __EXPORT SPI : public CDev class __EXPORT SPI : public CDev
{ {
public:
// no copy, assignment, move, move assignment
SPI(const SPI &) = delete;
SPI &operator=(const SPI &) = delete;
SPI(SPI &&) = delete;
SPI &operator=(SPI &&) = delete;
protected: protected:
/** /**
* Constructor * Constructor
@ -79,6 +86,15 @@ protected:
SPI(const char *name, const char *devname, int bus, uint32_t device, enum spi_mode_e mode, uint32_t frequency); SPI(const char *name, const char *devname, int bus, uint32_t device, enum spi_mode_e mode, uint32_t frequency);
virtual ~SPI(); virtual ~SPI();
/**
* Locking modes supported by the driver.
*/
enum LockMode {
LOCK_PREEMPTION, /**< the default; lock against all forms of preemption. */
LOCK_THREADS, /**< lock only against other threads, using SPI_LOCK */
LOCK_NONE /**< perform no locking, only safe if the bus is entirely private */
};
virtual int init(); virtual int init();
/** /**
@ -140,18 +156,28 @@ protected:
void set_frequency(uint32_t frequency) { _frequency = frequency; } void set_frequency(uint32_t frequency) { _frequency = frequency; }
uint32_t get_frequency() { return _frequency; } uint32_t get_frequency() { return _frequency; }
private: /**
int _fd{-1}; * Set the SPI bus locking mode
*
* This set the SPI locking mode. For devices competing with NuttX SPI
* drivers on a bus the right lock mode is LOCK_THREADS.
*
* @param mode Locking mode
*/
void set_lockmode(enum LockMode mode) { _locking_mode = mode; }
private:
uint32_t _device; uint32_t _device;
enum spi_mode_e _mode; enum spi_mode_e _mode;
uint32_t _frequency; uint32_t _frequency;
int _fd{-1};
/* this class does not allow copying */ LockMode _locking_mode{LOCK_THREADS}; /**< selected locking mode */
SPI(const SPI &);
SPI operator=(const SPI &);
protected: protected:
int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
int _transferhword(uint16_t *send, uint16_t *recv, unsigned len);
bool external() { return px4_spi_bus_external(get_device_bus()); } bool external() { return px4_spi_bus_external(get_device_bus()); }

5
src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp

@ -106,6 +106,9 @@ class BlockLocalPositionEstimator : public control::SuperBlock, public ModulePar
// //
public: public:
BlockLocalPositionEstimator(const BlockLocalPositionEstimator &) = delete;
BlockLocalPositionEstimator operator=(const BlockLocalPositionEstimator &) = delete;
// constants // constants
enum {X_x = 0, X_y, X_z, X_vx, X_vy, X_vz, X_bx, X_by, X_bz, X_tz, n_x}; enum {X_x = 0, X_y, X_z, X_vx, X_vy, X_vz, X_bx, X_by, X_bz, X_tz, n_x};
enum {U_ax = 0, U_ay, U_az, n_u}; enum {U_ax = 0, U_ay, U_az, n_u};
@ -154,8 +157,6 @@ public:
virtual ~BlockLocalPositionEstimator() = default; virtual ~BlockLocalPositionEstimator() = default;
private: private:
BlockLocalPositionEstimator(const BlockLocalPositionEstimator &) = delete;
BlockLocalPositionEstimator operator=(const BlockLocalPositionEstimator &) = delete;
// methods // methods
// ---------------------------- // ----------------------------

8
src/modules/uORB/uORB_tests/uORBTest_UnitTest.hpp

@ -76,17 +76,17 @@ public:
// Singleton pattern // Singleton pattern
static uORBTest::UnitTest &instance(); static uORBTest::UnitTest &instance();
~UnitTest() {} ~UnitTest() = default;
int test(); int test();
template<typename S> int latency_test(orb_id_t T, bool print); template<typename S> int latency_test(orb_id_t T, bool print);
int info(); int info();
private:
UnitTest() : pubsubtest_passed(false), pubsubtest_print(false) {}
// Disallow copy // Disallow copy
UnitTest(const uORBTest::UnitTest & /*unused*/) = delete; UnitTest(const uORBTest::UnitTest & /*unused*/) = delete;
private:
UnitTest() : pubsubtest_passed(false), pubsubtest_print(false) {}
static int pubsubtest_threadEntry(int argc, char *argv[]); static int pubsubtest_threadEntry(int argc, char *argv[]);
int pubsublatency_main(); int pubsublatency_main();

Loading…
Cancel
Save