aboutsummaryrefslogtreecommitdiff
path: root/apps/sensors/sensors.cpp
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-08-26 13:51:18 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-08-26 13:51:18 +0200
commit6026595d83b5ce5048ad77b7e0aa78ecd83e46af (patch)
tree8f1255d8d296fbef67ee993d914364b963f4ad73 /apps/sensors/sensors.cpp
parent60311a37786a8731b10dba4d4f5ab3a56108788d (diff)
downloadpx4-firmware-6026595d83b5ce5048ad77b7e0aa78ecd83e46af.tar.gz
px4-firmware-6026595d83b5ce5048ad77b7e0aa78ecd83e46af.tar.bz2
px4-firmware-6026595d83b5ce5048ad77b7e0aa78ecd83e46af.zip
Fixed axis assignment and raw value outputs. Scaling and offsets to be done
Diffstat (limited to 'apps/sensors/sensors.cpp')
-rw-r--r--apps/sensors/sensors.cpp36
1 files changed, 19 insertions, 17 deletions
diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp
index 56a9d8995..f75834ddf 100644
--- a/apps/sensors/sensors.cpp
+++ b/apps/sensors/sensors.cpp
@@ -2,8 +2,6 @@
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -604,14 +602,16 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
read(_fd_bma180, buf, sizeof(buf));
accel_report.timestamp = hrt_absolute_time();
- accel_report.x_raw = buf[0];
- accel_report.y_raw = buf[1];
- accel_report.z_raw = buf[2];
- /* XXX scale raw values to readings */
- accel_report.x = 0;
- accel_report.y = 0;
- accel_report.z = 0;
+ accel_report.x_raw = (buf[1] == -32768) ? 32767 : -buf[1];
+ accel_report.y_raw = (buf[0] == -32768) ? -32767 : buf[0];
+ accel_report.z_raw = (buf[2] == -32768) ? -32767 : buf[2];
+
+ const float range_g = 4.0f;
+ /* scale from 14 bit to m/s2 */
+ accel_report.x = (((accel_report.x_raw - _parameters.acc_offset[0]) * range_g) / 8192.0f) / 9.81f;
+ accel_report.y = (((accel_report.y_raw - _parameters.acc_offset[0]) * range_g) / 8192.0f) / 9.81f;
+ accel_report.z = (((accel_report.z_raw - _parameters.acc_offset[0]) * range_g) / 8192.0f) / 9.81f;
} else {
orb_copy(ORB_ID(sensor_accel), _accel_sub, &accel_report);
@@ -640,14 +640,16 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
read(_fd_gyro_l3gd20, buf, sizeof(buf));
gyro_report.timestamp = hrt_absolute_time();
- gyro_report.x_raw = buf[0];
- gyro_report.y_raw = buf[1];
- gyro_report.z_raw = buf[2];
-
- /* XXX scale raw values to readings */
- gyro_report.x = 0;
- gyro_report.y = 0;
- gyro_report.z = 0;
+
+ gyro_report.x_raw = ((buf[1] == -32768) ? -32768 : buf[1]);
+ gyro_report.y_raw = ((buf[0] == -32768) ? 32767 : -buf[0]);
+ gyro_report.z_raw = ((buf[2] == -32768) ? -32768 : buf[2]);
+
+ /* scaling calculated as: raw * (1/(32768*(500/180*PI))) */
+ gyro_report.x = (gyro_report.x_raw - _parameters.gyro_offset[0]) * 0.000266316109f;
+ gyro_report.y = (gyro_report.y_raw - _parameters.gyro_offset[1]) * 0.000266316109f;
+ gyro_report.z = (gyro_report.z_raw - _parameters.gyro_offset[2]) * 0.000266316109f;
+
} else {
orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &gyro_report);