aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2015-02-23 19:50:11 +0100
committerLorenz Meier <lm@inf.ethz.ch>2015-02-23 19:50:11 +0100
commit836a3c6f4be619059d5369b85032acfdfc9f5edb (patch)
tree55a1d0d4b62a1f52ec8baeac594e974f6d543eda
parent91efd50f868170f0551cee8171e2235a519c1d81 (diff)
downloadpx4-firmware-sensors_multi_2.tar.gz
px4-firmware-sensors_multi_2.tar.bz2
px4-firmware-sensors_multi_2.zip
WIP on moving to generated sensor messagessensors_multi_2
-rw-r--r--msg/gyro_report.msg17
-rw-r--r--msg/sensor_combined.msg3
-rw-r--r--src/drivers/drv_gyro.h26
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp3
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp1
-rw-r--r--src/modules/uORB/topics/sensor_combined.h4
6 files changed, 24 insertions, 30 deletions
diff --git a/msg/gyro_report.msg b/msg/gyro_report.msg
new file mode 100644
index 000000000..654019b6a
--- /dev/null
+++ b/msg/gyro_report.msg
@@ -0,0 +1,17 @@
+#
+# Gyro report structure. Reads from the device must be in multiples of this
+# structure.
+#
+uint64 timestamp # Microseconds since system boot
+uint64 error_count
+float32 x # angular velocity in the NED X board axis in rad/s
+float32 y # angular velocity in the NED Y board axis in rad/s
+float32 z # angular velocity in the NED Z board axis in rad/s
+float32 temperature; # temperature in degrees celcius
+float32 range_rad_s;
+float32 scaling;
+
+int16 x_raw;
+int16 y_raw;
+int16 z_raw;
+int16 temperature_raw;
diff --git a/msg/sensor_combined.msg b/msg/sensor_combined.msg
new file mode 100644
index 000000000..b2d5cd4cb
--- /dev/null
+++ b/msg/sensor_combined.msg
@@ -0,0 +1,3 @@
+
+uint64 timestamp
+px4/gyro_report[3] gyro \ No newline at end of file
diff --git a/src/drivers/drv_gyro.h b/src/drivers/drv_gyro.h
index 122d20415..1e8993d34 100644
--- a/src/drivers/drv_gyro.h
+++ b/src/drivers/drv_gyro.h
@@ -44,33 +44,12 @@
#include <sys/ioctl.h>
#include "drv_sensor.h"
-#include "drv_orb_dev.h"
#define GYRO_BASE_DEVICE_PATH "/dev/gyro"
#define GYRO0_DEVICE_PATH "/dev/gyro0"
#define GYRO1_DEVICE_PATH "/dev/gyro1"
#define GYRO2_DEVICE_PATH "/dev/gyro2"
-/**
- * gyro report structure. Reads from the device must be in multiples of this
- * structure.
- */
-struct gyro_report {
- uint64_t timestamp;
- uint64_t error_count;
- float x; /**< angular velocity in the NED X board axis in rad/s */
- float y; /**< angular velocity in the NED Y board axis in rad/s */
- float z; /**< angular velocity in the NED Z board axis in rad/s */
- float temperature; /**< temperature in degrees celcius */
- float range_rad_s;
- float scaling;
-
- int16_t x_raw;
- int16_t y_raw;
- int16_t z_raw;
- int16_t temperature_raw;
-};
-
/** gyro scaling factors; Vout = (Vin * Vscale) + Voffset */
struct gyro_scale {
float x_offset;
@@ -82,11 +61,6 @@ struct gyro_scale {
};
/*
- * ObjDev tag for raw gyro data.
- */
-ORB_DECLARE(sensor_gyro);
-
-/*
* ioctl() definitions
*/
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 4aa05a980..36dfd5dda 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -482,7 +482,7 @@ private:
extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); }
MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device, enum Rotation rotation) :
- SPI("MPU6000", path_accel, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED),
+ SPI("MPU6000", path_accel, bus, device, SPIDEV_MODE3, MPU6000_HIGH_BUS_SPEED),
_gyro(new MPU6000_gyro(this, path_gyro)),
_product(0),
_call{},
@@ -658,6 +658,7 @@ out:
int MPU6000::reset()
{
+ set_frequency(MPU6000_LOW_BUS_SPEED);
// if the mpu6000 is initialised after the l3gd20 and lsm303d
// then if we don't do an irqsave/irqrestore here the mpu6000
// frequenctly comes up in a bad state where all transfers
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 0bdc285e7..6f3597161 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -62,7 +62,6 @@
#include <poll.h>
#include <time.h>
#include <drivers/drv_hrt.h>
-#include <drivers/drv_accel.h>
#include <arch/board/board.h>
#include <uORB/uORB.h>
#include <uORB/topics/airspeed.h>
diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h
index ded82adea..a2f9135a7 100644
--- a/src/modules/uORB/topics/sensor_combined.h
+++ b/src/modules/uORB/topics/sensor_combined.h
@@ -91,8 +91,8 @@ struct sensor_combined_s {
uint64_t accelerometer_timestamp; /**< Accelerometer timestamp */
unsigned accelerometer_errcount; /**< Error counter for accel 0 */
- int16_t magnetometer_raw[3]; /**< Raw magnetic field in NED body frame */
- float magnetometer_ga[3]; /**< Magnetic field in NED body frame, in Gauss */
+ int16_t magnetometer_raw[3][3]; /**< Raw magnetic field in NED body frame */
+ float magnetometer_ga[3][3]; /**< Magnetic field in NED body frame, in Gauss */
int magnetometer_mode; /**< Magnetometer measurement mode */
float magnetometer_range_ga; /**< ± measurement range in Gauss */
float magnetometer_cuttoff_freq_hz; /**< Internal analog low pass frequency of sensor */