Browse Source

Merge pull request #1188 from PX4/sensor_startup_cleanup

Sensor startup cleanup
sbg
Lorenz Meier 11 years ago
parent
commit
7625ea5e8a
  1. 4
      src/drivers/airspeed/airspeed.h
  2. 3
      src/drivers/device/i2c.h
  3. 4
      src/drivers/device/ringbuffer.h
  4. 5
      src/drivers/device/spi.h
  5. 3
      src/drivers/ets_airspeed/ets_airspeed.cpp
  6. 3
      src/drivers/ets_airspeed/module.mk
  7. 14
      src/drivers/hmc5883/hmc5883.cpp
  8. 7
      src/drivers/hmc5883/module.mk
  9. 9
      src/drivers/l3gd20/l3gd20.cpp
  10. 4
      src/drivers/l3gd20/module.mk
  11. 16
      src/drivers/lsm303d/lsm303d.cpp
  12. 2
      src/drivers/lsm303d/module.mk
  13. 7
      src/drivers/meas_airspeed/meas_airspeed.cpp
  14. 5
      src/drivers/meas_airspeed/module.mk
  15. 7
      src/drivers/mpu6000/module.mk
  16. 14
      src/drivers/mpu6000/mpu6000.cpp
  17. 5
      src/drivers/px4fmu/fmu.cpp
  18. 2
      src/drivers/px4fmu/module.mk
  19. 2
      src/drivers/px4io/module.mk
  20. 5
      src/drivers/px4io/px4io.cpp
  21. 12
      src/lib/mathlib/math/filter/LowPassFilter2p.hpp
  22. 15
      src/modules/systemlib/mixer/mixer.h

4
src/drivers/airspeed/airspeed.h

@ -107,6 +107,10 @@ private: @@ -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();

3
src/drivers/device/i2c.h

@ -138,6 +138,9 @@ private: @@ -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

4
src/drivers/device/ringbuffer.h

@ -162,6 +162,10 @@ private: @@ -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) :

5
src/drivers/device/spi.h

@ -129,10 +129,15 @@ private: @@ -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

3
src/drivers/ets_airspeed/ets_airspeed.cpp

@ -286,6 +286,9 @@ void info(); @@ -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)

3
src/drivers/ets_airspeed/module.mk

@ -36,6 +36,7 @@ @@ -36,6 +36,7 @@
#
MODULE_COMMAND = ets_airspeed
MODULE_STACKSIZE = 2048
SRCS = ets_airspeed.cpp
MODULE_STACKSIZE = 1200

14
src/drivers/hmc5883/hmc5883.cpp

@ -337,6 +337,9 @@ private: @@ -337,6 +337,9 @@ private:
*/
int check_offset();
/* this class has pointer data members, do not allow copying it */
HMC5883(const HMC5883&);
HMC5883 operator=(const HMC5883&);
};
/*
@ -347,8 +350,10 @@ extern "C" __EXPORT int hmc5883_main(int argc, char *argv[]); @@ -347,8 +350,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),
@ -867,7 +872,7 @@ HMC5883::collect() @@ -867,7 +872,7 @@ HMC5883::collect()
struct {
int16_t x, y, z;
} report;
int ret = -EIO;
int ret;
uint8_t cmd;
uint8_t check_counter;
@ -1157,7 +1162,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable) @@ -1157,7 +1162,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 */
@ -1353,6 +1358,9 @@ void usage(); @@ -1353,6 +1358,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)
@ -1448,7 +1456,7 @@ test(int bus) @@ -1448,7 +1456,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));

7
src/drivers/hmc5883/module.mk

@ -37,7 +37,8 @@ @@ -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++

9
src/drivers/l3gd20/l3gd20.cpp

@ -330,12 +330,18 @@ private: @@ -330,12 +330,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),
@ -990,6 +996,9 @@ void info(); @@ -990,6 +996,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)

4
src/drivers/l3gd20/module.mk

@ -4,3 +4,7 @@ @@ -4,3 +4,7 @@
MODULE_COMMAND = l3gd20
SRCS = l3gd20.cpp
MODULE_STACKSIZE = 1200
EXTRACXXFLAGS = -Weffc++

16
src/drivers/lsm303d/lsm303d.cpp

@ -461,6 +461,10 @@ private: @@ -461,6 +461,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&);
};
/**
@ -490,20 +494,28 @@ private: @@ -490,20 +494,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),
@ -524,6 +536,7 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rota @@ -524,6 +536,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),
@ -1803,6 +1816,9 @@ void usage(); @@ -1803,6 +1816,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)

2
src/drivers/lsm303d/module.mk

@ -5,4 +5,6 @@ @@ -5,4 +5,6 @@
MODULE_COMMAND = lsm303d
SRCS = lsm303d.cpp
MODULE_STACKSIZE = 1200
EXTRACXXFLAGS = -Weffc++

7
src/drivers/meas_airspeed/meas_airspeed.cpp

@ -140,9 +140,9 @@ extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]); @@ -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(); @@ -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)

5
src/drivers/meas_airspeed/module.mk

@ -36,6 +36,9 @@ @@ -36,6 +36,9 @@
#
MODULE_COMMAND = meas_airspeed
MODULE_STACKSIZE = 2048
SRCS = meas_airspeed.cpp
MODULE_STACKSIZE = 1200
EXTRACXXFLAGS = -Weffc++

7
src/drivers/mpu6000/module.mk

@ -37,7 +37,8 @@ @@ -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++

14
src/drivers/mpu6000/mpu6000.cpp

@ -343,6 +343,9 @@ private: @@ -343,6 +343,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&);
};
/**
@ -369,6 +372,9 @@ private: @@ -369,6 +372,9 @@ private:
orb_advert_t _gyro_topic;
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 */
@ -378,13 +384,16 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev @@ -378,13 +384,16 @@ 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_class_instance(-1),
_gyro_reports(nullptr),
_gyro_scale{},
_gyro_range_scale(0.0f),
_gyro_range_rad_s(0.0f),
_sample_rate(1000),
@ -1437,6 +1446,9 @@ void usage(); @@ -1437,6 +1446,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)
@ -1507,7 +1519,7 @@ test(bool external_bus) @@ -1507,7 +1519,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 */

5
src/drivers/px4fmu/fmu.cpp

@ -179,6 +179,9 @@ private: @@ -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() : @@ -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() : @@ -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),

2
src/drivers/px4fmu/module.mk

@ -6,3 +6,5 @@ MODULE_COMMAND = fmu @@ -6,3 +6,5 @@ MODULE_COMMAND = fmu
SRCS = fmu.cpp
MODULE_STACKSIZE = 1200
EXTRACXXFLAGS = -Weffc++

2
src/drivers/px4io/module.mk

@ -46,3 +46,5 @@ SRCS = px4io.cpp \ @@ -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++

5
src/drivers/px4io/px4io.cpp

@ -453,6 +453,9 @@ private: @@ -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) : @@ -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

12
src/lib/mathlib/math/filter/LowPassFilter2p.hpp

@ -46,10 +46,18 @@ class __EXPORT LowPassFilter2p @@ -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;
}
/**

15
src/modules/systemlib/mixer/mixer.h

@ -231,6 +231,10 @@ protected: @@ -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: @@ -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: @@ -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: @@ -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

Loading…
Cancel
Save