aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/10016_3dr_iris3
-rw-r--r--ROMFS/px4fmu_common/init.d/4010_dji_f3304
-rw-r--r--ROMFS/px4fmu_common/init.d/4011_dji_f4504
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.sensors39
-rw-r--r--makefiles/config_px4fmu-v2_test.mk5
-rw-r--r--src/drivers/airspeed/airspeed.h4
-rw-r--r--src/drivers/device/device.h11
-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/drv_accel.h4
-rw-r--r--src/drivers/drv_baro.h3
-rw-r--r--src/drivers/drv_gyro.h4
-rw-r--r--src/drivers/drv_mag.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.cpp48
-rw-r--r--src/drivers/hmc5883/module.mk7
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp44
-rw-r--r--src/drivers/l3gd20/module.mk4
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp82
-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.cpp81
-rw-r--r--src/drivers/ms5611/ms5611.cpp27
-rw-r--r--src/drivers/pca8574/module.mk2
-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/drivers/px4io/px4io_uploader.cpp51
-rw-r--r--src/drivers/px4io/uploader.h1
-rw-r--r--src/drivers/rgbled/module.mk2
-rw-r--r--src/examples/matlab_csv_serial/matlab_csv_serial.c247
-rw-r--r--src/examples/matlab_csv_serial/module.mk40
-rw-r--r--src/lib/mathlib/math/Matrix.hpp25
-rw-r--r--src/lib/mathlib/math/Vector.hpp21
-rw-r--r--src/lib/mathlib/math/filter/LowPassFilter2p.hpp12
-rw-r--r--src/modules/commander/commander.cpp2
-rw-r--r--src/modules/commander/gyro_calibration.cpp4
-rw-r--r--src/modules/commander/mag_calibration.cpp4
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp19
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_utilities.cpp7
-rw-r--r--src/modules/ekf_att_pos_estimator/module.mk2
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp4
-rw-r--r--src/modules/mavlink/mavlink_commands.cpp7
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp16
-rw-r--r--src/modules/mavlink/mavlink_main.cpp10
-rw-r--r--src/modules/mavlink/mavlink_main.h4
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp144
-rw-r--r--src/modules/mavlink/mavlink_mission.h4
-rw-r--r--src/modules/mavlink/mavlink_orb_subscription.h4
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp32
-rw-r--r--src/modules/mavlink/mavlink_receiver.h4
-rw-r--r--src/modules/mavlink/mavlink_stream.h4
-rw-r--r--src/modules/mavlink/module.mk2
-rw-r--r--src/modules/sdlog2/sdlog2.c66
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h10
-rw-r--r--src/modules/sensors/sensor_params.c13
-rw-r--r--src/modules/sensors/sensors.cpp126
-rw-r--r--src/modules/systemlib/mixer/mixer.h15
-rw-r--r--src/modules/uORB/objects_common.cpp15
-rw-r--r--src/modules/uORB/topics/sensor_combined.h24
65 files changed, 1173 insertions, 202 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
index 084dff140..3f47390c1 100644
--- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
@@ -30,3 +30,6 @@ fi
set MIXER FMU_quad_w
set PWM_OUTPUTS 1234
+
+set PWM_MIN 1200
+set PWM_MAX 1950
diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330
index e6e2e19dc..282ab620d 100644
--- a/ROMFS/px4fmu_common/init.d/4010_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330
@@ -23,5 +23,5 @@ then
param set MC_YAWRATE_D 0.0
fi
-set PWM_MIN 1175
-set PWM_MAX 1900
+set PWM_MIN 1200
+set PWM_MAX 1950
diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450
index 3465b59cf..517b4aa86 100644
--- a/ROMFS/px4fmu_common/init.d/4011_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450
@@ -24,5 +24,5 @@ then
param set MC_YAWRATE_D 0.0
fi
-set PWM_MIN 1175
-set PWM_MAX 1900
+set PWM_MIN 1230
+set PWM_MAX 1950
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index be54ea98b..ecb408a54 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -6,28 +6,51 @@
ms5611 start
adc start
-# Mag might be external
-if hmc5883 start
+if mpu6000 -X start
then
- echo "[init] Using HMC5883"
fi
if mpu6000 start
then
- echo "[init] Using MPU6000"
+fi
+
+if l3gd20 -X start
+then
fi
if l3gd20 start
then
- echo "[init] Using L3GD20(H)"
+fi
+
+# MAG selection
+if param compare SENS_EXT_MAG 2
+then
+ if hmc5883 -I start
+ then
+ fi
+else
+ # Use only external as primary
+ if param compare SENS_EXT_MAG 1
+ then
+ if hmc5883 -X start
+ then
+ fi
+ else
+ # auto-detect the primary, prefer external
+ if hmc5883 start
+ then
+ fi
+ fi
fi
if ver hwcmp PX4FMU_V2
then
- # IMPORTANT: EXTERNAL BUSES SHOULD BE SCANNED FIRST
+ if lsm303d -X start
+ then
+ fi
+
if lsm303d start
then
- echo "[init] Using LSM303D"
fi
fi
@@ -38,11 +61,9 @@ then
else
if ets_airspeed start
then
- echo "[init] Using ETS airspeed sensor (bus 3)"
else
if ets_airspeed start -b 1
then
- echo "[init] Using ETS airspeed sensor (bus 1)"
fi
fi
fi
diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk
index 395a8f2ac..932f92261 100644
--- a/makefiles/config_px4fmu-v2_test.mk
+++ b/makefiles/config_px4fmu-v2_test.mk
@@ -34,6 +34,11 @@ MODULES += systemcmds/mtd
MODULES += systemcmds/ver
#
+# Testing modules
+#
+MODULES += examples/matlab_csv_serial
+
+#
# Library modules
#
MODULES += modules/systemlib
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/device.h b/src/drivers/device/device.h
index 7df234cab..9d684e394 100644
--- a/src/drivers/device/device.h
+++ b/src/drivers/device/device.h
@@ -240,6 +240,7 @@ private:
* @param context Pointer to the interrupted context.
*/
static void dev_interrupt(int irq, void *context);
+
};
/**
@@ -469,6 +470,10 @@ private:
* @return OK, or -errno on error.
*/
int remove_poll_waiter(struct pollfd *fds);
+
+ /* do not allow copying this class */
+ CDev(const CDev&);
+ CDev operator=(const CDev&);
};
/**
@@ -538,6 +543,10 @@ private:
} // namespace device
// class instance for primary driver of each class
-#define CLASS_DEVICE_PRIMARY 0
+enum CLASS_DEVICE {
+ CLASS_DEVICE_PRIMARY=0,
+ CLASS_DEVICE_SECONDARY=1,
+ CLASS_DEVICE_TERTIARY=2
+};
#endif /* _DEVICE_DEVICE_H */
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/drv_accel.h b/src/drivers/drv_accel.h
index 7d93ed938..1f98d966b 100644
--- a/src/drivers/drv_accel.h
+++ b/src/drivers/drv_accel.h
@@ -81,7 +81,9 @@ struct accel_scale {
/*
* ObjDev tag for raw accelerometer data.
*/
-ORB_DECLARE(sensor_accel);
+ORB_DECLARE(sensor_accel0);
+ORB_DECLARE(sensor_accel1);
+ORB_DECLARE(sensor_accel2);
/*
* ioctl() definitions
diff --git a/src/drivers/drv_baro.h b/src/drivers/drv_baro.h
index e2f0137ae..248b9a73d 100644
--- a/src/drivers/drv_baro.h
+++ b/src/drivers/drv_baro.h
@@ -63,7 +63,8 @@ struct baro_report {
/*
* ObjDev tag for raw barometer data.
*/
-ORB_DECLARE(sensor_baro);
+ORB_DECLARE(sensor_baro0);
+ORB_DECLARE(sensor_baro1);
/*
* ioctl() definitions
diff --git a/src/drivers/drv_gyro.h b/src/drivers/drv_gyro.h
index 2ae8c7058..41b013a44 100644
--- a/src/drivers/drv_gyro.h
+++ b/src/drivers/drv_gyro.h
@@ -81,7 +81,9 @@ struct gyro_scale {
/*
* ObjDev tag for raw gyro data.
*/
-ORB_DECLARE(sensor_gyro);
+ORB_DECLARE(sensor_gyro0);
+ORB_DECLARE(sensor_gyro1);
+ORB_DECLARE(sensor_gyro2);
/*
* ioctl() definitions
diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h
index a259ac9c0..5ddf5d08e 100644
--- a/src/drivers/drv_mag.h
+++ b/src/drivers/drv_mag.h
@@ -79,8 +79,9 @@ struct mag_scale {
/*
* ObjDev tag for raw magnetometer data.
*/
-ORB_DECLARE(sensor_mag);
-
+ORB_DECLARE(sensor_mag0);
+ORB_DECLARE(sensor_mag1);
+ORB_DECLARE(sensor_mag2);
/*
* mag device types, for _device_id
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 4aef43102..0e9a961ac 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -162,6 +162,7 @@ private:
orb_advert_t _mag_topic;
orb_advert_t _subsystem_pub;
+ orb_id_t _mag_orb_id;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
@@ -337,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&);
};
/*
@@ -347,14 +351,17 @@ 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),
_class_instance(-1),
_mag_topic(-1),
_subsystem_pub(-1),
+ _mag_orb_id(nullptr),
_sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")),
_comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")),
_buffer_overflows(perf_alloc(PC_COUNT, "hmc5883_buffer_overflows")),
@@ -423,6 +430,20 @@ HMC5883::init()
_class_instance = register_class_devname(MAG_DEVICE_PATH);
+ switch (_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _mag_orb_id = ORB_ID(sensor_mag0);
+ break;
+
+ case CLASS_DEVICE_SECONDARY:
+ _mag_orb_id = ORB_ID(sensor_mag1);
+ break;
+
+ case CLASS_DEVICE_TERTIARY:
+ _mag_orb_id = ORB_ID(sensor_mag2);
+ break;
+ }
+
ret = OK;
/* sensor is ok, but not calibrated */
_sensor_ok = true;
@@ -867,7 +888,8 @@ HMC5883::collect()
struct {
int16_t x, y, z;
} report;
- int ret = -EIO;
+
+ int ret;
uint8_t cmd;
uint8_t check_counter;
@@ -945,16 +967,16 @@ HMC5883::collect()
// apply user specified rotation
rotate_3f(_rotation, new_report.x, new_report.y, new_report.z);
- if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
if (_mag_topic != -1) {
/* publish it */
- orb_publish(ORB_ID(sensor_mag), _mag_topic, &new_report);
+ orb_publish(_mag_orb_id, _mag_topic, &new_report);
} else {
- _mag_topic = orb_advertise(ORB_ID(sensor_mag), &new_report);
+ _mag_topic = orb_advertise(_mag_orb_id, &new_report);
if (_mag_topic < 0)
- debug("failed to create sensor_mag publication");
+ debug("ADVERT FAIL");
}
}
@@ -1157,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 */
@@ -1341,8 +1363,8 @@ namespace hmc5883
#endif
const int ERROR = -1;
-HMC5883 *g_dev_int;
-HMC5883 *g_dev_ext;
+HMC5883 *g_dev_int = nullptr;
+HMC5883 *g_dev_ext = nullptr;
void start(int bus, enum Rotation rotation);
void test(int bus);
@@ -1353,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)
@@ -1378,6 +1403,11 @@ start(int bus, enum Rotation rotation)
errx(0, "already started internal");
g_dev_int = new HMC5883(PX4_I2C_BUS_ONBOARD, HMC5883L_DEVICE_PATH_INT, rotation);
if (g_dev_int != nullptr && OK != g_dev_int->init()) {
+
+ /* tear down the failing onboard instance */
+ delete g_dev_int;
+ g_dev_int = nullptr;
+
if (bus == PX4_I2C_BUS_ONBOARD) {
goto fail;
}
@@ -1443,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 64d1a7e55..cfae8761c 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -213,6 +213,7 @@ private:
float _gyro_range_scale;
float _gyro_range_rad_s;
orb_advert_t _gyro_topic;
+ orb_id_t _orb_id;
int _class_instance;
unsigned _current_rate;
@@ -330,15 +331,22 @@ 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),
+ _orb_id(nullptr),
_class_instance(-1),
_current_rate(0),
_orientation(SENSOR_BOARD_ROTATION_DEFAULT),
@@ -399,21 +407,32 @@ L3GD20::init()
_class_instance = register_class_devname(GYRO_DEVICE_PATH);
- reset();
+ switch (_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _orb_id = ORB_ID(sensor_gyro0);
+ break;
- measure();
+ case CLASS_DEVICE_SECONDARY:
+ _orb_id = ORB_ID(sensor_gyro1);
+ break;
- if (_class_instance == CLASS_DEVICE_PRIMARY) {
+ case CLASS_DEVICE_TERTIARY:
+ _orb_id = ORB_ID(sensor_gyro2);
+ break;
+ }
- /* advertise sensor topic, measure manually to initialize valid report */
- struct gyro_report grp;
- _reports->get(&grp);
+ reset();
- _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grp);
+ measure();
- if (_gyro_topic < 0)
- debug("failed to create sensor_gyro publication");
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct gyro_report grp;
+ _reports->get(&grp);
+ _gyro_topic = orb_advertise(_orb_id, &grp);
+
+ if (_gyro_topic < 0) {
+ debug("failed to create sensor_gyro publication");
}
ret = OK;
@@ -931,9 +950,9 @@ L3GD20::measure()
poll_notify(POLLIN);
/* publish for subscribers */
- if (_gyro_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &report);
+ orb_publish(_orb_id, _gyro_topic, &report);
}
_read++;
@@ -990,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 45e775055..6880cf0f8 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -284,6 +284,7 @@ private:
unsigned _mag_samplerate;
orb_advert_t _accel_topic;
+ orb_id_t _accel_orb_id;
int _accel_class_instance;
unsigned _accel_read;
@@ -461,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&);
};
/**
@@ -485,29 +490,39 @@ private:
LSM303D *_parent;
orb_advert_t _mag_topic;
+ orb_id_t _mag_orb_id;
int _mag_class_instance;
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),
_accel_topic(-1),
+ _accel_orb_id(nullptr),
_accel_class_instance(-1),
_accel_read(0),
_mag_read(0),
@@ -524,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),
@@ -611,34 +627,56 @@ LSM303D::init()
/* fill report structures */
measure();
- if (_mag->_mag_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct mag_report mrp;
+ _mag_reports->get(&mrp);
- /* advertise sensor topic, measure manually to initialize valid report */
- struct mag_report mrp;
- _mag_reports->get(&mrp);
+ /* measurement will have generated a report, publish */
+ switch (_mag->_mag_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _mag->_mag_orb_id = ORB_ID(sensor_mag0);
+ break;
- /* measurement will have generated a report, publish */
- _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag), &mrp);
+ case CLASS_DEVICE_SECONDARY:
+ _mag->_mag_orb_id = ORB_ID(sensor_mag1);
+ break;
+
+ case CLASS_DEVICE_TERTIARY:
+ _mag->_mag_orb_id = ORB_ID(sensor_mag2);
+ break;
+ }
- if (_mag->_mag_topic < 0)
- debug("failed to create sensor_mag publication");
+ _mag->_mag_topic = orb_advertise(_mag->_mag_orb_id, &mrp);
+ if (_mag->_mag_topic < 0) {
+ warnx("ADVERT ERR");
}
_accel_class_instance = register_class_devname(ACCEL_DEVICE_PATH);
- if (_accel_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct accel_report arp;
+ _accel_reports->get(&arp);
- /* advertise sensor topic, measure manually to initialize valid report */
- struct accel_report arp;
- _accel_reports->get(&arp);
+ /* measurement will have generated a report, publish */
+ switch (_accel_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _accel_orb_id = ORB_ID(sensor_accel0);
+ break;
+
+ case CLASS_DEVICE_SECONDARY:
+ _accel_orb_id = ORB_ID(sensor_accel1);
+ break;
- /* measurement will have generated a report, publish */
- _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp);
+ case CLASS_DEVICE_TERTIARY:
+ _accel_orb_id = ORB_ID(sensor_accel2);
+ break;
+ }
- if (_accel_topic < 0)
- debug("failed to create sensor_accel publication");
+ _accel_topic = orb_advertise(_accel_orb_id, &arp);
+ if (_accel_topic < 0) {
+ warnx("ADVERT ERR");
}
out:
@@ -1557,9 +1595,9 @@ LSM303D::measure()
/* notify anyone waiting for data */
poll_notify(POLLIN);
- if (_accel_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_accel), _accel_topic, &accel_report);
+ orb_publish(_accel_orb_id, _accel_topic, &accel_report);
}
_accel_read++;
@@ -1634,9 +1672,9 @@ LSM303D::mag_measure()
/* notify anyone waiting for data */
poll_notify(POLLIN);
- if (_mag->_mag_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_mag), _mag->_mag_topic, &mag_report);
+ orb_publish(_mag->_mag_orb_id, _mag->_mag_topic, &mag_report);
}
_mag_read++;
@@ -1730,6 +1768,7 @@ LSM303D_mag::LSM303D_mag(LSM303D *parent) :
CDev("LSM303D_mag", LSM303D_DEVICE_PATH_MAG),
_parent(parent),
_mag_topic(-1),
+ _mag_orb_id(nullptr),
_mag_class_instance(-1)
{
}
@@ -1803,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 1b3a96a0d..6f5dae7ad 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -215,6 +215,7 @@ private:
float _accel_range_scale;
float _accel_range_m_s2;
orb_advert_t _accel_topic;
+ orb_id_t _accel_orb_id;
int _accel_class_instance;
RingBuffer *_gyro_reports;
@@ -343,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&);
};
/**
@@ -367,8 +371,12 @@ protected:
private:
MPU6000 *_parent;
orb_advert_t _gyro_topic;
+ 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 */
@@ -378,13 +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),
@@ -498,33 +510,58 @@ MPU6000::init()
measure();
- if (_accel_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct accel_report arp;
+ _accel_reports->get(&arp);
- /* advertise sensor topic, measure manually to initialize valid report */
- struct accel_report arp;
- _accel_reports->get(&arp);
+ /* measurement will have generated a report, publish */
+ switch (_accel_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _accel_orb_id = ORB_ID(sensor_accel0);
+ break;
+
+ case CLASS_DEVICE_SECONDARY:
+ _accel_orb_id = ORB_ID(sensor_accel1);
+ break;
- /* measurement will have generated a report, publish */
- _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp);
+ case CLASS_DEVICE_TERTIARY:
+ _accel_orb_id = ORB_ID(sensor_accel2);
+ break;
- if (_accel_topic < 0)
- debug("failed to create sensor_accel publication");
+ }
+
+ _accel_topic = orb_advertise(_accel_orb_id, &arp);
+ if (_accel_topic < 0) {
+ warnx("ADVERT FAIL");
}
- if (_gyro->_gyro_class_instance == CLASS_DEVICE_PRIMARY) {
- /* advertise sensor topic, measure manually to initialize valid report */
- struct gyro_report grp;
- _gyro_reports->get(&grp);
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct gyro_report grp;
+ _gyro_reports->get(&grp);
+
+ switch (_gyro->_gyro_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _gyro->_gyro_orb_id = ORB_ID(sensor_gyro0);
+ break;
- _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grp);
+ case CLASS_DEVICE_SECONDARY:
+ _gyro->_gyro_orb_id = ORB_ID(sensor_gyro1);
+ break;
- if (_gyro->_gyro_topic < 0)
- debug("failed to create sensor_gyro publication");
+ case CLASS_DEVICE_TERTIARY:
+ _gyro->_gyro_orb_id = ORB_ID(sensor_gyro2);
+ break;
}
+ _gyro->_gyro_topic = orb_advertise(_gyro->_gyro_orb_id, &grp);
+
+ if (_gyro->_gyro_topic < 0) {
+ warnx("ADVERT FAIL");
+ }
+
out:
return ret;
}
@@ -1345,14 +1382,14 @@ MPU6000::measure()
poll_notify(POLLIN);
_gyro->parent_poll_notify();
- if (_accel_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb);
+ orb_publish(_accel_orb_id, _accel_topic, &arb);
}
- if (_gyro->_gyro_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_gyro), _gyro->_gyro_topic, &grb);
+ orb_publish(_gyro->_gyro_orb_id, _gyro->_gyro_topic, &grb);
}
/* stop measuring */
@@ -1373,6 +1410,7 @@ MPU6000_gyro::MPU6000_gyro(MPU6000 *parent, const char *path) :
CDev("MPU6000_gyro", path),
_parent(parent),
_gyro_topic(-1),
+ _gyro_orb_id(nullptr),
_gyro_class_instance(-1)
{
}
@@ -1437,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)
@@ -1507,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/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index fe669b5f5..873fa62c4 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -300,12 +300,17 @@ MS5611::init()
ret = OK;
- if (_class_instance == CLASS_DEVICE_PRIMARY) {
-
- _baro_topic = orb_advertise(ORB_ID(sensor_baro), &brp);
+ switch (_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _baro_topic = orb_advertise(ORB_ID(sensor_baro0), &brp);
+ break;
+ case CLASS_DEVICE_SECONDARY:
+ _baro_topic = orb_advertise(ORB_ID(sensor_baro1), &brp);
+ break;
+ }
- if (_baro_topic < 0)
- debug("failed to create sensor_baro publication");
+ if (_baro_topic < 0) {
+ warnx("failed to create sensor_baro publication");
}
} while (0);
@@ -722,9 +727,17 @@ MS5611::collect()
report.altitude = (((pow((p / p1), (-(a * R) / g))) * T1) - T1) / a;
/* publish it */
- if (_baro_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_baro), _baro_topic, &report);
+ switch (_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ orb_publish(ORB_ID(sensor_baro0), _baro_topic, &report);
+ break;
+
+ case CLASS_DEVICE_SECONDARY:
+ orb_publish(ORB_ID(sensor_baro1), _baro_topic, &report);
+ break;
+ }
}
if (_reports->force(&report)) {
diff --git a/src/drivers/pca8574/module.mk b/src/drivers/pca8574/module.mk
index 825ee9bb7..c53ed9ab2 100644
--- a/src/drivers/pca8574/module.mk
+++ b/src/drivers/pca8574/module.mk
@@ -4,3 +4,5 @@
MODULE_COMMAND = pca8574
SRCS = pca8574.cpp
+
+MAXOPTIMIZATION = -Os
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/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp
index d134c0246..bf6893a7e 100644
--- a/src/drivers/px4io/px4io_uploader.cpp
+++ b/src/drivers/px4io/px4io_uploader.cpp
@@ -204,12 +204,8 @@ PX4IO_Uploader::upload(const char *filenames[])
if (bl_rev <= 2) {
ret = verify_rev2(fw_size);
- } else if(bl_rev == 3) {
- ret = verify_rev3(fw_size);
} else {
- /* verify rev 4 and higher still uses the same approach and
- * every version *needs* to be verified.
- */
+ /* verify rev 3 and higher. Every version *needs* to be verified. */
ret = verify_rev3(fw_size);
}
@@ -276,14 +272,14 @@ PX4IO_Uploader::recv(uint8_t &c, unsigned timeout)
int
PX4IO_Uploader::recv(uint8_t *p, unsigned count)
{
+ int ret;
while (count--) {
- int ret = recv(*p++, 5000);
+ ret = recv(*p++, 5000);
if (ret != OK)
- return ret;
+ break;
}
-
- return OK;
+ return ret;
}
void
@@ -314,21 +310,19 @@ PX4IO_Uploader::send(uint8_t c)
#endif
if (write(_io_fd, &c, 1) != 1)
return -errno;
-
return OK;
}
int
PX4IO_Uploader::send(uint8_t *p, unsigned count)
{
+ int ret;
while (count--) {
- int ret = send(*p++);
-
+ ret = send(*p++);
if (ret != OK)
- return ret;
+ break;
}
-
- return OK;
+ return ret;
}
int
@@ -419,12 +413,15 @@ PX4IO_Uploader::program(size_t fw_size)
int ret;
size_t sent = 0;
- file_buf = (uint8_t *)malloc(PROG_MULTI_MAX);
+ file_buf = new uint8_t[PROG_MULTI_MAX];
if (!file_buf) {
log("Can't allocate program buffer");
return -ENOMEM;
}
+ ASSERT((fw_size & 3) == 0);
+ ASSERT((PROG_MULTI_MAX & 3) == 0);
+
log("programming %u bytes...", (unsigned)fw_size);
ret = lseek(_fw_fd, 0, SEEK_SET);
@@ -443,34 +440,26 @@ PX4IO_Uploader::program(size_t fw_size)
(unsigned)sent,
(int)count,
(int)errno);
- }
-
- if (count == 0) {
- free(file_buf);
- return OK;
+ ret = -errno;
+ break;
}
sent += count;
- if (count < 0)
- return -errno;
-
- ASSERT((count % 4) == 0);
-
send(PROTO_PROG_MULTI);
send(count);
- send(&file_buf[0], count);
+ send(file_buf, count);
send(PROTO_EOC);
ret = get_sync(1000);
if (ret != OK) {
- free(file_buf);
- return ret;
+ break;
}
}
- free(file_buf);
- return OK;
+
+ delete [] file_buf;
+ return ret;
}
int
diff --git a/src/drivers/px4io/uploader.h b/src/drivers/px4io/uploader.h
index 55f63eef9..3e2142cf2 100644
--- a/src/drivers/px4io/uploader.h
+++ b/src/drivers/px4io/uploader.h
@@ -75,7 +75,6 @@ private:
INFO_FLASH_SIZE = 4, /**< max firmware size in bytes */
PROG_MULTI_MAX = 60, /**< protocol max is 255, must be multiple of 4 */
- READ_MULTI_MAX = 60, /**< protocol max is 255, something overflows with >= 64 */
};
diff --git a/src/drivers/rgbled/module.mk b/src/drivers/rgbled/module.mk
index 39b53ec9e..c287e35f3 100644
--- a/src/drivers/rgbled/module.mk
+++ b/src/drivers/rgbled/module.mk
@@ -4,3 +4,5 @@
MODULE_COMMAND = rgbled
SRCS = rgbled.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/examples/matlab_csv_serial/matlab_csv_serial.c b/src/examples/matlab_csv_serial/matlab_csv_serial.c
new file mode 100644
index 000000000..c66bebeec
--- /dev/null
+++ b/src/examples/matlab_csv_serial/matlab_csv_serial.c
@@ -0,0 +1,247 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file matlab_csv_serial_main.c
+ *
+ * Matlab CSV / ASCII format interface at 921600 baud, 8 data bits,
+ * 1 stop bit, no parity
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <float.h>
+#include <nuttx/sched.h>
+#include <sys/prctl.h>
+#include <drivers/drv_hrt.h>
+#include <termios.h>
+#include <errno.h>
+#include <limits.h>
+#include <math.h>
+#include <uORB/uORB.h>
+#include <drivers/drv_accel.h>
+#include <drivers/drv_gyro.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
+#include <poll.h>
+
+__EXPORT int matlab_csv_serial_main(int argc, char *argv[]);
+static bool thread_should_exit = false; /**< Daemon exit flag */
+static bool thread_running = false; /**< Daemon status flag */
+static int daemon_task; /**< Handle of daemon task / thread */
+
+int matlab_csv_serial_thread_main(int argc, char *argv[]);
+static void usage(const char *reason);
+
+static void usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+ fprintf(stderr, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
+ exit(1);
+}
+
+/**
+ * The daemon app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_spawn_cmd().
+ */
+int matlab_csv_serial_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start"))
+ {
+ if (thread_running)
+ {
+ warnx("already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+ daemon_task = task_spawn_cmd("matlab_csv_serial",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2000,
+ matlab_csv_serial_thread_main,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop"))
+ {
+ thread_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status"))
+ {
+ if (thread_running) {
+ warnx("running");
+ } else {
+ warnx("stopped");
+ }
+
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+int matlab_csv_serial_thread_main(int argc, char *argv[])
+{
+
+ if (argc < 2) {
+ errx(1, "need a serial port name as argument");
+ }
+
+ const char* uart_name = argv[1];
+
+ warnx("opening port %s", uart_name);
+
+ int serial_fd = open(uart_name, O_RDWR | O_NOCTTY);
+
+ unsigned speed = 921600;
+
+ if (serial_fd < 0) {
+ err(1, "failed to open port: %s", uart_name);
+ }
+
+ /* Try to set baud rate */
+ struct termios uart_config;
+ int termios_state;
+
+ /* Back up the original uart configuration to restore it after exit */
+ if ((termios_state = tcgetattr(serial_fd, &uart_config)) < 0) {
+ warnx("ERR GET CONF %s: %d\n", uart_name, termios_state);
+ close(serial_fd);
+ return -1;
+ }
+
+ /* Clear ONLCR flag (which appends a CR for every LF) */
+ uart_config.c_oflag &= ~ONLCR;
+
+ /* USB serial is indicated by /dev/ttyACM0*/
+ if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/ttyACM1") != OK) {
+
+ /* Set baud rate */
+ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
+ warnx("ERR SET BAUD %s: %d\n", uart_name, termios_state);
+ close(serial_fd);
+ return -1;
+ }
+
+ }
+
+ if ((termios_state = tcsetattr(serial_fd, TCSANOW, &uart_config)) < 0) {
+ warnx("ERR SET CONF %s\n", uart_name);
+ close(serial_fd);
+ return -1;
+ }
+
+ /* subscribe to vehicle status, attitude, sensors and flow*/
+ struct accel_report accel0;
+ struct accel_report accel1;
+ struct gyro_report gyro0;
+ struct gyro_report gyro1;
+
+ /* subscribe to parameter changes */
+ int accel0_sub = orb_subscribe(ORB_ID(sensor_accel0));
+ int accel1_sub = orb_subscribe(ORB_ID(sensor_accel1));
+ int gyro0_sub = orb_subscribe(ORB_ID(sensor_gyro0));
+ int gyro1_sub = orb_subscribe(ORB_ID(sensor_gyro1));
+
+ thread_running = true;
+
+ while (!thread_should_exit)
+ {
+
+ /*This runs at the rate of the sensors */
+ struct pollfd fds[] = {
+ { .fd = accel0_sub, .events = POLLIN }
+ };
+
+ /* wait for a sensor update, check for exit condition every 500 ms */
+ int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), 500);
+
+ if (ret < 0)
+ {
+ /* poll error, ignore */
+
+ }
+ else if (ret == 0)
+ {
+ /* no return value, ignore */
+ warnx("no sensor data");
+ }
+ else
+ {
+
+ /* accel0 update available? */
+ if (fds[0].revents & POLLIN)
+ {
+ orb_copy(ORB_ID(sensor_accel0), accel0_sub, &accel0);
+ orb_copy(ORB_ID(sensor_accel1), accel1_sub, &accel1);
+ orb_copy(ORB_ID(sensor_gyro0), gyro0_sub, &gyro0);
+ orb_copy(ORB_ID(sensor_gyro1), gyro1_sub, &gyro1);
+
+ // write out on accel 0, but collect for all other sensors as they have updates
+ dprintf(serial_fd, "%llu,%d,%d,%d,%d,%d,%d\n", accel0.timestamp, (int)accel0.x_raw, (int)accel0.y_raw, (int)accel0.z_raw,
+ (int)accel1.x_raw, (int)accel1.y_raw, (int)accel1.z_raw);
+ }
+
+ }
+ }
+
+ warnx("exiting");
+ thread_running = false;
+
+ fflush(stdout);
+ return 0;
+}
+
+
diff --git a/src/examples/matlab_csv_serial/module.mk b/src/examples/matlab_csv_serial/module.mk
new file mode 100644
index 000000000..1629c2ce4
--- /dev/null
+++ b/src/examples/matlab_csv_serial/module.mk
@@ -0,0 +1,40 @@
+############################################################################
+#
+# Copyright (c) 2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Build position estimator
+#
+
+MODULE_COMMAND = matlab_csv_serial
+
+SRCS = matlab_csv_serial.c
diff --git a/src/lib/mathlib/math/Matrix.hpp b/src/lib/mathlib/math/Matrix.hpp
index ea0cf4ca1..ca931e2da 100644
--- a/src/lib/mathlib/math/Matrix.hpp
+++ b/src/lib/mathlib/math/Matrix.hpp
@@ -69,27 +69,34 @@ public:
/**
* trivial ctor
- * note that this ctor will not initialize elements
+ * Initializes the elements to zero.
*/
- MatrixBase() {
- arm_mat = {M, N, &data[0][0]};
+ MatrixBase() :
+ data{},
+ arm_mat{M, N, &data[0][0]}
+ {
}
+ virtual ~MatrixBase() {};
+
/**
* copyt ctor
*/
- MatrixBase(const MatrixBase<M, N> &m) {
- arm_mat = {M, N, &data[0][0]};
+ MatrixBase(const MatrixBase<M, N> &m) :
+ arm_mat{M, N, &data[0][0]}
+ {
memcpy(data, m.data, sizeof(data));
}
- MatrixBase(const float *d) {
- arm_mat = {M, N, &data[0][0]};
+ MatrixBase(const float *d) :
+ arm_mat{M, N, &data[0][0]}
+ {
memcpy(data, d, sizeof(data));
}
- MatrixBase(const float d[M][N]) {
- arm_mat = {M, N, &data[0][0]};
+ MatrixBase(const float d[M][N]) :
+ arm_mat{M, N, &data[0][0]}
+ {
memcpy(data, d, sizeof(data));
}
diff --git a/src/lib/mathlib/math/Vector.hpp b/src/lib/mathlib/math/Vector.hpp
index c7323c215..0ddf77615 100644
--- a/src/lib/mathlib/math/Vector.hpp
+++ b/src/lib/mathlib/math/Vector.hpp
@@ -69,25 +69,32 @@ public:
/**
* trivial ctor
- * note that this ctor will not initialize elements
+ * initializes elements to zero
*/
- VectorBase() {
- arm_col = {N, 1, &data[0]};
+ VectorBase() :
+ data{},
+ arm_col{N, 1, &data[0]}
+ {
+
}
+ virtual ~VectorBase() {};
+
/**
* copy ctor
*/
- VectorBase(const VectorBase<N> &v) {
- arm_col = {N, 1, &data[0]};
+ VectorBase(const VectorBase<N> &v) :
+ arm_col{N, 1, &data[0]}
+ {
memcpy(data, v.data, sizeof(data));
}
/**
* setting ctor
*/
- VectorBase(const float d[N]) {
- arm_col = {N, 1, &data[0]};
+ VectorBase(const float d[N]) :
+ arm_col{N, 1, &data[0]}
+ {
memcpy(data, d, sizeof(data));
}
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/commander/commander.cpp b/src/modules/commander/commander.cpp
index fc9560e18..bdeb0b3d4 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1463,7 +1463,7 @@ int commander_thread_main(int argc, char *argv[])
/* data links check */
bool have_link = false;
for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
- if (hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) {
+ if (telemetry_last_heartbeat[i] != 0 && hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) {
/* handle the case where data link was regained */
if (telemetry_lost[i]) {
mavlink_log_critical(mavlink_fd, "data link %i regained", i);
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index cbc2844c1..d89c67c2b 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -92,7 +92,7 @@ int do_gyro_calibration(int mavlink_fd)
unsigned poll_errcount = 0;
/* subscribe to gyro sensor topic */
- int sub_sensor_gyro = orb_subscribe(ORB_ID(sensor_gyro));
+ int sub_sensor_gyro = orb_subscribe(ORB_ID(sensor_gyro0));
struct gyro_report gyro_report;
while (calibration_counter < calibration_count) {
@@ -104,7 +104,7 @@ int do_gyro_calibration(int mavlink_fd)
int poll_ret = poll(fds, 1, 1000);
if (poll_ret > 0) {
- orb_copy(ORB_ID(sensor_gyro), sub_sensor_gyro, &gyro_report);
+ orb_copy(ORB_ID(sensor_gyro0), sub_sensor_gyro, &gyro_report);
gyro_scale.x_offset += gyro_report.x;
gyro_scale.y_offset += gyro_report.y;
gyro_scale.z_offset += gyro_report.z;
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 0ead22f77..23900f386 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -145,7 +145,7 @@ int do_mag_calibration(int mavlink_fd)
}
if (res == OK) {
- int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
+ int sub_mag = orb_subscribe(ORB_ID(sensor_mag0));
struct mag_report mag;
/* limit update rate to get equally spaced measurements over time (in ms) */
@@ -170,7 +170,7 @@ int do_mag_calibration(int mavlink_fd)
int poll_ret = poll(fds, 1, 1000);
if (poll_ret > 0) {
- orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
+ orb_copy(ORB_ID(sensor_mag0), sub_mag, &mag);
x[calibration_counter] = mag.x;
y[calibration_counter] = mag.y;
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index 40cb6043f..ccc497323 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -112,6 +112,10 @@ public:
*/
FixedwingEstimator();
+ /* we do not want people ever copying this class */
+ FixedwingEstimator(const FixedwingEstimator& that) = delete;
+ FixedwingEstimator operator=(const FixedwingEstimator&) = delete;
+
/**
* Destructor, also kills the sensors task.
*/
@@ -371,9 +375,10 @@ FixedwingEstimator::FixedwingEstimator() :
_mag_offsets({}),
#ifdef SENSOR_COMBINED_SUB
- _sensor_combined({}),
+ _sensor_combined{},
#endif
+ _pos_ref{},
_baro_ref(0.0f),
_baro_ref_offset(0.0f),
_baro_gps_offset(0.0f),
@@ -390,12 +395,18 @@ FixedwingEstimator::FixedwingEstimator() :
/* states */
_baro_init(false),
_gps_initialized(false),
+ _gps_start_time(0),
+ _filter_start_time(0),
+ _last_sensor_timestamp(0),
+ _last_run(0),
_gyro_valid(false),
_accel_valid(false),
_mag_valid(false),
_ekf_logging(true),
_debug(0),
_mavlink_fd(-1),
+ _parameters{},
+ _parameter_handles{},
_ekf(nullptr),
_velocity_xy_filtered(0.0f),
_velocity_z_filtered(0.0f),
@@ -693,7 +704,7 @@ FixedwingEstimator::task_main()
/*
* do subscriptions
*/
- _baro_sub = orb_subscribe(ORB_ID(sensor_baro));
+ _baro_sub = orb_subscribe(ORB_ID(sensor_baro0));
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
_gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
@@ -1041,7 +1052,7 @@ FixedwingEstimator::task_main()
orb_check(_baro_sub, &baro_updated);
if (baro_updated) {
- orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro);
+ orb_copy(ORB_ID(sensor_baro0), _baro_sub, &_baro);
_ekf->baroHgt = _baro.altitude;
@@ -1133,7 +1144,7 @@ FixedwingEstimator::task_main()
initVelNED[2] = _gps.vel_d_m_s;
// Set up height correctly
- orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro);
+ orb_copy(ORB_ID(sensor_baro0), _baro_sub, &_baro);
_baro_ref_offset = _ekf->states[9]; // this should become zero in the local frame
_baro_gps_offset = _baro.altitude - gps_alt;
_ekf->baroHgt = _baro.altitude;
diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp
index 29a8c8d1e..77cc1eeeb 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp
@@ -45,8 +45,11 @@ void Vector3f::zero(void)
z = 0.0f;
}
-Mat3f::Mat3f() {
- identity();
+Mat3f::Mat3f() :
+ x{1.0f, 0.0f, 0.0f},
+ y{0.0f, 1.0f, 0.0f},
+ z{0.0f, 0.0f, 1.0f}
+{
}
void Mat3f::identity() {
diff --git a/src/modules/ekf_att_pos_estimator/module.mk b/src/modules/ekf_att_pos_estimator/module.mk
index dc5220bf0..36d854ddd 100644
--- a/src/modules/ekf_att_pos_estimator/module.mk
+++ b/src/modules/ekf_att_pos_estimator/module.mk
@@ -41,3 +41,5 @@ SRCS = ekf_att_pos_estimator_main.cpp \
ekf_att_pos_estimator_params.c \
estimator_23states.cpp \
estimator_utilities.cpp
+
+EXTRACXXFLAGS = -Weffc++
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index 4cdba735a..0cea13cc4 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -529,7 +529,7 @@ FixedwingAttitudeControl::vehicle_accel_poll()
orb_check(_accel_sub, &accel_updated);
if (accel_updated) {
- orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel);
+ orb_copy(ORB_ID(sensor_accel0), _accel_sub, &_accel);
}
}
@@ -577,7 +577,7 @@ FixedwingAttitudeControl::task_main()
*/
_att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
_att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- _accel_sub = orb_subscribe(ORB_ID(sensor_accel));
+ _accel_sub = orb_subscribe(ORB_ID(sensor_accel0));
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
_vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
diff --git a/src/modules/mavlink/mavlink_commands.cpp b/src/modules/mavlink/mavlink_commands.cpp
index fccd4d9a5..b502c3c86 100644
--- a/src/modules/mavlink/mavlink_commands.cpp
+++ b/src/modules/mavlink/mavlink_commands.cpp
@@ -40,9 +40,12 @@
#include "mavlink_commands.h"
-MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel), _cmd_time(0)
+MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) :
+ _cmd_sub(mavlink->add_orb_subscription(ORB_ID(vehicle_command))),
+ _cmd{},
+ _channel(channel),
+ _cmd_time(0)
{
- _cmd_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_command));
}
void
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index 675a6870e..6a2c900af 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -50,16 +50,20 @@ MavlinkFTP::getServer()
return _server;
}
-MavlinkFTP::MavlinkFTP()
+MavlinkFTP::MavlinkFTP() :
+ _session_fds{},
+ _workBufs{},
+ _workFree{},
+ _lock{}
{
// initialise the request freelist
dq_init(&_workFree);
sem_init(&_lock, 0, 1);
-
- // initialize session list
- for (size_t i=0; i<kMaxSession; i++) {
- _session_fds[i] = -1;
- }
+
+ // initialize session list
+ for (size_t i=0; i<kMaxSession; i++) {
+ _session_fds[i] = -1;
+ }
// drop work entries onto the free list
for (unsigned i = 0; i < kRequestQueueSize; i++) {
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 7707c0bc8..75799804c 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -216,6 +216,7 @@ Mavlink::Mavlink() :
_device_name(DEFAULT_DEVICE_NAME),
_task_should_exit(false),
next(nullptr),
+ _instance_id(0),
_mavlink_fd(-1),
_task_running(false),
_hil_enabled(false),
@@ -231,17 +232,24 @@ Mavlink::Mavlink() :
_mission_pub(-1),
_mission_result_sub(-1),
_mode(MAVLINK_MODE_NORMAL),
+ _channel(MAVLINK_COMM_0),
+ _logbuffer{},
_total_counter(0),
+ _receive_thread{},
_verbose(false),
_forwarding_on(false),
_passing_on(false),
_ftp_on(false),
_uart_fd(-1),
+ _baudrate(57600),
+ _datarate(10000),
_mavlink_param_queue_index(0),
+ mavlink_link_termination_allowed(false),
_subscribe_to_stream(nullptr),
_subscribe_to_stream_rate(0.0f),
_flow_control_enabled(true),
- _message_buffer({}),
+ _message_buffer{},
+ _message_buffer_mutex{},
_param_initialized(false),
_param_system_id(0),
_param_component_id(0),
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 8738a6f18..f3882270c 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -376,4 +376,8 @@ private:
* Main mavlink task.
*/
int task_main(int argc, char *argv[]);
+
+ /* do not allow copying this class */
+ Mavlink(const Mavlink&);
+ Mavlink operator=(const Mavlink&);
};
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 7c864f127..6885bebde 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -258,7 +258,16 @@ private:
MavlinkOrbSubscription *status_sub;
MavlinkOrbSubscription *pos_sp_triplet_sub;
+ /* do not allow top copying this class */
+ MavlinkStreamHeartbeat(MavlinkStreamHeartbeat &);
+ MavlinkStreamHeartbeat& operator = (const MavlinkStreamHeartbeat &);
+
protected:
+ explicit MavlinkStreamHeartbeat() : MavlinkStream(),
+ status_sub(nullptr),
+ pos_sp_triplet_sub(nullptr)
+ {}
+
void subscribe(Mavlink *mavlink)
{
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
@@ -322,7 +331,15 @@ public:
private:
MavlinkOrbSubscription *status_sub;
+ /* do not allow top copying this class */
+ MavlinkStreamSysStatus(MavlinkStreamSysStatus &);
+ MavlinkStreamSysStatus& operator = (const MavlinkStreamSysStatus &);
+
protected:
+ explicit MavlinkStreamSysStatus() : MavlinkStream(),
+ status_sub(nullptr)
+ {}
+
void subscribe(Mavlink *mavlink)
{
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
@@ -384,8 +401,13 @@ private:
uint64_t mag_timestamp;
uint64_t baro_timestamp;
+ /* do not allow top copying this class */
+ MavlinkStreamHighresIMU(MavlinkStreamHighresIMU &);
+ MavlinkStreamHighresIMU& operator = (const MavlinkStreamHighresIMU &);
+
protected:
explicit MavlinkStreamHighresIMU() : MavlinkStream(),
+ sensor_sub(nullptr),
sensor_time(0),
accel_timestamp(0),
gyro_timestamp(0),
@@ -469,8 +491,14 @@ private:
MavlinkOrbSubscription *att_sub;
uint64_t att_time;
+ /* do not allow top copying this class */
+ MavlinkStreamAttitude(MavlinkStreamAttitude &);
+ MavlinkStreamAttitude& operator = (const MavlinkStreamAttitude &);
+
+
protected:
explicit MavlinkStreamAttitude() : MavlinkStream(),
+ att_sub(nullptr),
att_time(0)
{}
@@ -520,8 +548,13 @@ private:
MavlinkOrbSubscription *att_sub;
uint64_t att_time;
+ /* do not allow top copying this class */
+ MavlinkStreamAttitudeQuaternion(MavlinkStreamAttitudeQuaternion &);
+ MavlinkStreamAttitudeQuaternion& operator = (const MavlinkStreamAttitudeQuaternion &);
+
protected:
explicit MavlinkStreamAttitudeQuaternion() : MavlinkStream(),
+ att_sub(nullptr),
att_time(0)
{}
@@ -589,12 +622,21 @@ private:
MavlinkOrbSubscription *airspeed_sub;
uint64_t airspeed_time;
+ /* do not allow top copying this class */
+ MavlinkStreamVFRHUD(MavlinkStreamVFRHUD &);
+ MavlinkStreamVFRHUD& operator = (const MavlinkStreamVFRHUD &);
+
protected:
explicit MavlinkStreamVFRHUD() : MavlinkStream(),
+ att_sub(nullptr),
att_time(0),
+ pos_sub(nullptr),
pos_time(0),
+ armed_sub(nullptr),
armed_time(0),
+ act_sub(nullptr),
act_time(0),
+ airspeed_sub(nullptr),
airspeed_time(0)
{}
@@ -665,8 +707,13 @@ private:
MavlinkOrbSubscription *gps_sub;
uint64_t gps_time;
+ /* do not allow top copying this class */
+ MavlinkStreamGPSRawInt(MavlinkStreamGPSRawInt &);
+ MavlinkStreamGPSRawInt& operator = (const MavlinkStreamGPSRawInt &);
+
protected:
explicit MavlinkStreamGPSRawInt() : MavlinkStream(),
+ gps_sub(nullptr),
gps_time(0)
{}
@@ -726,9 +773,15 @@ private:
MavlinkOrbSubscription *home_sub;
uint64_t home_time;
+ /* do not allow top copying this class */
+ MavlinkStreamGlobalPositionInt(MavlinkStreamGlobalPositionInt &);
+ MavlinkStreamGlobalPositionInt& operator = (const MavlinkStreamGlobalPositionInt &);
+
protected:
explicit MavlinkStreamGlobalPositionInt() : MavlinkStream(),
+ pos_sub(nullptr),
pos_time(0),
+ home_sub(nullptr),
home_time(0)
{}
@@ -789,8 +842,13 @@ private:
MavlinkOrbSubscription *pos_sub;
uint64_t pos_time;
+ /* do not allow top copying this class */
+ MavlinkStreamLocalPositionNED(MavlinkStreamLocalPositionNED &);
+ MavlinkStreamLocalPositionNED& operator = (const MavlinkStreamLocalPositionNED &);
+
protected:
explicit MavlinkStreamLocalPositionNED() : MavlinkStream(),
+ pos_sub(nullptr),
pos_time(0)
{}
@@ -845,8 +903,13 @@ private:
MavlinkOrbSubscription *pos_sub;
uint64_t pos_time;
+ /* do not allow top copying this class */
+ MavlinkStreamViconPositionEstimate(MavlinkStreamViconPositionEstimate &);
+ MavlinkStreamViconPositionEstimate& operator = (const MavlinkStreamViconPositionEstimate &);
+
protected:
explicit MavlinkStreamViconPositionEstimate() : MavlinkStream(),
+ pos_sub(nullptr),
pos_time(0)
{}
@@ -899,7 +962,15 @@ public:
private:
MavlinkOrbSubscription *home_sub;
+ /* do not allow top copying this class */
+ MavlinkStreamGPSGlobalOrigin(MavlinkStreamGPSGlobalOrigin &);
+ MavlinkStreamGPSGlobalOrigin& operator = (const MavlinkStreamGPSGlobalOrigin &);
+
protected:
+ explicit MavlinkStreamGPSGlobalOrigin() : MavlinkStream(),
+ home_sub(nullptr)
+ {}
+
void subscribe(Mavlink *mavlink)
{
home_sub = mavlink->add_orb_subscription(ORB_ID(home_position));
@@ -962,8 +1033,13 @@ private:
MavlinkOrbSubscription *act_sub;
uint64_t act_time;
+ /* do not allow top copying this class */
+ MavlinkStreamServoOutputRaw(MavlinkStreamServoOutputRaw &);
+ MavlinkStreamServoOutputRaw& operator = (const MavlinkStreamServoOutputRaw &);
+
protected:
explicit MavlinkStreamServoOutputRaw() : MavlinkStream(),
+ act_sub(nullptr),
act_time(0)
{}
@@ -1033,10 +1109,17 @@ private:
MavlinkOrbSubscription *act_sub;
uint64_t act_time;
+ /* do not allow top copying this class */
+ MavlinkStreamHILControls(MavlinkStreamHILControls &);
+ MavlinkStreamHILControls& operator = (const MavlinkStreamHILControls &);
+
protected:
explicit MavlinkStreamHILControls() : MavlinkStream(),
+ status_sub(nullptr),
status_time(0),
+ pos_sp_triplet_sub(nullptr),
pos_sp_triplet_time(0),
+ act_sub(nullptr),
act_time(0)
{}
@@ -1159,7 +1242,15 @@ public:
private:
MavlinkOrbSubscription *pos_sp_triplet_sub;
+ /* do not allow top copying this class */
+ MavlinkStreamGlobalPositionSetpointInt(MavlinkStreamGlobalPositionSetpointInt &);
+ MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &);
+
protected:
+ explicit MavlinkStreamGlobalPositionSetpointInt() : MavlinkStream(),
+ pos_sp_triplet_sub(nullptr)
+ {}
+
void subscribe(Mavlink *mavlink)
{
pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet));
@@ -1208,8 +1299,13 @@ private:
MavlinkOrbSubscription *pos_sp_sub;
uint64_t pos_sp_time;
+ /* do not allow top copying this class */
+ MavlinkStreamLocalPositionSetpoint(MavlinkStreamLocalPositionSetpoint &);
+ MavlinkStreamLocalPositionSetpoint& operator = (const MavlinkStreamLocalPositionSetpoint &);
+
protected:
explicit MavlinkStreamLocalPositionSetpoint() : MavlinkStream(),
+ pos_sp_sub(nullptr),
pos_sp_time(0)
{}
@@ -1261,8 +1357,13 @@ private:
MavlinkOrbSubscription *att_sp_sub;
uint64_t att_sp_time;
+ /* do not allow top copying this class */
+ MavlinkStreamRollPitchYawThrustSetpoint(MavlinkStreamRollPitchYawThrustSetpoint &);
+ MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &);
+
protected:
explicit MavlinkStreamRollPitchYawThrustSetpoint() : MavlinkStream(),
+ att_sp_sub(nullptr),
att_sp_time(0)
{}
@@ -1314,8 +1415,13 @@ private:
MavlinkOrbSubscription *att_rates_sp_sub;
uint64_t att_rates_sp_time;
+ /* do not allow top copying this class */
+ MavlinkStreamRollPitchYawRatesThrustSetpoint(MavlinkStreamRollPitchYawRatesThrustSetpoint &);
+ MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &);
+
protected:
explicit MavlinkStreamRollPitchYawRatesThrustSetpoint() : MavlinkStream(),
+ att_rates_sp_sub(nullptr),
att_rates_sp_time(0)
{}
@@ -1367,8 +1473,13 @@ private:
MavlinkOrbSubscription *rc_sub;
uint64_t rc_time;
+ /* do not allow top copying this class */
+ MavlinkStreamRCChannelsRaw(MavlinkStreamRCChannelsRaw &);
+ MavlinkStreamRCChannelsRaw& operator = (const MavlinkStreamRCChannelsRaw &);
+
protected:
explicit MavlinkStreamRCChannelsRaw() : MavlinkStream(),
+ rc_sub(nullptr),
rc_time(0)
{}
@@ -1456,8 +1567,13 @@ private:
MavlinkOrbSubscription *manual_sub;
uint64_t manual_time;
+ /* do not allow top copying this class */
+ MavlinkStreamManualControl(MavlinkStreamManualControl &);
+ MavlinkStreamManualControl& operator = (const MavlinkStreamManualControl &);
+
protected:
explicit MavlinkStreamManualControl() : MavlinkStream(),
+ manual_sub(nullptr),
manual_time(0)
{}
@@ -1510,8 +1626,13 @@ private:
MavlinkOrbSubscription *flow_sub;
uint64_t flow_time;
+ /* do not allow top copying this class */
+ MavlinkStreamOpticalFlow(MavlinkStreamOpticalFlow &);
+ MavlinkStreamOpticalFlow& operator = (const MavlinkStreamOpticalFlow &);
+
protected:
explicit MavlinkStreamOpticalFlow() : MavlinkStream(),
+ flow_sub(nullptr),
flow_time(0)
{}
@@ -1563,8 +1684,13 @@ private:
MavlinkOrbSubscription *att_ctrl_sub;
uint64_t att_ctrl_time;
+ /* do not allow top copying this class */
+ MavlinkStreamAttitudeControls(MavlinkStreamAttitudeControls &);
+ MavlinkStreamAttitudeControls& operator = (const MavlinkStreamAttitudeControls &);
+
protected:
explicit MavlinkStreamAttitudeControls() : MavlinkStream(),
+ att_ctrl_sub(nullptr),
att_ctrl_time(0)
{}
@@ -1626,8 +1752,13 @@ private:
MavlinkOrbSubscription *debug_sub;
uint64_t debug_time;
+ /* do not allow top copying this class */
+ MavlinkStreamNamedValueFloat(MavlinkStreamNamedValueFloat &);
+ MavlinkStreamNamedValueFloat& operator = (const MavlinkStreamNamedValueFloat &);
+
protected:
explicit MavlinkStreamNamedValueFloat() : MavlinkStream(),
+ debug_sub(nullptr),
debug_time(0)
{}
@@ -1678,7 +1809,15 @@ public:
private:
MavlinkOrbSubscription *status_sub;
+ /* do not allow top copying this class */
+ MavlinkStreamCameraCapture(MavlinkStreamCameraCapture &);
+ MavlinkStreamCameraCapture& operator = (const MavlinkStreamCameraCapture &);
+
protected:
+ explicit MavlinkStreamCameraCapture() : MavlinkStream(),
+ status_sub(nullptr)
+ {}
+
void subscribe(Mavlink *mavlink)
{
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
@@ -1729,8 +1868,13 @@ private:
MavlinkOrbSubscription *range_sub;
uint64_t range_time;
+ /* do not allow top copying this class */
+ MavlinkStreamDistanceSensor(MavlinkStreamDistanceSensor &);
+ MavlinkStreamDistanceSensor& operator = (const MavlinkStreamDistanceSensor &);
+
protected:
explicit MavlinkStreamDistanceSensor() : MavlinkStream(),
+ range_sub(nullptr),
range_time(0)
{}
diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h
index f63c32f24..b792b9aaf 100644
--- a/src/modules/mavlink/mavlink_mission.h
+++ b/src/modules/mavlink/mavlink_mission.h
@@ -174,4 +174,8 @@ private:
mavlink_channel_t _channel;
uint8_t _comp_id;
+
+ /* do not allow copying this class */
+ MavlinkMissionManager(const MavlinkMissionManager&);
+ MavlinkMissionManager operator=(const MavlinkMissionManager&);
};
diff --git a/src/modules/mavlink/mavlink_orb_subscription.h b/src/modules/mavlink/mavlink_orb_subscription.h
index 71efb43af..7af454df6 100644
--- a/src/modules/mavlink/mavlink_orb_subscription.h
+++ b/src/modules/mavlink/mavlink_orb_subscription.h
@@ -82,6 +82,10 @@ private:
const orb_id_t _topic; ///< topic metadata
int _fd; ///< subscription handle
bool _published; ///< topic was ever published
+
+ /* do not allow copying this class */
+ MavlinkOrbSubscription(const MavlinkOrbSubscription&);
+ MavlinkOrbSubscription operator=(const MavlinkOrbSubscription&);
};
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 2cc2d6162..7458e09f7 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -86,7 +86,9 @@ static const float mg2ms2 = CONSTANTS_ONE_G / 1000.0f;
MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_mavlink(parent),
-
+ status{},
+ hil_local_pos{},
+ _control_mode{},
_global_pos_pub(-1),
_local_pos_pub(-1),
_attitude_pub(-1),
@@ -112,15 +114,13 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_manual_pub(-1),
_telemetry_heartbeat_time(0),
_radio_status_available(false),
- _control_mode_sub(-1),
+ _control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))),
_hil_frames(0),
_old_timestamp(0),
_hil_local_proj_inited(0),
- _hil_local_alt0(0.0)
+ _hil_local_alt0(0.0f),
+ _hil_local_proj_ref{}
{
- _control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
- memset(&hil_local_pos, 0, sizeof(hil_local_pos));
- memset(&_control_mode, 0, sizeof(_control_mode));
// make sure the FTP server is started
(void)MavlinkFTP::getServer();
@@ -740,10 +740,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
gyro.temperature = imu.temperature;
if (_gyro_pub < 0) {
- _gyro_pub = orb_advertise(ORB_ID(sensor_gyro), &gyro);
+ _gyro_pub = orb_advertise(ORB_ID(sensor_gyro0), &gyro);
} else {
- orb_publish(ORB_ID(sensor_gyro), _gyro_pub, &gyro);
+ orb_publish(ORB_ID(sensor_gyro0), _gyro_pub, &gyro);
}
}
@@ -762,10 +762,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
accel.temperature = imu.temperature;
if (_accel_pub < 0) {
- _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel);
+ _accel_pub = orb_advertise(ORB_ID(sensor_accel0), &accel);
} else {
- orb_publish(ORB_ID(sensor_accel), _accel_pub, &accel);
+ orb_publish(ORB_ID(sensor_accel0), _accel_pub, &accel);
}
}
@@ -783,10 +783,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
mag.z = imu.zmag;
if (_mag_pub < 0) {
- _mag_pub = orb_advertise(ORB_ID(sensor_mag), &mag);
+ _mag_pub = orb_advertise(ORB_ID(sensor_mag0), &mag);
} else {
- orb_publish(ORB_ID(sensor_mag), _mag_pub, &mag);
+ orb_publish(ORB_ID(sensor_mag0), _mag_pub, &mag);
}
}
@@ -801,10 +801,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
baro.temperature = imu.temperature;
if (_baro_pub < 0) {
- _baro_pub = orb_advertise(ORB_ID(sensor_baro), &baro);
+ _baro_pub = orb_advertise(ORB_ID(sensor_baro0), &baro);
} else {
- orb_publish(ORB_ID(sensor_baro), _baro_pub, &baro);
+ orb_publish(ORB_ID(sensor_baro0), _baro_pub, &baro);
}
}
@@ -1078,10 +1078,10 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
accel.temperature = 25.0f;
if (_accel_pub < 0) {
- _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel);
+ _accel_pub = orb_advertise(ORB_ID(sensor_accel0), &accel);
} else {
- orb_publish(ORB_ID(sensor_accel), _accel_pub, &accel);
+ orb_publish(ORB_ID(sensor_accel0), _accel_pub, &accel);
}
}
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index 0044b42cb..fc2b2a49b 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -160,4 +160,8 @@ private:
bool _hil_local_proj_inited;
float _hil_local_alt0;
struct map_projection_reference_s _hil_local_proj_ref;
+
+ /* do not allow copying this class */
+ MavlinkReceiver(const MavlinkReceiver&);
+ MavlinkReceiver operator=(const MavlinkReceiver&);
};
diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h
index 69809a386..20e1c7c44 100644
--- a/src/modules/mavlink/mavlink_stream.h
+++ b/src/modules/mavlink/mavlink_stream.h
@@ -77,6 +77,10 @@ protected:
private:
hrt_abstime _last_sent;
+
+ /* do not allow top copying this class */
+ MavlinkStream(const MavlinkStream&);
+ MavlinkStream& operator=(const MavlinkStream&);
};
diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk
index d49bbb7f7..1986ae3c8 100644
--- a/src/modules/mavlink/module.mk
+++ b/src/modules/mavlink/module.mk
@@ -52,3 +52,5 @@ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 1024
+
+EXTRACXXFLAGS = -Weffc++
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 0d36fa2c6..f534c0f4c 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -1073,6 +1073,12 @@ int sdlog2_thread_main(int argc, char *argv[])
hrt_abstime magnetometer_timestamp = 0;
hrt_abstime barometer_timestamp = 0;
hrt_abstime differential_pressure_timestamp = 0;
+ hrt_abstime gyro1_timestamp = 0;
+ hrt_abstime accelerometer1_timestamp = 0;
+ hrt_abstime magnetometer1_timestamp = 0;
+ hrt_abstime gyro2_timestamp = 0;
+ hrt_abstime accelerometer2_timestamp = 0;
+ hrt_abstime magnetometer2_timestamp = 0;
/* initialize calculated mean SNR */
float snr_mean = 0.0f;
@@ -1209,6 +1215,8 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- SENSOR COMBINED --- */
if (copy_if_updated(ORB_ID(sensor_combined), subs.sensor_sub, &buf.sensor)) {
bool write_IMU = false;
+ bool write_IMU1 = false;
+ bool write_IMU2 = false;
bool write_SENS = false;
if (buf.sensor.timestamp != gyro_timestamp) {
@@ -1260,6 +1268,64 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(SENS);
}
+ if (buf.sensor.accelerometer1_timestamp != accelerometer1_timestamp) {
+ accelerometer1_timestamp = buf.sensor.accelerometer1_timestamp;
+ write_IMU1 = true;
+ }
+
+ if (buf.sensor.gyro1_timestamp != gyro1_timestamp) {
+ gyro1_timestamp = buf.sensor.gyro1_timestamp;
+ write_IMU1 = true;
+ }
+
+ if (buf.sensor.magnetometer1_timestamp != magnetometer1_timestamp) {
+ magnetometer1_timestamp = buf.sensor.magnetometer1_timestamp;
+ write_IMU1 = true;
+ }
+
+ if (write_IMU1) {
+ log_msg.msg_type = LOG_IMU1_MSG;
+ log_msg.body.log_IMU.gyro_x = buf.sensor.gyro1_rad_s[0];
+ log_msg.body.log_IMU.gyro_y = buf.sensor.gyro1_rad_s[1];
+ log_msg.body.log_IMU.gyro_z = buf.sensor.gyro1_rad_s[2];
+ log_msg.body.log_IMU.acc_x = buf.sensor.accelerometer1_m_s2[0];
+ log_msg.body.log_IMU.acc_y = buf.sensor.accelerometer1_m_s2[1];
+ log_msg.body.log_IMU.acc_z = buf.sensor.accelerometer1_m_s2[2];
+ log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer1_ga[0];
+ log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer1_ga[1];
+ log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer1_ga[2];
+ LOGBUFFER_WRITE_AND_COUNT(IMU);
+ }
+
+ if (buf.sensor.accelerometer2_timestamp != accelerometer2_timestamp) {
+ accelerometer2_timestamp = buf.sensor.accelerometer2_timestamp;
+ write_IMU2 = true;
+ }
+
+ if (buf.sensor.gyro2_timestamp != gyro2_timestamp) {
+ gyro2_timestamp = buf.sensor.gyro2_timestamp;
+ write_IMU2 = true;
+ }
+
+ if (buf.sensor.magnetometer2_timestamp != magnetometer2_timestamp) {
+ magnetometer2_timestamp = buf.sensor.magnetometer2_timestamp;
+ write_IMU2 = true;
+ }
+
+ if (write_IMU2) {
+ log_msg.msg_type = LOG_IMU2_MSG;
+ log_msg.body.log_IMU.gyro_x = buf.sensor.gyro2_rad_s[0];
+ log_msg.body.log_IMU.gyro_y = buf.sensor.gyro2_rad_s[1];
+ log_msg.body.log_IMU.gyro_z = buf.sensor.gyro2_rad_s[2];
+ log_msg.body.log_IMU.acc_x = buf.sensor.accelerometer2_m_s2[0];
+ log_msg.body.log_IMU.acc_y = buf.sensor.accelerometer2_m_s2[1];
+ log_msg.body.log_IMU.acc_z = buf.sensor.accelerometer2_m_s2[2];
+ log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer2_ga[0];
+ log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer2_ga[1];
+ log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer2_ga[2];
+ LOGBUFFER_WRITE_AND_COUNT(IMU);
+ }
+
}
/* --- ATTITUDE --- */
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 87f7f718f..b14ef04cc 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -73,6 +73,8 @@ struct log_ATSP_s {
/* --- IMU - IMU SENSORS --- */
#define LOG_IMU_MSG 4
+#define LOG_IMU1_MSG 22
+#define LOG_IMU2_MSG 23
struct log_IMU_s {
float acc_x;
float acc_y;
@@ -276,8 +278,8 @@ struct log_DIST_s {
uint8_t flags;
};
-// ID 22 available
-// ID 23 available
+/* LOG IMU1 and IMU2 MSGs consume IDs 22 and 23 */
+
/* --- PWR - ONBOARD POWER SYSTEM --- */
#define LOG_PWR_MSG 24
@@ -420,7 +422,9 @@ static const struct log_format_s log_formats[] = {
/* business-level messages, ID < 0x80 */
LOG_FORMAT(ATT, "fffffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ"),
LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
- LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
+ LOG_FORMAT_S(IMU, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
+ LOG_FORMAT_S(IMU1, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
+ LOG_FORMAT_S(IMU2, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT(SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
LOG_FORMAT(LPOS, "ffffffffLLfBBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,LFlg,GFlg,EPH,EPV"),
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 38b190761..7ce6ef5ef 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -292,6 +292,19 @@ PARAM_DEFINE_FLOAT(SENS_BOARD_Z_OFF, 0.0f);
*/
PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0);
+/**
+* Set usage of external magnetometer
+*
+* * Set to 0 (default) to auto-detect (will try to get the external as primary)
+* * Set to 1 to force the external magnetometer as primary
+* * Set to 2 to force the internal magnetometer as primary
+*
+* @min 0
+* @max 2
+* @group Sensor Calibration
+*/
+PARAM_DEFINE_INT32(SENS_EXT_MAG, 0);
+
/**
* RC Channel 1 Minimum
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 6bafb9ba6..4e8a8c01d 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -199,9 +199,15 @@ private:
bool _hil_enabled; /**< if true, HIL is active */
bool _publishing; /**< if true, we are publishing sensor data */
- int _gyro_sub; /**< raw gyro data subscription */
- int _accel_sub; /**< raw accel data subscription */
- int _mag_sub; /**< raw mag data subscription */
+ int _gyro_sub; /**< raw gyro0 data subscription */
+ int _accel_sub; /**< raw accel0 data subscription */
+ int _mag_sub; /**< raw mag0 data subscription */
+ int _gyro1_sub; /**< raw gyro1 data subscription */
+ int _accel1_sub; /**< raw accel1 data subscription */
+ int _mag1_sub; /**< raw mag1 data subscription */
+ int _gyro2_sub; /**< raw gyro2 data subscription */
+ int _accel2_sub; /**< raw accel2 data subscription */
+ int _mag2_sub; /**< raw mag2 data subscription */
int _rc_sub; /**< raw rc channels data subscription */
int _baro_sub; /**< raw baro data subscription */
int _airspeed_sub; /**< airspeed subscription */
@@ -478,6 +484,12 @@ Sensors::Sensors() :
_gyro_sub(-1),
_accel_sub(-1),
_mag_sub(-1),
+ _gyro1_sub(-1),
+ _accel1_sub(-1),
+ _mag1_sub(-1),
+ _gyro2_sub(-1),
+ _accel2_sub(-1),
+ _mag2_sub(-1),
_rc_sub(-1),
_baro_sub(-1),
_vcontrol_mode_sub(-1),
@@ -1004,7 +1016,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
if (accel_updated) {
struct accel_report accel_report;
- orb_copy(ORB_ID(sensor_accel), _accel_sub, &accel_report);
+ orb_copy(ORB_ID(sensor_accel0), _accel_sub, &accel_report);
math::Vector<3> vect(accel_report.x, accel_report.y, accel_report.z);
vect = _board_rotation * vect;
@@ -1019,6 +1031,48 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
raw.accelerometer_timestamp = accel_report.timestamp;
}
+
+ orb_check(_accel1_sub, &accel_updated);
+
+ if (accel_updated) {
+ struct accel_report accel_report;
+
+ orb_copy(ORB_ID(sensor_accel1), _accel_sub, &accel_report);
+
+ math::Vector<3> vect(accel_report.x, accel_report.y, accel_report.z);
+ vect = _board_rotation * vect;
+
+ raw.accelerometer1_m_s2[0] = vect(0);
+ raw.accelerometer1_m_s2[1] = vect(1);
+ raw.accelerometer1_m_s2[2] = vect(2);
+
+ raw.accelerometer1_raw[0] = accel_report.x_raw;
+ raw.accelerometer1_raw[1] = accel_report.y_raw;
+ raw.accelerometer1_raw[2] = accel_report.z_raw;
+
+ raw.accelerometer1_timestamp = accel_report.timestamp;
+ }
+
+ orb_check(_accel2_sub, &accel_updated);
+
+ if (accel_updated) {
+ struct accel_report accel_report;
+
+ orb_copy(ORB_ID(sensor_accel2), _accel_sub, &accel_report);
+
+ math::Vector<3> vect(accel_report.x, accel_report.y, accel_report.z);
+ vect = _board_rotation * vect;
+
+ raw.accelerometer2_m_s2[0] = vect(0);
+ raw.accelerometer2_m_s2[1] = vect(1);
+ raw.accelerometer2_m_s2[2] = vect(2);
+
+ raw.accelerometer2_raw[0] = accel_report.x_raw;
+ raw.accelerometer2_raw[1] = accel_report.y_raw;
+ raw.accelerometer2_raw[2] = accel_report.z_raw;
+
+ raw.accelerometer2_timestamp = accel_report.timestamp;
+ }
}
void
@@ -1030,7 +1084,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
if (gyro_updated) {
struct gyro_report gyro_report;
- orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &gyro_report);
+ orb_copy(ORB_ID(sensor_gyro0), _gyro_sub, &gyro_report);
math::Vector<3> vect(gyro_report.x, gyro_report.y, gyro_report.z);
vect = _board_rotation * vect;
@@ -1045,6 +1099,48 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
raw.timestamp = gyro_report.timestamp;
}
+
+ orb_check(_gyro1_sub, &gyro_updated);
+
+ if (gyro_updated) {
+ struct gyro_report gyro_report;
+
+ orb_copy(ORB_ID(sensor_gyro1), _gyro1_sub, &gyro_report);
+
+ math::Vector<3> vect(gyro_report.x, gyro_report.y, gyro_report.z);
+ vect = _board_rotation * vect;
+
+ raw.gyro1_rad_s[0] = vect(0);
+ raw.gyro1_rad_s[1] = vect(1);
+ raw.gyro1_rad_s[2] = vect(2);
+
+ raw.gyro1_raw[0] = gyro_report.x_raw;
+ raw.gyro1_raw[1] = gyro_report.y_raw;
+ raw.gyro1_raw[2] = gyro_report.z_raw;
+
+ raw.gyro1_timestamp = gyro_report.timestamp;
+ }
+
+ orb_check(_gyro2_sub, &gyro_updated);
+
+ if (gyro_updated) {
+ struct gyro_report gyro_report;
+
+ orb_copy(ORB_ID(sensor_gyro2), _gyro_sub, &gyro_report);
+
+ math::Vector<3> vect(gyro_report.x, gyro_report.y, gyro_report.z);
+ vect = _board_rotation * vect;
+
+ raw.gyro2_rad_s[0] = vect(0);
+ raw.gyro2_rad_s[1] = vect(1);
+ raw.gyro2_rad_s[2] = vect(2);
+
+ raw.gyro2_raw[0] = gyro_report.x_raw;
+ raw.gyro2_raw[1] = gyro_report.y_raw;
+ raw.gyro2_raw[2] = gyro_report.z_raw;
+
+ raw.gyro2_timestamp = gyro_report.timestamp;
+ }
}
void
@@ -1056,10 +1152,12 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
if (mag_updated) {
struct mag_report mag_report;
- orb_copy(ORB_ID(sensor_mag), _mag_sub, &mag_report);
+ orb_copy(ORB_ID(sensor_mag0), _mag_sub, &mag_report);
math::Vector<3> vect(mag_report.x, mag_report.y, mag_report.z);
+ // XXX we need device-id based handling here
+
if (_mag_is_external) {
vect = _external_mag_rotation * vect;
@@ -1087,7 +1185,7 @@ Sensors::baro_poll(struct sensor_combined_s &raw)
if (baro_updated) {
- orb_copy(ORB_ID(sensor_baro), _baro_sub, &_barometer);
+ orb_copy(ORB_ID(sensor_baro0), _baro_sub, &_barometer);
raw.baro_pres_mbar = _barometer.pressure; // Pressure in mbar
raw.baro_alt_meter = _barometer.altitude; // Altitude in meters
@@ -1618,11 +1716,17 @@ Sensors::task_main()
/*
* do subscriptions
*/
- _gyro_sub = orb_subscribe(ORB_ID(sensor_gyro));
- _accel_sub = orb_subscribe(ORB_ID(sensor_accel));
- _mag_sub = orb_subscribe(ORB_ID(sensor_mag));
+ _gyro_sub = orb_subscribe(ORB_ID(sensor_gyro0));
+ _accel_sub = orb_subscribe(ORB_ID(sensor_accel0));
+ _mag_sub = orb_subscribe(ORB_ID(sensor_mag0));
+ _gyro1_sub = orb_subscribe(ORB_ID(sensor_gyro1));
+ _accel1_sub = orb_subscribe(ORB_ID(sensor_accel1));
+ _mag1_sub = orb_subscribe(ORB_ID(sensor_mag1));
+ _gyro2_sub = orb_subscribe(ORB_ID(sensor_gyro2));
+ _accel2_sub = orb_subscribe(ORB_ID(sensor_accel2));
+ _mag2_sub = orb_subscribe(ORB_ID(sensor_mag2));
_rc_sub = orb_subscribe(ORB_ID(input_rc));
- _baro_sub = orb_subscribe(ORB_ID(sensor_baro));
+ _baro_sub = orb_subscribe(ORB_ID(sensor_baro0));
_diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
_vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
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
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index c5831462b..08c3ce1ac 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -46,16 +46,23 @@
#include <drivers/drv_orb_dev.h>
#include <drivers/drv_mag.h>
-ORB_DEFINE(sensor_mag, struct mag_report);
+ORB_DEFINE(sensor_mag0, struct mag_report);
+ORB_DEFINE(sensor_mag1, struct mag_report);
+ORB_DEFINE(sensor_mag2, struct mag_report);
#include <drivers/drv_accel.h>
-ORB_DEFINE(sensor_accel, struct accel_report);
+ORB_DEFINE(sensor_accel0, struct accel_report);
+ORB_DEFINE(sensor_accel1, struct accel_report);
+ORB_DEFINE(sensor_accel2, struct accel_report);
#include <drivers/drv_gyro.h>
-ORB_DEFINE(sensor_gyro, struct gyro_report);
+ORB_DEFINE(sensor_gyro0, struct gyro_report);
+ORB_DEFINE(sensor_gyro1, struct gyro_report);
+ORB_DEFINE(sensor_gyro2, struct gyro_report);
#include <drivers/drv_baro.h>
-ORB_DEFINE(sensor_baro, struct baro_report);
+ORB_DEFINE(sensor_baro0, struct baro_report);
+ORB_DEFINE(sensor_baro1, struct baro_report);
#include <drivers/drv_range_finder.h>
ORB_DEFINE(sensor_range_finder, struct range_finder_report);
diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h
index fa3367de9..06dfcdab3 100644
--- a/src/modules/uORB/topics/sensor_combined.h
+++ b/src/modules/uORB/topics/sensor_combined.h
@@ -95,6 +95,30 @@ struct sensor_combined_s {
float magnetometer_cuttoff_freq_hz; /**< Internal analog low pass frequency of sensor */
uint64_t magnetometer_timestamp; /**< Magnetometer timestamp */
+ int16_t gyro1_raw[3]; /**< Raw sensor values of angular velocity */
+ float gyro1_rad_s[3]; /**< Angular velocity in radian per seconds */
+ uint64_t gyro1_timestamp; /**< Gyro timestamp */
+
+ int16_t accelerometer1_raw[3]; /**< Raw acceleration in NED body frame */
+ float accelerometer1_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */
+ uint64_t accelerometer1_timestamp; /**< Accelerometer timestamp */
+
+ int16_t magnetometer1_raw[3]; /**< Raw magnetic field in NED body frame */
+ float magnetometer1_ga[3]; /**< Magnetic field in NED body frame, in Gauss */
+ uint64_t magnetometer1_timestamp; /**< Magnetometer timestamp */
+
+ int16_t gyro2_raw[3]; /**< Raw sensor values of angular velocity */
+ float gyro2_rad_s[3]; /**< Angular velocity in radian per seconds */
+ uint64_t gyro2_timestamp; /**< Gyro timestamp */
+
+ int16_t accelerometer2_raw[3]; /**< Raw acceleration in NED body frame */
+ float accelerometer2_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */
+ uint64_t accelerometer2_timestamp; /**< Accelerometer timestamp */
+
+ int16_t magnetometer2_raw[3]; /**< Raw magnetic field in NED body frame */
+ float magnetometer2_ga[3]; /**< Magnetic field in NED body frame, in Gauss */
+ uint64_t magnetometer2_timestamp; /**< Magnetometer timestamp */
+
float baro_pres_mbar; /**< Barometric pressure, already temp. comp. */
float baro_alt_meter; /**< Altitude, already temp. comp. */
float baro_temp_celcius; /**< Temperature in degrees celsius */