aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/drivers/airspeed/airspeed.h4
-rw-r--r--src/drivers/device/i2c.h3
-rw-r--r--src/drivers/device/ringbuffer.h4
-rw-r--r--src/drivers/device/spi.h5
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp3
-rw-r--r--src/drivers/ets_airspeed/module.mk3
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp12
-rw-r--r--src/drivers/hmc5883/module.mk7
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp9
-rw-r--r--src/drivers/l3gd20/module.mk4
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp16
-rw-r--r--src/drivers/lsm303d/module.mk2
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp7
-rw-r--r--src/drivers/meas_airspeed/module.mk5
-rw-r--r--src/drivers/mpu6000/module.mk7
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp14
-rw-r--r--src/drivers/px4fmu/fmu.cpp5
-rw-r--r--src/drivers/px4fmu/module.mk2
-rw-r--r--src/drivers/px4io/module.mk2
-rw-r--r--src/drivers/px4io/px4io.cpp5
-rw-r--r--src/lib/mathlib/math/filter/LowPassFilter2p.hpp12
-rw-r--r--src/modules/systemlib/mixer/mixer.h15
22 files changed, 131 insertions, 15 deletions
diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h
index 0b8e949c9..d6a88714b 100644
--- a/src/drivers/airspeed/airspeed.h
+++ b/src/drivers/airspeed/airspeed.h
@@ -107,6 +107,10 @@ private:
RingBuffer *_reports;
perf_counter_t _buffer_overflows;
+ /* this class has pointer data members and should not be copied */
+ Airspeed(const Airspeed&);
+ Airspeed& operator=(const Airspeed&);
+
protected:
virtual int probe();
diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h
index 549879352..705b398b0 100644
--- a/src/drivers/device/i2c.h
+++ b/src/drivers/device/i2c.h
@@ -138,6 +138,9 @@ private:
uint16_t _address;
uint32_t _frequency;
struct i2c_dev_s *_dev;
+
+ I2C(const device::I2C&);
+ I2C operator=(const device::I2C&);
};
} // namespace device
diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h
index a9e22eaa6..b26e2e7c8 100644
--- a/src/drivers/device/ringbuffer.h
+++ b/src/drivers/device/ringbuffer.h
@@ -162,6 +162,10 @@ private:
volatile unsigned _tail; /**< removal point in _item_size units */
unsigned _next(unsigned index);
+
+ /* we don't want this class to be copied */
+ RingBuffer(const RingBuffer&);
+ RingBuffer operator=(const RingBuffer&);
};
RingBuffer::RingBuffer(unsigned num_items, size_t item_size) :
diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h
index 54849c8c3..1d9837689 100644
--- a/src/drivers/device/spi.h
+++ b/src/drivers/device/spi.h
@@ -129,10 +129,15 @@ private:
uint32_t _frequency;
struct spi_dev_s *_dev;
+ /* this class does not allow copying */
+ SPI(const SPI&);
+ SPI operator=(const SPI&);
+
protected:
int _bus;
int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
+
};
} // namespace device
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index c15a0cee4..f98d615a2 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -286,6 +286,9 @@ void info();
/**
* Start the driver.
+ *
+ * This function only returns if the sensor is up and running
+ * or could not be detected successfully.
*/
void
start(int i2c_bus)
diff --git a/src/drivers/ets_airspeed/module.mk b/src/drivers/ets_airspeed/module.mk
index 15346c5c5..966a5b819 100644
--- a/src/drivers/ets_airspeed/module.mk
+++ b/src/drivers/ets_airspeed/module.mk
@@ -36,6 +36,7 @@
#
MODULE_COMMAND = ets_airspeed
-MODULE_STACKSIZE = 2048
SRCS = ets_airspeed.cpp
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index f229ecc32..0e9a961ac 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -338,6 +338,9 @@ private:
*/
int check_offset();
+ /* this class has pointer data members, do not allow copying it */
+ HMC5883(const HMC5883&);
+ HMC5883 operator=(const HMC5883&);
};
/*
@@ -348,8 +351,10 @@ extern "C" __EXPORT int hmc5883_main(int argc, char *argv[]);
HMC5883::HMC5883(int bus, const char *path, enum Rotation rotation) :
I2C("HMC5883", path, bus, HMC5883L_ADDRESS, 400000),
+ _work{},
_measure_ticks(0),
_reports(nullptr),
+ _scale{},
_range_scale(0), /* default range scale from counts to gauss */
_range_ga(1.3f),
_collect_phase(false),
@@ -1174,7 +1179,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
out:
if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_previous)) {
- warn("WARNING: failed to set new scale / offsets for mag");
+ warn("failed to set new scale / offsets for mag");
}
/* set back to normal mode */
@@ -1370,6 +1375,9 @@ void usage();
/**
* Start the driver.
+ *
+ * This function call only returns once the driver
+ * is either successfully up and running or failed to start.
*/
void
start(int bus, enum Rotation rotation)
@@ -1465,7 +1473,7 @@ test(int bus)
int fd = open(path, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", path);
+ err(1, "%s open failed (try 'hmc5883 start')", path);
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
diff --git a/src/drivers/hmc5883/module.mk b/src/drivers/hmc5883/module.mk
index 07377556d..5daa01dc5 100644
--- a/src/drivers/hmc5883/module.mk
+++ b/src/drivers/hmc5883/module.mk
@@ -37,7 +37,8 @@
MODULE_COMMAND = hmc5883
-# XXX seems excessive, check if 2048 is sufficient
-MODULE_STACKSIZE = 4096
-
SRCS = hmc5883.cpp
+
+MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 5e90733ff..cfae8761c 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -331,12 +331,18 @@ private:
* @return 0 on success, 1 on failure
*/
int self_test();
+
+ /* this class does not allow copying */
+ L3GD20(const L3GD20&);
+ L3GD20 operator=(const L3GD20&);
};
L3GD20::L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotation) :
SPI("L3GD20", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within margins for L3GD20 */),
+ _call{},
_call_interval(0),
_reports(nullptr),
+ _gyro_scale{},
_gyro_range_scale(0.0f),
_gyro_range_rad_s(0.0f),
_gyro_topic(-1),
@@ -1003,6 +1009,9 @@ void info();
/**
* Start the driver.
+ *
+ * This function call only returns once the driver
+ * started or failed to detect the sensor.
*/
void
start(bool external_bus, enum Rotation rotation)
diff --git a/src/drivers/l3gd20/module.mk b/src/drivers/l3gd20/module.mk
index 23e77e871..5630e7aec 100644
--- a/src/drivers/l3gd20/module.mk
+++ b/src/drivers/l3gd20/module.mk
@@ -4,3 +4,7 @@
MODULE_COMMAND = l3gd20
SRCS = l3gd20.cpp
+
+MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 2750f8755..6880cf0f8 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -462,6 +462,10 @@ private:
* @return OK if the value can be supported.
*/
int mag_set_samplerate(unsigned frequency);
+
+ /* this class cannot be copied */
+ LSM303D(const LSM303D&);
+ LSM303D operator=(const LSM303D&);
};
/**
@@ -492,20 +496,28 @@ private:
void measure();
void measure_trampoline(void *arg);
+
+ /* this class does not allow copying due to ptr data members */
+ LSM303D_mag(const LSM303D_mag&);
+ LSM303D_mag operator=(const LSM303D_mag&);
};
LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rotation) :
SPI("LSM303D", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within safety margins for LSM303D */),
_mag(new LSM303D_mag(this)),
+ _accel_call{},
+ _mag_call{},
_call_accel_interval(0),
_call_mag_interval(0),
_accel_reports(nullptr),
_mag_reports(nullptr),
+ _accel_scale{},
_accel_range_m_s2(0.0f),
_accel_range_scale(0.0f),
_accel_samplerate(0),
_accel_onchip_filter_bandwith(0),
+ _mag_scale{},
_mag_range_ga(0.0f),
_mag_range_scale(0.0f),
_mag_samplerate(0),
@@ -527,6 +539,7 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rota
_reg7_expected(0),
_accel_log_fd(-1),
_accel_logging_enabled(false),
+ _last_extreme_us(0),
_last_log_us(0),
_last_log_sync_us(0),
_last_log_reg_us(0),
@@ -1829,6 +1842,9 @@ void usage();
/**
* Start the driver.
+ *
+ * This function call only returns once the driver is
+ * up and running or failed to detect the sensor.
*/
void
start(bool external_bus, enum Rotation rotation)
diff --git a/src/drivers/lsm303d/module.mk b/src/drivers/lsm303d/module.mk
index e40f718c5..b4f3974f4 100644
--- a/src/drivers/lsm303d/module.mk
+++ b/src/drivers/lsm303d/module.mk
@@ -5,4 +5,6 @@
MODULE_COMMAND = lsm303d
SRCS = lsm303d.cpp
+MODULE_STACKSIZE = 1200
+EXTRACXXFLAGS = -Weffc++
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
index 07611f903..6ab437716 100644
--- a/src/drivers/meas_airspeed/meas_airspeed.cpp
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -140,9 +140,9 @@ extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]);
MEASAirspeed::MEASAirspeed(int bus, int address, const char *path) : Airspeed(bus, address,
CONVERSION_INTERVAL, path),
_filter(MEAS_RATE, MEAS_DRIVER_FILTER_FREQ),
- _t_system_power(-1)
+ _t_system_power(-1),
+ system_power{}
{
- memset(&system_power, 0, sizeof(system_power));
}
int
@@ -420,6 +420,9 @@ void info();
/**
* Start the driver.
+ *
+ * This function call only returns once the driver is up and running
+ * or failed to detect the sensor.
*/
void
start(int i2c_bus)
diff --git a/src/drivers/meas_airspeed/module.mk b/src/drivers/meas_airspeed/module.mk
index fed4078b6..2a15b669f 100644
--- a/src/drivers/meas_airspeed/module.mk
+++ b/src/drivers/meas_airspeed/module.mk
@@ -36,6 +36,9 @@
#
MODULE_COMMAND = meas_airspeed
-MODULE_STACKSIZE = 2048
SRCS = meas_airspeed.cpp
+
+MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
diff --git a/src/drivers/mpu6000/module.mk b/src/drivers/mpu6000/module.mk
index c7d9cd3ef..5b4893b12 100644
--- a/src/drivers/mpu6000/module.mk
+++ b/src/drivers/mpu6000/module.mk
@@ -37,7 +37,8 @@
MODULE_COMMAND = mpu6000
-# XXX seems excessive, check if 2048 is not sufficient
-MODULE_STACKSIZE = 4096
-
SRCS = mpu6000.cpp
+
+MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 09eec0caf..6f5dae7ad 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -344,6 +344,9 @@ private:
*/
void _set_sample_rate(uint16_t desired_sample_rate_hz);
+ /* do not allow to copy this class due to pointer data members */
+ MPU6000(const MPU6000&);
+ MPU6000 operator=(const MPU6000&);
};
/**
@@ -371,6 +374,9 @@ private:
orb_id_t _gyro_orb_id;
int _gyro_class_instance;
+ /* do not allow to copy this class due to pointer data members */
+ MPU6000_gyro(const MPU6000_gyro&);
+ MPU6000_gyro operator=(const MPU6000_gyro&);
};
/** driver 'main' command */
@@ -380,14 +386,17 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev
SPI("MPU6000", path_accel, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED),
_gyro(new MPU6000_gyro(this, path_gyro)),
_product(0),
+ _call{},
_call_interval(0),
_accel_reports(nullptr),
+ _accel_scale{},
_accel_range_scale(0.0f),
_accel_range_m_s2(0.0f),
_accel_topic(-1),
_accel_orb_id(nullptr),
_accel_class_instance(-1),
_gyro_reports(nullptr),
+ _gyro_scale{},
_gyro_range_scale(0.0f),
_gyro_range_rad_s(0.0f),
_sample_rate(1000),
@@ -1466,6 +1475,9 @@ void usage();
/**
* Start the driver.
+ *
+ * This function only returns if the driver is up and running
+ * or failed to detect the sensor.
*/
void
start(bool external_bus, enum Rotation rotation)
@@ -1536,7 +1548,7 @@ test(bool external_bus)
int fd = open(path_accel, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)",
+ err(1, "%s open failed (try 'mpu6000 start')",
path_accel);
/* get the driver */
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 8cc1141aa..82977a032 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -179,6 +179,9 @@ private:
uint32_t gpio_read(void);
int gpio_ioctl(file *filp, int cmd, unsigned long arg);
+ /* do not allow to copy due to ptr data members */
+ PX4FMU(const PX4FMU&);
+ PX4FMU operator=(const PX4FMU&);
};
const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
@@ -242,6 +245,7 @@ PX4FMU::PX4FMU() :
_task(-1),
_armed_sub(-1),
_outputs_pub(-1),
+ _armed{},
_num_outputs(0),
_primary_pwm_device(false),
_task_should_exit(false),
@@ -252,6 +256,7 @@ PX4FMU::PX4FMU() :
_groups_subscribed(0),
_control_subs{-1},
_poll_fds_num(0),
+ _pwm_limit{},
_failsafe_pwm{0},
_disarmed_pwm{0},
_num_failsafe_set(0),
diff --git a/src/drivers/px4fmu/module.mk b/src/drivers/px4fmu/module.mk
index eeb59e1a1..a60f1a434 100644
--- a/src/drivers/px4fmu/module.mk
+++ b/src/drivers/px4fmu/module.mk
@@ -6,3 +6,5 @@ MODULE_COMMAND = fmu
SRCS = fmu.cpp
MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
diff --git a/src/drivers/px4io/module.mk b/src/drivers/px4io/module.mk
index c14f1f783..5b838fb75 100644
--- a/src/drivers/px4io/module.mk
+++ b/src/drivers/px4io/module.mk
@@ -46,3 +46,5 @@ SRCS = px4io.cpp \
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 7d78b0d27..711674886 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -453,6 +453,9 @@ private:
*/
void io_handle_vservo(uint16_t vservo, uint16_t vrssi);
+ /* do not allow to copy this class due to ptr data members */
+ PX4IO(const PX4IO&);
+ PX4IO operator=(const PX4IO&);
};
namespace
@@ -496,6 +499,8 @@ PX4IO::PX4IO(device::Device *interface) :
_to_battery(0),
_to_servorail(0),
_to_safety(0),
+ _outputs{},
+ _servorail_status{},
_primary_pwm_device(false),
_lockdown_override(false),
_battery_amp_per_volt(90.0f / 5.0f), // this matches the 3DR current sensor
diff --git a/src/lib/mathlib/math/filter/LowPassFilter2p.hpp b/src/lib/mathlib/math/filter/LowPassFilter2p.hpp
index 74cd5d78c..436065175 100644
--- a/src/lib/mathlib/math/filter/LowPassFilter2p.hpp
+++ b/src/lib/mathlib/math/filter/LowPassFilter2p.hpp
@@ -46,10 +46,18 @@ class __EXPORT LowPassFilter2p
{
public:
// constructor
- LowPassFilter2p(float sample_freq, float cutoff_freq) {
+ LowPassFilter2p(float sample_freq, float cutoff_freq) :
+ _cutoff_freq(cutoff_freq),
+ _a1(0.0f),
+ _a2(0.0f),
+ _b0(0.0f),
+ _b1(0.0f),
+ _b2(0.0f),
+ _delay_element_1(0.0f),
+ _delay_element_2(0.0f)
+ {
// set initial parameters
set_cutoff_frequency(sample_freq, cutoff_freq);
- _delay_element_1 = _delay_element_2 = 0;
}
/**
diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h
index 225570fa4..cdf60febc 100644
--- a/src/modules/systemlib/mixer/mixer.h
+++ b/src/modules/systemlib/mixer/mixer.h
@@ -231,6 +231,10 @@ protected:
static const char * skipline(const char *buf, unsigned &buflen);
private:
+
+ /* do not allow to copy due to prt data members */
+ Mixer(const Mixer&);
+ Mixer& operator=(const Mixer&);
};
/**
@@ -307,6 +311,10 @@ public:
private:
Mixer *_first; /**< linked list of mixers */
+
+ /* do not allow to copy due to pointer data members */
+ MixerGroup(const MixerGroup&);
+ MixerGroup operator=(const MixerGroup&);
};
/**
@@ -424,6 +432,10 @@ private:
mixer_scaler_s &scaler,
uint8_t &control_group,
uint8_t &control_index);
+
+ /* do not allow to copy due to ptr data members */
+ SimpleMixer(const SimpleMixer&);
+ SimpleMixer operator=(const SimpleMixer&);
};
/**
@@ -522,6 +534,9 @@ private:
unsigned _rotor_count;
const Rotor *_rotors;
+ /* do not allow to copy due to ptr data members */
+ MultirotorMixer(const MultirotorMixer&);
+ MultirotorMixer operator=(const MultirotorMixer&);
};
#endif