aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-08-21 18:13:01 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-08-21 18:13:01 +0200
commitfab110d21f147e5064ff140aadac649017fa466e (patch)
treeb41291188db4e5734353f0d09a0af306c58ed9f5 /src/drivers
parent309ea8146055528c22395fca06b7a70b660c22b3 (diff)
downloadpx4-firmware-fab110d21f147e5064ff140aadac649017fa466e.tar.gz
px4-firmware-fab110d21f147e5064ff140aadac649017fa466e.tar.bz2
px4-firmware-fab110d21f147e5064ff140aadac649017fa466e.zip
Moved math library to library dir, improved sensor-level HIL, cleaned up geo / conversion libs
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/hott/messages.cpp2
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp17
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp10
3 files changed, 16 insertions, 13 deletions
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
index 57c256339..bb8d45bea 100644
--- a/src/drivers/hott/messages.cpp
+++ b/src/drivers/hott/messages.cpp
@@ -42,7 +42,7 @@
#include <math.h>
#include <stdio.h>
#include <string.h>
-#include <systemlib/geo/geo.h>
+#include <geo/geo.h>
#include <unistd.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/battery_status.h>
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index efe7cf8eb..cf5f8d94c 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -54,7 +54,6 @@
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
-#include <systemlib/geo/geo.h>
#include <nuttx/arch.h>
#include <nuttx/clock.h>
@@ -178,6 +177,8 @@ static const int ERROR = -1;
#define LSM303D_MAG_DEFAULT_RANGE_GA 2
#define LSM303D_MAG_DEFAULT_RATE 100
+#define LSM303D_ONE_G 9.80665f
+
extern "C" { __EXPORT int lsm303d_main(int argc, char *argv[]); }
@@ -778,7 +779,7 @@ LSM303D::ioctl(struct file *filp, int cmd, unsigned long arg)
case ACCELIOCGRANGE:
/* convert to m/s^2 and return rounded in G */
- return (unsigned long)((_accel_range_m_s2)/CONSTANTS_ONE_G + 0.5f);
+ return (unsigned long)((_accel_range_m_s2)/LSM303D_ONE_G + 0.5f);
case ACCELIOCGSCALE:
/* copy scale out */
@@ -1015,27 +1016,27 @@ LSM303D::accel_set_range(unsigned max_g)
max_g = 16;
if (max_g <= 2) {
- _accel_range_m_s2 = 2.0f*CONSTANTS_ONE_G;
+ _accel_range_m_s2 = 2.0f*LSM303D_ONE_G;
setbits |= REG2_FULL_SCALE_2G_A;
new_scale_g_digit = 0.061e-3f;
} else if (max_g <= 4) {
- _accel_range_m_s2 = 4.0f*CONSTANTS_ONE_G;
+ _accel_range_m_s2 = 4.0f*LSM303D_ONE_G;
setbits |= REG2_FULL_SCALE_4G_A;
new_scale_g_digit = 0.122e-3f;
} else if (max_g <= 6) {
- _accel_range_m_s2 = 6.0f*CONSTANTS_ONE_G;
+ _accel_range_m_s2 = 6.0f*LSM303D_ONE_G;
setbits |= REG2_FULL_SCALE_6G_A;
new_scale_g_digit = 0.183e-3f;
} else if (max_g <= 8) {
- _accel_range_m_s2 = 8.0f*CONSTANTS_ONE_G;
+ _accel_range_m_s2 = 8.0f*LSM303D_ONE_G;
setbits |= REG2_FULL_SCALE_8G_A;
new_scale_g_digit = 0.244e-3f;
} else if (max_g <= 16) {
- _accel_range_m_s2 = 16.0f*CONSTANTS_ONE_G;
+ _accel_range_m_s2 = 16.0f*LSM303D_ONE_G;
setbits |= REG2_FULL_SCALE_16G_A;
new_scale_g_digit = 0.732e-3f;
@@ -1043,7 +1044,7 @@ LSM303D::accel_set_range(unsigned max_g)
return -EINVAL;
}
- _accel_range_scale = new_scale_g_digit * CONSTANTS_ONE_G;
+ _accel_range_scale = new_scale_g_digit * LSM303D_ONE_G;
modify_reg(ADDR_CTRL_REG2, clearbits, setbits);
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 0e65923db..14f8f44b8 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -159,6 +159,8 @@
#define MPU6000_DEFAULT_ONCHIP_FILTER_FREQ 42
+#define MPU6000_ONE_G 9.80665f
+
class MPU6000_gyro;
class MPU6000 : public device::SPI
@@ -543,8 +545,8 @@ void MPU6000::reset()
// Correct accel scale factors of 4096 LSB/g
// scale to m/s^2 ( 1g = 9.81 m/s^2)
- _accel_range_scale = (CONSTANTS_ONE_G / 4096.0f);
- _accel_range_m_s2 = 8.0f * CONSTANTS_ONE_G;
+ _accel_range_scale = (MPU6000_ONE_G / 4096.0f);
+ _accel_range_m_s2 = 8.0f * MPU6000_ONE_G;
usleep(1000);
@@ -906,7 +908,7 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
// _accel_range_m_s2 = 8.0f * 9.81f;
return -EINVAL;
case ACCELIOCGRANGE:
- return (unsigned long)((_accel_range_m_s2)/CONSTANTS_ONE_G + 0.5f);
+ return (unsigned long)((_accel_range_m_s2)/MPU6000_ONE_G + 0.5f);
case ACCELIOCSELFTEST:
return accel_self_test();
@@ -1409,7 +1411,7 @@ test()
warnx("acc y: \t%d\traw 0x%0x", (short)a_report.y_raw, (unsigned short)a_report.y_raw);
warnx("acc z: \t%d\traw 0x%0x", (short)a_report.z_raw, (unsigned short)a_report.z_raw);
warnx("acc range: %8.4f m/s^2 (%8.4f g)", (double)a_report.range_m_s2,
- (double)(a_report.range_m_s2 / CONSTANTS_ONE_G));
+ (double)(a_report.range_m_s2 / MPU6000_ONE_G));
/* do a simple demand read */
sz = read(fd_gyro, &g_report, sizeof(g_report));