Merge branch 'master' of github.com:PX4/Firmware

This commit is contained in:
Lorenz Meier
2012-08-31 21:06:30 +02:00
5 changed files with 399 additions and 267 deletions
File diff suppressed because it is too large Load Diff
+1 -1
View File
@@ -109,7 +109,7 @@ ORB_DECLARE(sensor_accel);
/** set the accel measurement range to handle at least (arg) g */
#define ACCELIOCSRANGE _ACCELIOC(7)
/** get the current accel measurement range */
/** get the current accel measurement range in g */
#define ACCELIOCGRANGE _ACCELIOC(8)
#endif /* _DRV_ACCEL_H */
+2 -2
View File
@@ -103,10 +103,10 @@ ORB_DECLARE(sensor_gyro);
/** get the gyro scaling constants into (arg) */
#define GYROIOCGSCALE _GYROIOC(5)
/** set the gyro measurement range to handle at least (arg) g */
/** set the gyro measurement range to handle at least (arg) degrees per second */
#define GYROIOCSRANGE _GYROIOC(6)
/** get the current gyro measurement range */
/** get the current gyro measurement range in degrees per second */
#define GYROIOCGRANGE _GYROIOC(7)
#endif /* _DRV_GYRO_H */
+10 -12
View File
@@ -146,9 +146,6 @@ static const int ERROR = -1;
#define FIFO_CTRL_STREAM_TO_FIFO_MODE (3<<5)
#define FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
extern "C" { __EXPORT int l3gd20_main(int argc, char *argv[]); }
class L3GD20 : public device::SPI
@@ -268,12 +265,6 @@ private:
#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
/*
* Driver 'main' command.
*/
extern "C" { int l3gd20_main(int argc, char *argv[]); }
L3GD20::L3GD20(int bus, spi_dev_e device) :
SPI("L3GD20", GYRO_DEVICE_PATH, bus, device, SPIDEV_MODE3, 8000000),
_call_interval(0),
@@ -689,12 +680,19 @@ L3GD20::measure()
report->y_raw = raw_report.y;
report->z_raw = raw_report.z;
report->x = ((raw_report.x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
report->y = ((raw_report.y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
report->z = ((raw_report.z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
report->x = ((report->x_raw * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
report->y = ((report->y_raw * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
report->z = ((report->z_raw * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
report->scaling = _gyro_range_scale;
report->range_rad_s = _gyro_range_rad_s;
/* post a report to the ring - note, not locked */
INCREMENT(_next_report, _num_reports);
/* if we are running up against the oldest report, fix it */
if (_next_report == _oldest_report)
INCREMENT(_oldest_report, _num_reports);
/* notify anyone waiting for data */
poll_notify(POLLIN);
+4 -2
View File
@@ -45,6 +45,7 @@ CONFIGURED_APPS += system/readline
CONFIGURED_APPS += systemlib
CONFIGURED_APPS += systemlib/mixer
# System utility commands
CONFIGURED_APPS += systemcmds/reboot
CONFIGURED_APPS += systemcmds/perf
CONFIGURED_APPS += systemcmds/top
@@ -62,6 +63,7 @@ CONFIGURED_APPS += systemcmds/led
# https://pixhawk.ethz.ch/px4/dev/deamon
# CONFIGURED_APPS += examples/px4_deamon_app
# Shared object broker; required by many parts of the system.
CONFIGURED_APPS += uORB
CONFIGURED_APPS += mavlink
@@ -76,6 +78,7 @@ CONFIGURED_APPS += fixedwing_control
CONFIGURED_APPS += position_estimator
CONFIGURED_APPS += attitude_estimator_ekf
# Hacking tools
#CONFIGURED_APPS += system/i2c
#CONFIGURED_APPS += tools/i2c_dev
@@ -84,7 +87,7 @@ CONFIGURED_APPS += drivers/device
CONFIGURED_APPS += drivers/ms5611
CONFIGURED_APPS += drivers/hmc5883
CONFIGURED_APPS += drivers/mpu6000
#CONFIGURED_APPS += drivers/bma180
CONFIGURED_APPS += drivers/bma180
CONFIGURED_APPS += drivers/l3gd20
CONFIGURED_APPS += px4/px4io/driver
CONFIGURED_APPS += px4/fmu
@@ -102,4 +105,3 @@ endif
CONFIGURED_APPS += examples/cdcacm
#endif
#endif