aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-07-15 22:07:03 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-07-15 22:07:03 +0200
commite696ed5509d001e181c33a2379d634e76190c42a (patch)
tree8fd3e88c0782ceb90e6b9589daa1290d548058fd /src/drivers
parent79aa600d29c66e4619aacf73e71e51df13560205 (diff)
parent619433d36911b9c3923bae666d3632beb713935f (diff)
downloadpx4-firmware-e696ed5509d001e181c33a2379d634e76190c42a.tar.gz
px4-firmware-e696ed5509d001e181c33a2379d634e76190c42a.tar.bz2
px4-firmware-e696ed5509d001e181c33a2379d634e76190c42a.zip
Merged master
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/ardrone_interface/ardrone_motor_control.c2
-rw-r--r--src/drivers/ardrone_interface/module.mk2
-rw-r--r--src/drivers/blinkm/blinkm.cpp15
-rw-r--r--src/drivers/blinkm/module.mk2
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h1
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_init.c2
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_led.c4
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h13
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_led.c2
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_spi.c24
-rw-r--r--src/drivers/device/cdev.cpp7
-rw-r--r--src/drivers/device/device.cpp12
-rw-r--r--src/drivers/device/device.h28
-rw-r--r--src/drivers/device/i2c.cpp8
-rw-r--r--src/drivers/device/spi.cpp72
-rw-r--r--src/drivers/device/spi.h6
-rw-r--r--src/drivers/drv_device.h7
-rw-r--r--src/drivers/drv_mag.h7
-rw-r--r--src/drivers/drv_px4flow.h16
-rw-r--r--src/drivers/drv_range_finder.h9
-rw-r--r--src/drivers/drv_rc_input.h9
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp8
-rw-r--r--src/drivers/frsky_telemetry/module.mk2
-rw-r--r--src/drivers/gps/gps.cpp148
-rw-r--r--src/drivers/gps/gps_helper.h4
-rw-r--r--src/drivers/gps/module.mk2
-rw-r--r--src/drivers/gps/mtk.cpp10
-rw-r--r--src/drivers/gps/ubx.cpp1123
-rw-r--r--src/drivers/gps/ubx.h712
-rw-r--r--src/drivers/hil/hil.cpp2
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp327
-rw-r--r--src/drivers/hott/hott_sensors/module.mk2
-rw-r--r--src/drivers/hott/hott_telemetry/module.mk2
-rw-r--r--src/drivers/hott/messages.cpp2
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp70
-rw-r--r--src/drivers/ll40ls/ll40ls.cpp882
-rw-r--r--src/drivers/ll40ls/module.mk42
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp86
-rw-r--r--src/drivers/mb12xx/mb12xx.cpp45
-rw-r--r--src/drivers/mb12xx/module.mk2
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp6
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp27
-rw-r--r--src/drivers/mkblctrl/module.mk4
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp165
-rw-r--r--src/drivers/ms5611/ms5611.cpp47
-rw-r--r--src/drivers/ms5611/ms5611.h2
-rw-r--r--src/drivers/ms5611/ms5611_spi.cpp14
-rw-r--r--src/drivers/px4fmu/fmu.cpp18
-rw-r--r--src/drivers/px4io/px4io.cpp54
-rwxr-xr-x[-rw-r--r--]src/drivers/px4io/px4io_i2c.cpp2
-rw-r--r--src/drivers/px4io/px4io_serial.cpp2
-rw-r--r--src/drivers/px4io/px4io_uploader.cpp28
-rw-r--r--src/drivers/roboclaw/RoboClaw.cpp10
-rw-r--r--src/drivers/sf0x/module.mk2
-rw-r--r--src/drivers/sf0x/sf0x.cpp2
55 files changed, 3011 insertions, 1091 deletions
diff --git a/src/drivers/ardrone_interface/ardrone_motor_control.c b/src/drivers/ardrone_interface/ardrone_motor_control.c
index 81f634992..fc017dd58 100644
--- a/src/drivers/ardrone_interface/ardrone_motor_control.c
+++ b/src/drivers/ardrone_interface/ardrone_motor_control.c
@@ -382,8 +382,6 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
float output_band = 0.0f;
const float startpoint_full_control = 0.25f; /**< start full control at 25% thrust */
- static bool initialized = false;
-
/* linearly scale the control inputs from 0 to startpoint_full_control */
if (motor_thrust < startpoint_full_control) {
output_band = motor_thrust/startpoint_full_control; // linear from 0 to 1
diff --git a/src/drivers/ardrone_interface/module.mk b/src/drivers/ardrone_interface/module.mk
index d8e6c76c6..285db1351 100644
--- a/src/drivers/ardrone_interface/module.mk
+++ b/src/drivers/ardrone_interface/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = ardrone_interface
SRCS = ardrone_interface.c \
ardrone_motor_control.c
MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 5c502f682..6b14f5945 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -293,7 +293,7 @@ BlinkM::BlinkM(int bus, int blinkm) :
safety_sub_fd(-1),
num_of_cells(0),
detected_cells_runcount(0),
- t_led_color({0}),
+ t_led_color{0},
t_led_blink(0),
led_thread_runcount(0),
led_interval(1000),
@@ -559,13 +559,7 @@ BlinkM::led()
}
/* get number of used satellites in navigation */
- num_of_used_sats = 0;
-
- for(unsigned satloop=0; satloop<sizeof(vehicle_gps_position_raw.satellite_used); satloop++) {
- if(vehicle_gps_position_raw.satellite_used[satloop] == 1) {
- num_of_used_sats++;
- }
- }
+ num_of_used_sats = vehicle_gps_position_raw.satellites_used;
if (new_data_vehicle_status || no_data_vehicle_status < 3) {
if (num_of_cells == 0) {
@@ -655,13 +649,14 @@ BlinkM::led()
/* indicate main control state */
if (vehicle_status_raw.main_state == MAIN_STATE_POSCTL)
led_color_4 = LED_GREEN;
- else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO)
+ /* TODO: add other Auto modes */
+ else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO_MISSION)
led_color_4 = LED_BLUE;
else if (vehicle_status_raw.main_state == MAIN_STATE_ALTCTL)
led_color_4 = LED_YELLOW;
else if (vehicle_status_raw.main_state == MAIN_STATE_MANUAL)
led_color_4 = LED_WHITE;
- else
+ else
led_color_4 = LED_OFF;
led_color_5 = led_color_4;
}
diff --git a/src/drivers/blinkm/module.mk b/src/drivers/blinkm/module.mk
index b48b90f3f..c90673317 100644
--- a/src/drivers/blinkm/module.mk
+++ b/src/drivers/blinkm/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = blinkm
SRCS = blinkm.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
index c944007a5..a70a6240c 100644
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -86,7 +86,6 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
#define PX4_SPI_BUS_SENSORS 1
-#define PX4_SPI_BUS_EXT 2
/*
* Use these in place of the spi_dev_e enumeration to
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_init.c b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
index 4b12b75f9..293021f8b 100644
--- a/src/drivers/boards/px4fmu-v1/px4fmu_init.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
@@ -99,7 +99,7 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
-extern void led_init();
+extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_led.c b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
index ea91f34ad..ee53fc43d 100644
--- a/src/drivers/boards/px4fmu-v1/px4fmu_led.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
@@ -54,13 +54,13 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
-extern void led_init();
+extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
__END_DECLS
-__EXPORT void led_init()
+__EXPORT void led_init(void)
{
/* Configure LED1-2 GPIOs for output */
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index 36eb7bec4..0190a5b5b 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -108,6 +108,8 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
#define GPIO_SPI_CS_EXT0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
#define GPIO_SPI_CS_EXT1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
+#define GPIO_SPI_CS_EXT2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
+#define GPIO_SPI_CS_EXT3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_EXT 4
@@ -121,10 +123,19 @@ __BEGIN_DECLS
/* External bus */
#define PX4_SPIDEV_EXT0 1
#define PX4_SPIDEV_EXT1 2
+#define PX4_SPIDEV_EXT2 3
+#define PX4_SPIDEV_EXT3 4
+
+/* FMUv3 SPI on external bus */
+#define PX4_SPIDEV_EXT_MPU PX4_SPIDEV_EXT0
+#define PX4_SPIDEV_EXT_BARO PX4_SPIDEV_EXT1
+#define PX4_SPIDEV_EXT_ACCEL_MAG PX4_SPIDEV_EXT2
+#define PX4_SPIDEV_EXT_GYRO PX4_SPIDEV_EXT3
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
-#define PX4_I2C_BUS_LED 2
+#define PX4_I2C_BUS_ONBOARD 2
+#define PX4_I2C_BUS_LED PX4_I2C_BUS_ONBOARD
/* Devices on the onboard bus.
*
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_led.c b/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
index a856ccb02..3c05bfa46 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
@@ -54,7 +54,7 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
-extern void led_init();
+extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
index 01dbd6e77..8c37d31a7 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
@@ -98,8 +98,12 @@ __EXPORT void weak_function stm32_spiinitialize(void)
#ifdef CONFIG_STM32_SPI4
stm32_configgpio(GPIO_SPI_CS_EXT0);
stm32_configgpio(GPIO_SPI_CS_EXT1);
+ stm32_configgpio(GPIO_SPI_CS_EXT2);
+ stm32_configgpio(GPIO_SPI_CS_EXT3);
stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1);
#endif
}
@@ -174,12 +178,32 @@ __EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
/* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_EXT0, !selected);
stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1);
break;
case PX4_SPIDEV_EXT1:
/* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
stm32_gpiowrite(GPIO_SPI_CS_EXT1, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1);
+ break;
+
+ case PX4_SPIDEV_EXT2:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT2, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1);
+ break;
+
+ case PX4_SPIDEV_EXT3:
+ /* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT3, !selected);
break;
default:
diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp
index 6e2ebb1f7..39fb89501 100644
--- a/src/drivers/device/cdev.cpp
+++ b/src/drivers/device/cdev.cpp
@@ -268,6 +268,13 @@ CDev::ioctl(struct file *filp, int cmd, unsigned long arg)
break;
}
+ /* try the superclass. The different ioctl() function form
+ * means we need to copy arg */
+ unsigned arg2 = arg;
+ int ret = Device::ioctl(cmd, arg2);
+ if (ret != -ENODEV)
+ return ret;
+
return -ENOTTY;
}
diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp
index 683455149..f1f777dce 100644
--- a/src/drivers/device/device.cpp
+++ b/src/drivers/device/device.cpp
@@ -42,6 +42,7 @@
#include <nuttx/arch.h>
#include <stdio.h>
#include <unistd.h>
+#include <drivers/drv_device.h>
namespace device
{
@@ -93,6 +94,13 @@ Device::Device(const char *name,
_irq_attached(false)
{
sem_init(&_lock, 0, 1);
+
+ /* setup a default device ID. When bus_type is UNKNOWN the
+ other fields are invalid */
+ _device_id.devid_s.bus_type = DeviceBusType_UNKNOWN;
+ _device_id.devid_s.bus = 0;
+ _device_id.devid_s.address = 0;
+ _device_id.devid_s.devtype = 0;
}
Device::~Device()
@@ -238,6 +246,10 @@ Device::write(unsigned offset, void *data, unsigned count)
int
Device::ioctl(unsigned operation, unsigned &arg)
{
+ switch (operation) {
+ case DEVIOCGDEVICEID:
+ return (int)_device_id.devid;
+ }
return -ENODEV;
}
diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h
index be6f6f4ec..b65649d9d 100644
--- a/src/drivers/device/device.h
+++ b/src/drivers/device/device.h
@@ -124,9 +124,37 @@ public:
*/
virtual int ioctl(unsigned operation, unsigned &arg);
+ /*
+ device bus types for DEVID
+ */
+ enum DeviceBusType {
+ DeviceBusType_UNKNOWN = 0,
+ DeviceBusType_I2C = 1,
+ DeviceBusType_SPI = 2
+ };
+
+ /*
+ broken out device elements. The bitfields are used to keep
+ the overall value small enough to fit in a float accurately,
+ which makes it possible to transport over the MAVLink
+ parameter protocol without loss of information.
+ */
+ struct DeviceStructure {
+ enum DeviceBusType bus_type:3;
+ uint8_t bus:5; // which instance of the bus type
+ uint8_t address; // address on the bus (eg. I2C address)
+ uint8_t devtype; // device class specific device type
+ };
+
+ union DeviceId {
+ struct DeviceStructure devid_s;
+ uint32_t devid;
+ };
+
protected:
const char *_name; /**< driver name */
bool _debug_enabled; /**< if true, debug messages are printed */
+ union DeviceId _device_id; /**< device identifier information */
/**
* Constructor
diff --git a/src/drivers/device/i2c.cpp b/src/drivers/device/i2c.cpp
index a416801eb..286778c01 100644
--- a/src/drivers/device/i2c.cpp
+++ b/src/drivers/device/i2c.cpp
@@ -62,6 +62,12 @@ I2C::I2C(const char *name,
_frequency(frequency),
_dev(nullptr)
{
+ // fill in _device_id fields for a I2C device
+ _device_id.devid_s.bus_type = DeviceBusType_I2C;
+ _device_id.devid_s.bus = bus;
+ _device_id.devid_s.address = address;
+ // devtype needs to be filled in by the driver
+ _device_id.devid_s.devtype = 0;
}
I2C::~I2C()
@@ -201,4 +207,4 @@ I2C::transfer(i2c_msg_s *msgv, unsigned msgs)
return ret;
}
-} // namespace device \ No newline at end of file
+} // namespace device
diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp
index fed6c312c..200acac05 100644
--- a/src/drivers/device/spi.cpp
+++ b/src/drivers/device/spi.cpp
@@ -69,12 +69,18 @@ SPI::SPI(const char *name,
// protected
locking_mode(LOCK_PREEMPTION),
// private
- _bus(bus),
_device(device),
_mode(mode),
_frequency(frequency),
- _dev(nullptr)
+ _dev(nullptr),
+ _bus(bus)
{
+ // fill in _device_id fields for a SPI device
+ _device_id.devid_s.bus_type = DeviceBusType_SPI;
+ _device_id.devid_s.bus = bus;
+ _device_id.devid_s.address = (uint8_t)device;
+ // devtype needs to be filled in by the driver
+ _device_id.devid_s.devtype = 0;
}
SPI::~SPI()
@@ -133,26 +139,44 @@ SPI::probe()
int
SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
{
- irqstate_t state;
+ int result;
if ((send == nullptr) && (recv == nullptr))
return -EINVAL;
+ LockMode mode = up_interrupt_context() ? LOCK_NONE : locking_mode;
+
/* lock the bus as required */
- if (!up_interrupt_context()) {
- switch (locking_mode) {
- default:
- case LOCK_PREEMPTION:
- state = irqsave();
- break;
- case LOCK_THREADS:
- SPI_LOCK(_dev, true);
- break;
- case LOCK_NONE:
- break;
+ switch (mode) {
+ default:
+ case LOCK_PREEMPTION:
+ {
+ irqstate_t state = irqsave();
+ result = _transfer(send, recv, len);
+ irqrestore(state);
}
+ break;
+ case LOCK_THREADS:
+ SPI_LOCK(_dev, true);
+ result = _transfer(send, recv, len);
+ SPI_LOCK(_dev, false);
+ break;
+ case LOCK_NONE:
+ result = _transfer(send, recv, len);
+ break;
}
+ return result;
+}
+void
+SPI::set_frequency(uint32_t frequency)
+{
+ _frequency = frequency;
+}
+
+int
+SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
+{
SPI_SETFREQUENCY(_dev, _frequency);
SPI_SETMODE(_dev, _mode);
SPI_SETBITS(_dev, 8);
@@ -164,27 +188,7 @@ SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
/* and clean up */
SPI_SELECT(_dev, _device, false);
- if (!up_interrupt_context()) {
- switch (locking_mode) {
- default:
- case LOCK_PREEMPTION:
- irqrestore(state);
- break;
- case LOCK_THREADS:
- SPI_LOCK(_dev, false);
- break;
- case LOCK_NONE:
- break;
- }
- }
-
return OK;
}
-void
-SPI::set_frequency(uint32_t frequency)
-{
- _frequency = frequency;
-}
-
} // namespace device
diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h
index 299575dc5..54849c8c3 100644
--- a/src/drivers/device/spi.h
+++ b/src/drivers/device/spi.h
@@ -124,11 +124,15 @@ protected:
LockMode locking_mode; /**< selected locking mode */
private:
- int _bus;
enum spi_dev_e _device;
enum spi_mode_e _mode;
uint32_t _frequency;
struct spi_dev_s *_dev;
+
+protected:
+ int _bus;
+
+ int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
};
} // namespace device
diff --git a/src/drivers/drv_device.h b/src/drivers/drv_device.h
index b310beb74..19d55cef3 100644
--- a/src/drivers/drv_device.h
+++ b/src/drivers/drv_device.h
@@ -59,4 +59,11 @@
/** check publication block status */
#define DEVIOCGPUBBLOCK _DEVICEIOC(1)
+/**
+ * Return device ID, to enable matching of configuration parameters
+ * (such as compass offsets) to specific sensors
+ */
+#define DEVIOCGDEVICEID _DEVICEIOC(2)
+
+
#endif /* _DRV_DEVICE_H */
diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h
index 32e0e48b3..a6c509d31 100644
--- a/src/drivers/drv_mag.h
+++ b/src/drivers/drv_mag.h
@@ -82,6 +82,13 @@ struct mag_scale {
ORB_DECLARE(sensor_mag0);
ORB_DECLARE(sensor_mag1);
+
+/*
+ * mag device types, for _device_id
+ */
+#define DRV_MAG_DEVTYPE_HMC5883 1
+#define DRV_MAG_DEVTYPE_LSM303D 2
+
/*
* ioctl() definitions
*/
diff --git a/src/drivers/drv_px4flow.h b/src/drivers/drv_px4flow.h
index bef02d54e..76ec55c3e 100644
--- a/src/drivers/drv_px4flow.h
+++ b/src/drivers/drv_px4flow.h
@@ -47,9 +47,17 @@
#define PX4FLOW_DEVICE_PATH "/dev/px4flow"
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* Optical flow in NED body frame in SI units.
*
* @see http://en.wikipedia.org/wiki/International_System_of_Units
+ *
+ * @warning If possible the usage of the raw flow and performing rotation-compensation
+ * using the autopilot angular rate estimate is recommended.
*/
struct px4flow_report {
@@ -57,14 +65,18 @@ struct px4flow_report {
int16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */
int16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */
- float flow_comp_x_m; /**< speed over ground in meters, rotation-compensated */
- float flow_comp_y_m; /**< speed over ground in meters, rotation-compensated */
+ float flow_comp_x_m; /**< speed over ground in meters per second, rotation-compensated */
+ float flow_comp_y_m; /**< speed over ground in meters per second, rotation-compensated */
float ground_distance_m; /**< Altitude / distance to ground in meters */
uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */
uint8_t sensor_id; /**< id of the sensor emitting the flow value */
};
+/**
+ * @}
+ */
+
/*
* ObjDev tag for px4flow data.
*/
diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h
index e45939b37..0f8362f58 100644
--- a/src/drivers/drv_range_finder.h
+++ b/src/drivers/drv_range_finder.h
@@ -51,6 +51,11 @@ enum RANGE_FINDER_TYPE {
};
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* range finder report structure. Reads from the device must be in multiples of this
* structure.
*/
@@ -64,6 +69,10 @@ struct range_finder_report {
uint8_t valid; /**< 1 == within sensor range, 0 = outside sensor range */
};
+/**
+ * @}
+ */
+
/*
* ObjDev tag for raw range finder data.
*/
diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h
index 20763e265..47fa8fa59 100644
--- a/src/drivers/drv_rc_input.h
+++ b/src/drivers/drv_rc_input.h
@@ -68,6 +68,11 @@
#define RC_INPUT_RSSI_MAX 255
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* Input signal type, value is a control position from zero to 100
* percent.
*/
@@ -141,6 +146,10 @@ struct rc_input_values {
rc_input_t values[RC_INPUT_MAX_CHANNELS];
};
+/**
+ * @}
+ */
+
/*
* ObjDev tag for R/C inputs.
*/
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index 2de7063ea..c15a0cee4 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -172,6 +172,9 @@ ETSAirspeed::collect()
diff_pres_pa = diff_pres_pa_raw - _diff_pres_offset;
}
+ // The raw value still should be compensated for the known offset
+ diff_pres_pa_raw -= _diff_pres_offset;
+
// Track maximum differential pressure measured (so we can work out top speed).
if (diff_pres_pa > _max_differential_pressure_pa) {
_max_differential_pressure_pa = diff_pres_pa;
@@ -186,7 +189,6 @@ ETSAirspeed::collect()
report.differential_pressure_filtered_pa = (float)diff_pres_pa;
report.differential_pressure_raw_pa = (float)diff_pres_pa_raw;
report.temperature = -1000.0f;
- report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
if (_airspeed_pub > 0 && !(_pub_blocked)) {
@@ -364,7 +366,7 @@ test()
err(1, "immediate read failed");
warnx("single read");
- warnx("diff pressure: %d pa", report.differential_pressure_pa);
+ warnx("diff pressure: %f pa", (double)report.differential_pressure_pa);
/* start the sensor polling at 2Hz */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
@@ -389,7 +391,7 @@ test()
err(1, "periodic read failed");
warnx("periodic read %u", i);
- warnx("diff pressure: %d pa", report.differential_pressure_pa);
+ warnx("diff pressure: %f pa", (double)report.differential_pressure_pa);
}
/* reset the sensor polling to its default rate */
diff --git a/src/drivers/frsky_telemetry/module.mk b/src/drivers/frsky_telemetry/module.mk
index 9a49589ee..78ad6f67e 100644
--- a/src/drivers/frsky_telemetry/module.mk
+++ b/src/drivers/frsky_telemetry/module.mk
@@ -41,3 +41,5 @@ SRCS = frsky_data.c \
frsky_telemetry.c
MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index 5342ccf78..34dd63086 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -63,6 +63,7 @@
#include <drivers/drv_gps.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/satellite_info.h>
#include <board_config.h>
@@ -79,10 +80,18 @@
#endif
static const int ERROR = -1;
+/* class for dynamic allocation of satellite info data */
+class GPS_Sat_Info
+{
+public:
+ struct satellite_info_s _data;
+};
+
+
class GPS : public device::CDev
{
public:
- GPS(const char *uart_path, bool fake_gps);
+ GPS(const char *uart_path, bool fake_gps, bool enable_sat_info);
virtual ~GPS();
virtual int init();
@@ -100,14 +109,17 @@ private:
int _serial_fd; ///< serial interface to GPS
unsigned _baudrate; ///< current baudrate
char _port[20]; ///< device / serial port path
- volatile int _task; //< worker task
+ volatile int _task; ///< worker task
bool _healthy; ///< flag to signal if the GPS is ok
- bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed
+ bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed
bool _mode_changed; ///< flag that the GPS mode has changed
gps_driver_mode_t _mode; ///< current mode
GPS_Helper *_Helper; ///< instance of GPS parser
- struct vehicle_gps_position_s _report; ///< uORB topic for gps position
- orb_advert_t _report_pub; ///< uORB pub for gps position
+ GPS_Sat_Info *_Sat_Info; ///< instance of GPS sat info data object
+ struct vehicle_gps_position_s _report_gps_pos; ///< uORB topic for gps position
+ orb_advert_t _report_gps_pos_pub; ///< uORB pub for gps position
+ struct satellite_info_s *_p_report_sat_info; ///< pointer to uORB topic for satellite info
+ orb_advert_t _report_sat_info_pub; ///< uORB pub for satellite info
float _rate; ///< position update rate
bool _fake_gps; ///< fake gps output
@@ -115,7 +127,7 @@ private:
/**
* Try to configure the GPS, handle outgoing communication to the GPS
*/
- void config();
+ void config();
/**
* Trampoline to the worker task
@@ -154,14 +166,17 @@ GPS *g_dev;
}
-GPS::GPS(const char *uart_path, bool fake_gps) :
+GPS::GPS(const char *uart_path, bool fake_gps, bool enable_sat_info) :
CDev("gps", GPS_DEVICE_PATH),
_task_should_exit(false),
_healthy(false),
_mode_changed(false),
_mode(GPS_DRIVER_MODE_UBX),
_Helper(nullptr),
- _report_pub(-1),
+ _Sat_Info(nullptr),
+ _report_gps_pos_pub(-1),
+ _p_report_sat_info(nullptr),
+ _report_sat_info_pub(-1),
_rate(0.0f),
_fake_gps(fake_gps)
{
@@ -172,7 +187,14 @@ GPS::GPS(const char *uart_path, bool fake_gps) :
/* we need this potentially before it could be set in task_main */
g_dev = this;
- memset(&_report, 0, sizeof(_report));
+ memset(&_report_gps_pos, 0, sizeof(_report_gps_pos));
+
+ /* create satellite info data object if requested */
+ if (enable_sat_info) {
+ _Sat_Info = new(GPS_Sat_Info);
+ _p_report_sat_info = &_Sat_Info->_data;
+ memset(_p_report_sat_info, 0, sizeof(*_p_report_sat_info));
+ }
_debug_enabled = true;
}
@@ -207,7 +229,7 @@ GPS::init()
/* start the GPS driver worker task */
_task = task_spawn_cmd("gps", SCHED_DEFAULT,
- SCHED_PRIORITY_SLOW_DRIVER, 2000, (main_t)&GPS::task_main_trampoline, nullptr);
+ SCHED_PRIORITY_SLOW_DRIVER, 1500, (main_t)&GPS::task_main_trampoline, nullptr);
if (_task < 0) {
warnx("task start failed: %d", errno);
@@ -271,33 +293,32 @@ GPS::task_main()
if (_fake_gps) {
- _report.timestamp_position = hrt_absolute_time();
- _report.lat = (int32_t)47.378301e7f;
- _report.lon = (int32_t)8.538777e7f;
- _report.alt = (int32_t)1200e3f;
- _report.timestamp_variance = hrt_absolute_time();
- _report.s_variance_m_s = 10.0f;
- _report.p_variance_m = 10.0f;
- _report.c_variance_rad = 0.1f;
- _report.fix_type = 3;
- _report.eph_m = 0.9f;
- _report.epv_m = 1.8f;
- _report.timestamp_velocity = hrt_absolute_time();
- _report.vel_n_m_s = 0.0f;
- _report.vel_e_m_s = 0.0f;
- _report.vel_d_m_s = 0.0f;
- _report.vel_m_s = sqrtf(_report.vel_n_m_s * _report.vel_n_m_s + _report.vel_e_m_s * _report.vel_e_m_s + _report.vel_d_m_s * _report.vel_d_m_s);
- _report.cog_rad = 0.0f;
- _report.vel_ned_valid = true;
+ _report_gps_pos.timestamp_position = hrt_absolute_time();
+ _report_gps_pos.lat = (int32_t)47.378301e7f;
+ _report_gps_pos.lon = (int32_t)8.538777e7f;
+ _report_gps_pos.alt = (int32_t)1200e3f;
+ _report_gps_pos.timestamp_variance = hrt_absolute_time();
+ _report_gps_pos.s_variance_m_s = 10.0f;
+ _report_gps_pos.c_variance_rad = 0.1f;
+ _report_gps_pos.fix_type = 3;
+ _report_gps_pos.eph = 0.9f;
+ _report_gps_pos.epv = 1.8f;
+ _report_gps_pos.timestamp_velocity = hrt_absolute_time();
+ _report_gps_pos.vel_n_m_s = 0.0f;
+ _report_gps_pos.vel_e_m_s = 0.0f;
+ _report_gps_pos.vel_d_m_s = 0.0f;
+ _report_gps_pos.vel_m_s = sqrtf(_report_gps_pos.vel_n_m_s * _report_gps_pos.vel_n_m_s + _report_gps_pos.vel_e_m_s * _report_gps_pos.vel_e_m_s + _report_gps_pos.vel_d_m_s * _report_gps_pos.vel_d_m_s);
+ _report_gps_pos.cog_rad = 0.0f;
+ _report_gps_pos.vel_ned_valid = true;
//no time and satellite information simulated
if (!(_pub_blocked)) {
- if (_report_pub > 0) {
- orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+ if (_report_gps_pos_pub > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
} else {
- _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ _report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
}
}
@@ -313,11 +334,11 @@ GPS::task_main()
switch (_mode) {
case GPS_DRIVER_MODE_UBX:
- _Helper = new UBX(_serial_fd, &_report);
+ _Helper = new UBX(_serial_fd, &_report_gps_pos, _p_report_sat_info);
break;
case GPS_DRIVER_MODE_MTK:
- _Helper = new MTK(_serial_fd, &_report);
+ _Helper = new MTK(_serial_fd, &_report_gps_pos);
break;
default:
@@ -332,20 +353,33 @@ GPS::task_main()
// GPS is obviously detected successfully, reset statistics
_Helper->reset_update_rates();
- while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) {
+ int helper_ret;
+ while ((helper_ret = _Helper->receive(TIMEOUT_5HZ)) > 0 && !_task_should_exit) {
// lock();
/* opportunistic publishing - else invalid data would end up on the bus */
if (!(_pub_blocked)) {
- if (_report_pub > 0) {
- orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+ if (helper_ret & 1) {
+ if (_report_gps_pos_pub > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
- } else {
- _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ } else {
+ _report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
+ }
+ }
+ if (_p_report_sat_info && (helper_ret & 2)) {
+ if (_report_sat_info_pub > 0) {
+ orb_publish(ORB_ID(satellite_info), _report_sat_info_pub, _p_report_sat_info);
+
+ } else {
+ _report_sat_info_pub = orb_advertise(ORB_ID(satellite_info), _p_report_sat_info);
+ }
}
}
- last_rate_count++;
+ if (helper_ret & 1) { // consider only pos info updates for rate calculation */
+ last_rate_count++;
+ }
/* measure update rate every 5 seconds */
if (hrt_absolute_time() - last_rate_measurement > RATE_MEASUREMENT_PERIOD) {
@@ -357,7 +391,7 @@ GPS::task_main()
}
if (!_healthy) {
- char *mode_str = "unknown";
+ const char *mode_str = "unknown";
switch (_mode) {
case GPS_DRIVER_MODE_UBX:
@@ -446,12 +480,15 @@ GPS::print_info()
}
warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK");
-
- if (_report.timestamp_position != 0) {
- warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report.fix_type,
- _report.satellites_visible, (double)(hrt_absolute_time() - _report.timestamp_position) / 1000.0f);
- warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt);
- warnx("eph: %.2fm, epv: %.2fm", (double)_report.eph_m, (double)_report.epv_m);
+ warnx("sat info: %s", (_p_report_sat_info != nullptr) ? "enabled" : "disabled");
+
+ if (_report_gps_pos.timestamp_position != 0) {
+ warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report_gps_pos.fix_type,
+ _report_gps_pos.satellites_used, (double)(hrt_absolute_time() - _report_gps_pos.timestamp_position) / 1000.0);
+ warnx("lat: %d, lon: %d, alt: %d", _report_gps_pos.lat, _report_gps_pos.lon, _report_gps_pos.alt);
+ warnx("vel: %.2fm/s, %.2fm/s, %.2fm/s", (double)_report_gps_pos.vel_n_m_s,
+ (double)_report_gps_pos.vel_e_m_s, (double)_report_gps_pos.vel_d_m_s);
+ warnx("eph: %.2fm, epv: %.2fm", (double)_report_gps_pos.eph, (double)_report_gps_pos.epv);
warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate());
warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate());
warnx("rate publication:\t%6.2f Hz", (double)_rate);
@@ -469,7 +506,7 @@ namespace gps
GPS *g_dev;
-void start(const char *uart_path, bool fake_gps);
+void start(const char *uart_path, bool fake_gps, bool enable_sat_info);
void stop();
void test();
void reset();
@@ -479,7 +516,7 @@ void info();
* Start the driver.
*/
void
-start(const char *uart_path, bool fake_gps)
+start(const char *uart_path, bool fake_gps, bool enable_sat_info)
{
int fd;
@@ -487,7 +524,7 @@ start(const char *uart_path, bool fake_gps)
errx(1, "already started");
/* create the driver */
- g_dev = new GPS(uart_path, fake_gps);
+ g_dev = new GPS(uart_path, fake_gps, enable_sat_info);
if (g_dev == nullptr)
goto fail;
@@ -578,8 +615,9 @@ gps_main(int argc, char *argv[])
{
/* set to default */
- char *device_name = GPS_DEFAULT_UART_PORT;
+ const char *device_name = GPS_DEFAULT_UART_PORT;
bool fake_gps = false;
+ bool enable_sat_info = false;
/*
* Start/load the driver.
@@ -601,7 +639,13 @@ gps_main(int argc, char *argv[])
fake_gps = true;
}
- gps::start(device_name, fake_gps);
+ /* Detect sat info option */
+ for (int i = 2; i < argc; i++) {
+ if (!strcmp(argv[i], "-s"))
+ enable_sat_info = true;
+ }
+
+ gps::start(device_name, fake_gps, enable_sat_info);
}
if (!strcmp(argv[1], "stop"))
@@ -626,5 +670,5 @@ gps_main(int argc, char *argv[])
gps::info();
out:
- errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n][-f]");
+ errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n][-f][-s]");
}
diff --git a/src/drivers/gps/gps_helper.h b/src/drivers/gps/gps_helper.h
index d14a95afe..3623397b2 100644
--- a/src/drivers/gps/gps_helper.h
+++ b/src/drivers/gps/gps_helper.h
@@ -62,8 +62,8 @@ protected:
uint8_t _rate_count_lat_lon;
uint8_t _rate_count_vel;
- float _rate_lat_lon;
- float _rate_vel;
+ float _rate_lat_lon = 0.0f;
+ float _rate_vel = 0.0f;
uint64_t _interval_rate_start;
};
diff --git a/src/drivers/gps/module.mk b/src/drivers/gps/module.mk
index eb382c4b2..b00818424 100644
--- a/src/drivers/gps/module.mk
+++ b/src/drivers/gps/module.mk
@@ -43,3 +43,5 @@ SRCS = gps.cpp \
ubx.cpp
MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp
index 680f00d97..c4f4f7bec 100644
--- a/src/drivers/gps/mtk.cpp
+++ b/src/drivers/gps/mtk.cpp
@@ -251,19 +251,19 @@ MTK::handle_message(gps_mtk_packet_t &packet)
_gps_position->lon = 0;
// Indicate this data is not usable and bail out
- _gps_position->eph_m = 1000.0f;
- _gps_position->epv_m = 1000.0f;
+ _gps_position->eph = 1000.0f;
+ _gps_position->epv = 1000.0f;
_gps_position->fix_type = 0;
return;
}
_gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm
_gps_position->fix_type = packet.fix_type;
- _gps_position->eph_m = packet.hdop / 100.0f; // from cm to m
- _gps_position->epv_m = _gps_position->eph_m; // unknown in mtk custom mode, so we cheat with eph
+ _gps_position->eph = packet.hdop / 100.0f; // from cm to m
+ _gps_position->epv = _gps_position->eph; // unknown in mtk custom mode, so we cheat with eph
_gps_position->vel_m_s = ((float)packet.ground_speed) * 1e-2f; // from cm/s to m/s
_gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad
- _gps_position->satellites_visible = packet.satellites;
+ _gps_position->satellites_used = packet.satellites;
/* convert time and date information to unix timestamp */
struct tm timeinfo; //TODO: test this conversion
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index c143eeb0c..d0854f5e9 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 2013, 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
@@ -34,14 +34,18 @@
/**
* @file ubx.cpp
*
- * U-Blox protocol implementation. Following u-blox 6/7 Receiver Description
+ * U-Blox protocol implementation. Following u-blox 6/7/8 Receiver Description
* including Prototol Specification.
*
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
*
+ * @author Hannes Delago
+ * (rework, add ubx7+ compatibility)
+ *
* @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
+ * @see http://www.u-blox.com/images/downloads/Product_Docs/u-bloxM8-V15_ReceiverDescriptionProtocolSpec_Public_%28UBX-13003221%29.pdf
*/
#include <assert.h>
@@ -55,24 +59,44 @@
#include <systemlib/err.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/satellite_info.h>
#include <drivers/drv_hrt.h>
#include "ubx.h"
-#define UBX_CONFIG_TIMEOUT 200 // ms, timeout for waiting ACK
-#define UBX_PACKET_TIMEOUT 2 // ms, if now data during this delay assume that full update received
+#define UBX_CONFIG_TIMEOUT 200 // ms, timeout for waiting ACK
+#define UBX_PACKET_TIMEOUT 2 // ms, if now data during this delay assume that full update received
#define UBX_WAIT_BEFORE_READ 20 // ms, wait before reading to save read() calls
-#define DISABLE_MSG_INTERVAL 1000000 // us, try to disable message with this interval
+#define DISABLE_MSG_INTERVAL 1000000 // us, try to disable message with this interval
+
+#define MIN(X,Y) ((X) < (Y) ? (X) : (Y))
+#define SWAP16(X) ((((X) >> 8) & 0x00ff) | (((X) << 8) & 0xff00))
+
+#define FNV1_32_INIT ((uint32_t)0x811c9dc5) // init value for FNV1 hash algorithm
+#define FNV1_32_PRIME ((uint32_t)0x01000193) // magic prime for FNV1 hash algorithm
+
-UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) :
+/**** Trace macros, disable for production builds */
+#define UBX_TRACE_PARSER(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* decoding progress in parse_char() */
+#define UBX_TRACE_RXMSG(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* Rx msgs in payload_rx_done() */
+#define UBX_TRACE_SVINFO(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* NAV-SVINFO processing (debug use only, will cause rx buffer overflows) */
+
+/**** Warning macros, disable to save memory */
+#define UBX_WARN(s, ...) {warnx(s, ## __VA_ARGS__);}
+
+
+UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info) :
_fd(fd),
_gps_position(gps_position),
+ _satellite_info(satellite_info),
_configured(false),
- _waiting_for_ack(false),
+ _ack_state(UBX_ACK_IDLE),
_got_posllh(false),
_got_velned(false),
- _got_timeutc(false),
- _disable_cmd_last(0)
+ _disable_cmd_last(0),
+ _ack_waiting_msg(0),
+ _ubx_version(0),
+ _use_nav_pvt(false)
{
decode_init();
}
@@ -86,182 +110,167 @@ UBX::configure(unsigned &baudrate)
{
_configured = false;
/* try different baudrates */
- const unsigned baudrates_to_try[] = {9600, 38400, 19200, 57600, 115200};
+ const unsigned baudrates[] = {9600, 38400, 19200, 57600, 115200};
- int baud_i;
+ unsigned baud_i;
- for (baud_i = 0; baud_i < 5; baud_i++) {
- baudrate = baudrates_to_try[baud_i];
+ for (baud_i = 0; baud_i < sizeof(baudrates) / sizeof(baudrates[0]); baud_i++) {
+ baudrate = baudrates[baud_i];
set_baudrate(_fd, baudrate);
+ /* flush input and wait for at least 20 ms silence */
+ decode_init();
+ receive(20);
+ decode_init();
+
/* Send a CFG-PRT message to set the UBX protocol for in and out
- * and leave the baudrate as it is, we just want an ACK-ACK from this
- */
- type_gps_bin_cfg_prt_packet_t cfg_prt_packet;
- /* Set everything else of the packet to 0, otherwise the module wont accept it */
- memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet));
-
- _message_class_needed = UBX_CLASS_CFG;
- _message_id_needed = UBX_MESSAGE_CFG_PRT;
-
- /* Define the package contents, don't change the baudrate */
- cfg_prt_packet.clsID = UBX_CLASS_CFG;
- cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT;
- cfg_prt_packet.length = UBX_CFG_PRT_LENGTH;
- cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID;
- cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE;
- cfg_prt_packet.baudRate = baudrate;
- cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK;
- cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
-
- send_config_packet(_fd, (uint8_t *)&cfg_prt_packet, sizeof(cfg_prt_packet));
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ * and leave the baudrate as it is, we just want an ACK-ACK for this */
+ memset(&_buf.payload_tx_cfg_prt, 0, sizeof(_buf.payload_tx_cfg_prt));
+ _buf.payload_tx_cfg_prt.portID = UBX_TX_CFG_PRT_PORTID;
+ _buf.payload_tx_cfg_prt.mode = UBX_TX_CFG_PRT_MODE;
+ _buf.payload_tx_cfg_prt.baudRate = baudrate;
+ _buf.payload_tx_cfg_prt.inProtoMask = UBX_TX_CFG_PRT_INPROTOMASK;
+ _buf.payload_tx_cfg_prt.outProtoMask = UBX_TX_CFG_PRT_OUTPROTOMASK;
+
+ send_message(UBX_MSG_CFG_PRT, _buf.raw, sizeof(_buf.payload_tx_cfg_prt));
+
+ if (wait_for_ack(UBX_MSG_CFG_PRT, UBX_CONFIG_TIMEOUT, false) < 0) {
/* try next baudrate */
continue;
}
/* Send a CFG-PRT message again, this time change the baudrate */
+ memset(&_buf.payload_tx_cfg_prt, 0, sizeof(_buf.payload_tx_cfg_prt));
+ _buf.payload_tx_cfg_prt.portID = UBX_TX_CFG_PRT_PORTID;
+ _buf.payload_tx_cfg_prt.mode = UBX_TX_CFG_PRT_MODE;
+ _buf.payload_tx_cfg_prt.baudRate = UBX_TX_CFG_PRT_BAUDRATE;
+ _buf.payload_tx_cfg_prt.inProtoMask = UBX_TX_CFG_PRT_INPROTOMASK;
+ _buf.payload_tx_cfg_prt.outProtoMask = UBX_TX_CFG_PRT_OUTPROTOMASK;
- cfg_prt_packet.clsID = UBX_CLASS_CFG;
- cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT;
- cfg_prt_packet.length = UBX_CFG_PRT_LENGTH;
- cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID;
- cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE;
- cfg_prt_packet.baudRate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
- cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK;
- cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
-
- send_config_packet(_fd, (uint8_t *)&cfg_prt_packet, sizeof(cfg_prt_packet));
+ send_message(UBX_MSG_CFG_PRT, _buf.raw, sizeof(_buf.payload_tx_cfg_prt));
/* no ACK is expected here, but read the buffer anyway in case we actually get an ACK */
- wait_for_ack(UBX_CONFIG_TIMEOUT);
+ wait_for_ack(UBX_MSG_CFG_PRT, UBX_CONFIG_TIMEOUT, false);
- if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) {
- set_baudrate(_fd, UBX_CFG_PRT_PAYLOAD_BAUDRATE);
- baudrate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
+ if (UBX_TX_CFG_PRT_BAUDRATE != baudrate) {
+ set_baudrate(_fd, UBX_TX_CFG_PRT_BAUDRATE);
+ baudrate = UBX_TX_CFG_PRT_BAUDRATE;
}
/* at this point we have correct baudrate on both ends */
break;
}
- if (baud_i >= 5) {
- return 1;
+ if (baud_i >= sizeof(baudrates) / sizeof(baudrates[0])) {
+ return 1; // connection and/or baudrate detection failed
}
- /* send a CFG-RATE message to define update rate */
- type_gps_bin_cfg_rate_packet_t cfg_rate_packet;
- memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet));
+ /* Send a CFG-RATE message to define update rate */
+ memset(&_buf.payload_tx_cfg_rate, 0, sizeof(_buf.payload_tx_cfg_rate));
+ _buf.payload_tx_cfg_rate.measRate = UBX_TX_CFG_RATE_MEASINTERVAL;
+ _buf.payload_tx_cfg_rate.navRate = UBX_TX_CFG_RATE_NAVRATE;
+ _buf.payload_tx_cfg_rate.timeRef = UBX_TX_CFG_RATE_TIMEREF;
- _message_class_needed = UBX_CLASS_CFG;
- _message_id_needed = UBX_MESSAGE_CFG_RATE;
+ send_message(UBX_MSG_CFG_RATE, _buf.raw, sizeof(_buf.payload_tx_cfg_rate));
- cfg_rate_packet.clsID = UBX_CLASS_CFG;
- cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE;
- cfg_rate_packet.length = UBX_CFG_RATE_LENGTH;
- cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASINTERVAL;
- cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE;
- cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF;
-
- send_config_packet(_fd, (uint8_t *)&cfg_rate_packet, sizeof(cfg_rate_packet));
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("CFG FAIL: RATE");
+ if (wait_for_ack(UBX_MSG_CFG_RATE, UBX_CONFIG_TIMEOUT, true) < 0) {
return 1;
}
/* send a NAV5 message to set the options for the internal filter */
- type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet;
- memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet));
-
- _message_class_needed = UBX_CLASS_CFG;
- _message_id_needed = UBX_MESSAGE_CFG_NAV5;
+ memset(&_buf.payload_tx_cfg_nav5, 0, sizeof(_buf.payload_tx_cfg_nav5));
+ _buf.payload_tx_cfg_nav5.mask = UBX_TX_CFG_NAV5_MASK;
+ _buf.payload_tx_cfg_nav5.dynModel = UBX_TX_CFG_NAV5_DYNMODEL;
+ _buf.payload_tx_cfg_nav5.fixMode = UBX_TX_CFG_NAV5_FIXMODE;
- cfg_nav5_packet.clsID = UBX_CLASS_CFG;
- cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5;
- cfg_nav5_packet.length = UBX_CFG_NAV5_LENGTH;
- cfg_nav5_packet.mask = UBX_CFG_NAV5_PAYLOAD_MASK;
- cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL;
- cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE;
+ send_message(UBX_MSG_CFG_NAV5, _buf.raw, sizeof(_buf.payload_tx_cfg_nav5));
- send_config_packet(_fd, (uint8_t *)&cfg_nav5_packet, sizeof(cfg_nav5_packet));
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("CFG FAIL: NAV5");
+ if (wait_for_ack(UBX_MSG_CFG_NAV5, UBX_CONFIG_TIMEOUT, true) < 0) {
return 1;
}
/* configure message rates */
/* the last argument is divisor for measurement rate (set by CFG RATE), i.e. 1 means 5Hz */
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_POSLLH, 1);
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: NAV POSLLH");
- return 1;
+ /* try to set rate for NAV-PVT */
+ /* (implemented for ubx7+ modules only, use NAV-SOL, NAV-POSLLH, NAV-VELNED and NAV-TIMEUTC for ubx6) */
+ configure_message_rate(UBX_MSG_NAV_PVT, 1);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
+ _use_nav_pvt = false;
+ } else {
+ _use_nav_pvt = true;
}
+ UBX_WARN("%susing NAV-PVT", _use_nav_pvt ? "" : "not ");
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, 1);
+ if (!_use_nav_pvt) {
+ configure_message_rate(UBX_MSG_NAV_TIMEUTC, 5);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
+ return 1;
+ }
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: NAV TIMEUTC");
- return 1;
- }
+ configure_message_rate(UBX_MSG_NAV_POSLLH, 1);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
+ return 1;
+ }
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL, 1);
+ configure_message_rate(UBX_MSG_NAV_SOL, 1);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
+ return 1;
+ }
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: NAV SOL");
- return 1;
+ configure_message_rate(UBX_MSG_NAV_VELNED, 1);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
+ return 1;
+ }
}
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED, 1);
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: NAV VELNED");
+ configure_message_rate(UBX_MSG_NAV_SVINFO, (_satellite_info != nullptr) ? 5 : 0);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
return 1;
}
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5);
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: NAV SVINFO");
+ configure_message_rate(UBX_MSG_MON_HW, 1);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
return 1;
}
- configure_message_rate(UBX_CLASS_MON, UBX_MESSAGE_MON_HW, 1);
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: MON HW");
- return 1;
- }
+ /* request module version information by sending an empty MON-VER message */
+ send_message(UBX_MSG_MON_VER, nullptr, 0);
_configured = true;
return 0;
}
-int
-UBX::wait_for_ack(unsigned timeout)
+int // -1 = NAK, error or timeout, 0 = ACK
+UBX::wait_for_ack(const uint16_t msg, const unsigned timeout, const bool report)
{
- _waiting_for_ack = true;
- uint64_t time_started = hrt_absolute_time();
+ int ret = -1;
- while (hrt_absolute_time() < time_started + timeout * 1000) {
- if (receive(timeout) > 0) {
- if (!_waiting_for_ack) {
- return 1;
- }
+ _ack_state = UBX_ACK_WAITING;
+ _ack_waiting_msg = msg; // memorize sent msg class&ID for ACK check
+
+ hrt_abstime time_started = hrt_absolute_time();
+ while ((_ack_state == UBX_ACK_WAITING) && (hrt_absolute_time() < time_started + timeout * 1000)) {
+ receive(timeout);
+ }
+
+ if (_ack_state == UBX_ACK_GOT_ACK) {
+ ret = 0; // ACK received ok
+ } else if (report) {
+ if (_ack_state == UBX_ACK_GOT_NAK) {
+ UBX_WARN("ubx msg 0x%04x NAK", SWAP16((unsigned)msg));
} else {
- return -1; // timeout or error receiving, or NAK
+ UBX_WARN("ubx msg 0x%04x ACK timeout", SWAP16((unsigned)msg));
}
}
- return -1; // timeout
+ _ack_state = UBX_ACK_IDLE;
+ return ret;
}
-int
-UBX::receive(unsigned timeout)
+int // -1 = error, 0 = no message handled, 1 = message handled, 2 = sat info message handled
+UBX::receive(const unsigned timeout)
{
/* poll descriptor */
pollfd fds[1];
@@ -275,17 +284,17 @@ UBX::receive(unsigned timeout)
ssize_t count = 0;
- bool handled = false;
+ int handled = 0;
while (true) {
- bool ready_to_return = _configured ? (_got_posllh && _got_velned && _got_timeutc) : handled;
+ bool ready_to_return = _configured ? (_got_posllh && _got_velned) : handled;
/* poll for new data, wait for only UBX_PACKET_TIMEOUT (2ms) if something already received */
int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), ready_to_return ? UBX_PACKET_TIMEOUT : timeout);
if (ret < 0) {
/* something went wrong when polling */
- warnx("poll error");
+ UBX_WARN("ubx poll() err");
return -1;
} else if (ret == 0) {
@@ -293,8 +302,7 @@ UBX::receive(unsigned timeout)
if (ready_to_return) {
_got_posllh = false;
_got_velned = false;
- _got_timeutc = false;
- return 1;
+ return handled;
} else {
return -1;
@@ -314,440 +322,675 @@ UBX::receive(unsigned timeout)
/* pass received bytes to the packet decoder */
for (int i = 0; i < count; i++) {
- if (parse_char(buf[i]) > 0) {
- if (handle_message() > 0)
- handled = true;
- }
+ handled |= parse_char(buf[i]);
}
}
}
/* abort after timeout if no useful packets received */
if (time_started + timeout * 1000 < hrt_absolute_time()) {
- warnx("timeout - no useful messages");
return -1;
}
}
}
-int
-UBX::parse_char(uint8_t b)
+int // 0 = decoding, 1 = message handled, 2 = sat info message handled
+UBX::parse_char(const uint8_t b)
{
+ int ret = 0;
+
switch (_decode_state) {
- /* First, look for sync1 */
- case UBX_DECODE_UNINIT:
- if (b == UBX_SYNC1) {
- _decode_state = UBX_DECODE_GOT_SYNC1;
- }
+ /* Expecting Sync1 */
+ case UBX_DECODE_SYNC1:
+ if (b == UBX_SYNC1) { // Sync1 found --> expecting Sync2
+ UBX_TRACE_PARSER("\nA");
+ _decode_state = UBX_DECODE_SYNC2;
+ }
break;
- /* Second, look for sync2 */
- case UBX_DECODE_GOT_SYNC1:
- if (b == UBX_SYNC2) {
- _decode_state = UBX_DECODE_GOT_SYNC2;
+ /* Expecting Sync2 */
+ case UBX_DECODE_SYNC2:
+ if (b == UBX_SYNC2) { // Sync2 found --> expecting Class
+ UBX_TRACE_PARSER("B");
+ _decode_state = UBX_DECODE_CLASS;
- } else {
- /* Second start symbol was wrong, reset state machine */
+ } else { // Sync1 not followed by Sync2: reset parser
decode_init();
- /* don't return error, it can be just false sync1 */
}
+ break;
+ /* Expecting Class */
+ case UBX_DECODE_CLASS:
+ UBX_TRACE_PARSER("C");
+ add_byte_to_checksum(b); // checksum is calculated for everything except Sync and Checksum bytes
+ _rx_msg = b;
+ _decode_state = UBX_DECODE_ID;
break;
- /* Now look for class */
- case UBX_DECODE_GOT_SYNC2:
- /* everything except sync1 and sync2 needs to be added to the checksum */
+ /* Expecting ID */
+ case UBX_DECODE_ID:
+ UBX_TRACE_PARSER("D");
add_byte_to_checksum(b);
- _message_class = b;
- _decode_state = UBX_DECODE_GOT_CLASS;
+ _rx_msg |= b << 8;
+ _decode_state = UBX_DECODE_LENGTH1;
break;
- case UBX_DECODE_GOT_CLASS:
+ /* Expecting first length byte */
+ case UBX_DECODE_LENGTH1:
+ UBX_TRACE_PARSER("E");
add_byte_to_checksum(b);
- _message_id = b;
- _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ _rx_payload_length = b;
+ _decode_state = UBX_DECODE_LENGTH2;
break;
- case UBX_DECODE_GOT_MESSAGEID:
+ /* Expecting second length byte */
+ case UBX_DECODE_LENGTH2:
+ UBX_TRACE_PARSER("F");
add_byte_to_checksum(b);
- _payload_size = b; //this is the first length byte
- _decode_state = UBX_DECODE_GOT_LENGTH1;
+ _rx_payload_length |= b << 8; // calculate payload size
+ if (payload_rx_init() != 0) { // start payload reception
+ // payload will not be handled, discard message
+ decode_init();
+ } else {
+ _decode_state = (_rx_payload_length > 0) ? UBX_DECODE_PAYLOAD : UBX_DECODE_CHKSUM1;
+ }
break;
- case UBX_DECODE_GOT_LENGTH1:
+ /* Expecting payload */
+ case UBX_DECODE_PAYLOAD:
+ UBX_TRACE_PARSER(".");
add_byte_to_checksum(b);
- _payload_size += b << 8; // here comes the second byte of length
- _decode_state = UBX_DECODE_GOT_LENGTH2;
+ switch (_rx_msg) {
+ case UBX_MSG_NAV_SVINFO:
+ ret = payload_rx_add_nav_svinfo(b); // add a NAV-SVINFO payload byte
+ break;
+ case UBX_MSG_MON_VER:
+ ret = payload_rx_add_mon_ver(b); // add a MON-VER payload byte
+ break;
+ default:
+ ret = payload_rx_add(b); // add a payload byte
+ break;
+ }
+ if (ret < 0) {
+ // payload not handled, discard message
+ decode_init();
+ } else if (ret > 0) {
+ // payload complete, expecting checksum
+ _decode_state = UBX_DECODE_CHKSUM1;
+ } else {
+ // expecting more payload, stay in state UBX_DECODE_PAYLOAD
+ }
+ ret = 0;
break;
- case UBX_DECODE_GOT_LENGTH2:
+ /* Expecting first checksum byte */
+ case UBX_DECODE_CHKSUM1:
+ if (_rx_ck_a != b) {
+ UBX_WARN("ubx checksum err");
+ decode_init();
+ } else {
+ _decode_state = UBX_DECODE_CHKSUM2;
+ }
+ break;
- /* Add to checksum if not yet at checksum byte */
- if (_rx_count < _payload_size)
- add_byte_to_checksum(b);
+ /* Expecting second checksum byte */
+ case UBX_DECODE_CHKSUM2:
+ if (_rx_ck_b != b) {
+ UBX_WARN("ubx checksum err");
+ } else {
+ ret = payload_rx_done(); // finish payload processing
+ }
+ decode_init();
+ break;
- _rx_buffer[_rx_count] = b;
+ default:
+ break;
+ }
- /* once the payload has arrived, we can process the information */
- if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes
- /* compare checksum */
- if (_rx_ck_a == _rx_buffer[_rx_count - 1] && _rx_ck_b == _rx_buffer[_rx_count]) {
- decode_init();
- return 1; // message received successfully
+ return ret;
+}
- } else {
- warnx("checksum wrong");
- decode_init();
- return -1;
- }
+/**
+ * Start payload rx
+ */
+int // -1 = abort, 0 = continue
+UBX::payload_rx_init()
+{
+ int ret = 0;
- } else if (_rx_count < RECV_BUFFER_SIZE) {
- _rx_count++;
+ _rx_state = UBX_RXMSG_HANDLE; // handle by default
+
+ switch (_rx_msg) {
+ case UBX_MSG_NAV_PVT:
+ if ( (_rx_payload_length != UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7) /* u-blox 7 msg format */
+ && (_rx_payload_length != UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8)) /* u-blox 8+ msg format */
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else if (!_use_nav_pvt)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if not using NAV-PVT
+ break;
- } else {
- warnx("buffer full");
- decode_init();
- return -1;
- }
+ case UBX_MSG_NAV_POSLLH:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_nav_posllh_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else if (_use_nav_pvt)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead
+ break;
+ case UBX_MSG_NAV_SOL:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_nav_sol_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else if (_use_nav_pvt)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead
+ break;
+
+ case UBX_MSG_NAV_TIMEUTC:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_nav_timeutc_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else if (_use_nav_pvt)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead
+ break;
+
+ case UBX_MSG_NAV_SVINFO:
+ if (_satellite_info == nullptr)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if sat info not requested
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else
+ memset(_satellite_info, 0, sizeof(*_satellite_info)); // initialize sat info
+ break;
+
+ case UBX_MSG_NAV_VELNED:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_nav_velned_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else if (_use_nav_pvt)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead
+ break;
+
+ case UBX_MSG_MON_VER:
+ break; // unconditionally handle this message
+
+ case UBX_MSG_MON_HW:
+ if ( (_rx_payload_length != sizeof(ubx_payload_rx_mon_hw_ubx6_t)) /* u-blox 6 msg format */
+ && (_rx_payload_length != sizeof(ubx_payload_rx_mon_hw_ubx7_t))) /* u-blox 7+ msg format */
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ break;
+
+ case UBX_MSG_ACK_ACK:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_ack_ack_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if _configured
+ break;
+
+ case UBX_MSG_ACK_NAK:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_ack_nak_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if _configured
break;
default:
+ _rx_state = UBX_RXMSG_DISABLE; // disable all other messages
break;
}
- return 0; // message decoding in progress
+ switch (_rx_state) {
+ case UBX_RXMSG_HANDLE: // handle message
+ case UBX_RXMSG_IGNORE: // ignore message but don't report error
+ ret = 0;
+ break;
+
+ case UBX_RXMSG_DISABLE: // disable unexpected messages
+ UBX_WARN("ubx msg 0x%04x len %u unexpected", SWAP16((unsigned)_rx_msg), (unsigned)_rx_payload_length);
+
+ {
+ hrt_abstime t = hrt_absolute_time();
+
+ if (t > _disable_cmd_last + DISABLE_MSG_INTERVAL) {
+ /* don't attempt for every message to disable, some might not be disabled */
+ _disable_cmd_last = t;
+ UBX_WARN("ubx disabling msg 0x%04x", SWAP16((unsigned)_rx_msg));
+ configure_message_rate(_rx_msg, 0);
+ }
+ }
+
+ ret = -1; // return error, abort handling this message
+ break;
+
+ case UBX_RXMSG_ERROR_LENGTH: // error: invalid length
+ UBX_WARN("ubx msg 0x%04x invalid len %u", SWAP16((unsigned)_rx_msg), (unsigned)_rx_payload_length);
+ ret = -1; // return error, abort handling this message
+ break;
+
+ default: // invalid message state
+ UBX_WARN("ubx internal err1");
+ ret = -1; // return error, abort handling this message
+ break;
+ }
+
+ return ret;
}
+/**
+ * Add payload rx byte
+ */
+int // -1 = error, 0 = ok, 1 = payload completed
+UBX::payload_rx_add(const uint8_t b)
+{
+ int ret = 0;
+ _buf.raw[_rx_payload_index] = b;
-int
-UBX::handle_message()
+ if (++_rx_payload_index >= _rx_payload_length) {
+ ret = 1; // payload received completely
+ }
+
+ return ret;
+}
+
+/**
+ * Add NAV-SVINFO payload rx byte
+ */
+int // -1 = error, 0 = ok, 1 = payload completed
+UBX::payload_rx_add_nav_svinfo(const uint8_t b)
{
int ret = 0;
- if (_configured) {
- /* handle only info messages when configured */
- switch (_message_class) {
- case UBX_CLASS_NAV:
- switch (_message_id) {
- case UBX_MESSAGE_NAV_POSLLH: {
- // printf("GOT NAV_POSLLH\n");
- gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer;
-
- _gps_position->lat = packet->lat;
- _gps_position->lon = packet->lon;
- _gps_position->alt = packet->height_msl;
- _gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m
- _gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m
- _gps_position->timestamp_position = hrt_absolute_time();
-
- _rate_count_lat_lon++;
-
- _got_posllh = true;
- ret = 1;
- break;
- }
+ if (_rx_payload_index < sizeof(ubx_payload_rx_nav_svinfo_part1_t)) {
+ // Fill Part 1 buffer
+ _buf.raw[_rx_payload_index] = b;
+ } else {
+ if (_rx_payload_index == sizeof(ubx_payload_rx_nav_svinfo_part1_t)) {
+ // Part 1 complete: decode Part 1 buffer
+ _satellite_info->count = MIN(_buf.payload_rx_nav_svinfo_part1.numCh, SAT_INFO_MAX_SATELLITES);
+ UBX_TRACE_SVINFO("SVINFO len %u numCh %u\n", (unsigned)_rx_payload_length, (unsigned)_buf.payload_rx_nav_svinfo_part1.numCh);
+ }
+ if (_rx_payload_index < sizeof(ubx_payload_rx_nav_svinfo_part1_t) + _satellite_info->count * sizeof(ubx_payload_rx_nav_svinfo_part2_t)) {
+ // Still room in _satellite_info: fill Part 2 buffer
+ unsigned buf_index = (_rx_payload_index - sizeof(ubx_payload_rx_nav_svinfo_part1_t)) % sizeof(ubx_payload_rx_nav_svinfo_part2_t);
+ _buf.raw[buf_index] = b;
+ if (buf_index == sizeof(ubx_payload_rx_nav_svinfo_part2_t) - 1) {
+ // Part 2 complete: decode Part 2 buffer
+ unsigned sat_index = (_rx_payload_index - sizeof(ubx_payload_rx_nav_svinfo_part1_t)) / sizeof(ubx_payload_rx_nav_svinfo_part2_t);
+ _satellite_info->used[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.flags & 0x01);
+ _satellite_info->snr[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.cno);
+ _satellite_info->elevation[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.elev);
+ _satellite_info->azimuth[sat_index] = (uint8_t)((float)_buf.payload_rx_nav_svinfo_part2.azim * 255.0f / 360.0f);
+ _satellite_info->svid[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.svid);
+ UBX_TRACE_SVINFO("SVINFO #%02u used %u snr %3u elevation %3u azimuth %3u svid %3u\n",
+ (unsigned)sat_index + 1,
+ (unsigned)_satellite_info->used[sat_index],
+ (unsigned)_satellite_info->snr[sat_index],
+ (unsigned)_satellite_info->elevation[sat_index],
+ (unsigned)_satellite_info->azimuth[sat_index],
+ (unsigned)_satellite_info->svid[sat_index]
+ );
+ }
+ }
+ }
+
+ if (++_rx_payload_index >= _rx_payload_length) {
+ ret = 1; // payload received completely
+ }
- case UBX_MESSAGE_NAV_SOL: {
- // printf("GOT NAV_SOL\n");
- gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer;
+ return ret;
+}
- _gps_position->fix_type = packet->gpsFix;
- _gps_position->s_variance_m_s = (float)packet->sAcc * 1e-2f; // from cm/s to m/s
- _gps_position->p_variance_m = (float)packet->pAcc * 1e-2f; // from cm to m
- _gps_position->timestamp_variance = hrt_absolute_time();
+/**
+ * Add MON-VER payload rx byte
+ */
+int // -1 = error, 0 = ok, 1 = payload completed
+UBX::payload_rx_add_mon_ver(const uint8_t b)
+{
+ int ret = 0;
- ret = 1;
- break;
- }
+ if (_rx_payload_index < sizeof(ubx_payload_rx_mon_ver_part1_t)) {
+ // Fill Part 1 buffer
+ _buf.raw[_rx_payload_index] = b;
+ } else {
+ if (_rx_payload_index == sizeof(ubx_payload_rx_mon_ver_part1_t)) {
+ // Part 1 complete: decode Part 1 buffer and calculate hash for SW&HW version strings
+ _ubx_version = fnv1_32_str(_buf.payload_rx_mon_ver_part1.swVersion, FNV1_32_INIT);
+ _ubx_version = fnv1_32_str(_buf.payload_rx_mon_ver_part1.hwVersion, _ubx_version);
+ UBX_WARN("VER hash 0x%08x", _ubx_version);
+ UBX_WARN("VER hw \"%10s\"", _buf.payload_rx_mon_ver_part1.hwVersion);
+ UBX_WARN("VER sw \"%30s\"", _buf.payload_rx_mon_ver_part1.swVersion);
+ }
+ // fill Part 2 buffer
+ unsigned buf_index = (_rx_payload_index - sizeof(ubx_payload_rx_mon_ver_part1_t)) % sizeof(ubx_payload_rx_mon_ver_part2_t);
+ _buf.raw[buf_index] = b;
+ if (buf_index == sizeof(ubx_payload_rx_mon_ver_part2_t) - 1) {
+ // Part 2 complete: decode Part 2 buffer
+ UBX_WARN("VER ext \" %30s\"", _buf.payload_rx_mon_ver_part2.extension);
+ }
+ }
- case UBX_MESSAGE_NAV_TIMEUTC: {
- // printf("GOT NAV_TIMEUTC\n");
- gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer;
+ if (++_rx_payload_index >= _rx_payload_length) {
+ ret = 1; // payload received completely
+ }
- /* convert to unix timestamp */
- struct tm timeinfo;
- timeinfo.tm_year = packet->year - 1900;
- timeinfo.tm_mon = packet->month - 1;
- timeinfo.tm_mday = packet->day;
- timeinfo.tm_hour = packet->hour;
- timeinfo.tm_min = packet->min;
- timeinfo.tm_sec = packet->sec;
- time_t epoch = mktime(&timeinfo);
+ return ret;
+}
+
+/**
+ * Finish payload rx
+ */
+int // 0 = no message handled, 1 = message handled, 2 = sat info message handled
+UBX::payload_rx_done(void)
+{
+ int ret = 0;
+
+ // return if no message handled
+ if (_rx_state != UBX_RXMSG_HANDLE) {
+ return ret;
+ }
+
+ // handle message
+ switch (_rx_msg) {
+
+ case UBX_MSG_NAV_PVT:
+ UBX_TRACE_RXMSG("Rx NAV-PVT\n");
+
+ _gps_position->fix_type = _buf.payload_rx_nav_pvt.fixType;
+ _gps_position->satellites_used = _buf.payload_rx_nav_pvt.numSV;
+
+ _gps_position->lat = _buf.payload_rx_nav_pvt.lat;
+ _gps_position->lon = _buf.payload_rx_nav_pvt.lon;
+ _gps_position->alt = _buf.payload_rx_nav_pvt.hMSL;
+
+ _gps_position->eph = (float)_buf.payload_rx_nav_pvt.hAcc * 1e-3f;
+ _gps_position->epv = (float)_buf.payload_rx_nav_pvt.vAcc * 1e-3f;
+ _gps_position->s_variance_m_s = (float)_buf.payload_rx_nav_pvt.sAcc * 1e-3f;
+
+ _gps_position->vel_m_s = (float)_buf.payload_rx_nav_pvt.gSpeed * 1e-3f;
+
+ _gps_position->vel_n_m_s = (float)_buf.payload_rx_nav_pvt.velN * 1e-3f;
+ _gps_position->vel_e_m_s = (float)_buf.payload_rx_nav_pvt.velE * 1e-3f;
+ _gps_position->vel_d_m_s = (float)_buf.payload_rx_nav_pvt.velD * 1e-3f;
+ _gps_position->vel_ned_valid = true;
+
+ _gps_position->cog_rad = (float)_buf.payload_rx_nav_pvt.headMot * M_DEG_TO_RAD_F * 1e-5f;
+ _gps_position->c_variance_rad = (float)_buf.payload_rx_nav_pvt.headAcc * M_DEG_TO_RAD_F * 1e-5f;
+
+ {
+ /* convert to unix timestamp */
+ struct tm timeinfo;
+ timeinfo.tm_year = _buf.payload_rx_nav_pvt.year - 1900;
+ timeinfo.tm_mon = _buf.payload_rx_nav_pvt.month - 1;
+ timeinfo.tm_mday = _buf.payload_rx_nav_pvt.day;
+ timeinfo.tm_hour = _buf.payload_rx_nav_pvt.hour;
+ timeinfo.tm_min = _buf.payload_rx_nav_pvt.min;
+ timeinfo.tm_sec = _buf.payload_rx_nav_pvt.sec;
+ time_t epoch = mktime(&timeinfo);
#ifndef CONFIG_RTC
- //Since we lack a hardware RTC, set the system time clock based on GPS UTC
- //TODO generalize this by moving into gps.cpp?
- timespec ts;
- ts.tv_sec = epoch;
- ts.tv_nsec = packet->time_nanoseconds;
- clock_settime(CLOCK_REALTIME, &ts);
+ //Since we lack a hardware RTC, set the system time clock based on GPS UTC
+ //TODO generalize this by moving into gps.cpp?
+ timespec ts;
+ ts.tv_sec = epoch;
+ ts.tv_nsec = _buf.payload_rx_nav_pvt.nano;
+ clock_settime(CLOCK_REALTIME, &ts);
#endif
- _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
- _gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f);
- _gps_position->timestamp_time = hrt_absolute_time();
+ _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
+ _gps_position->time_gps_usec += (uint64_t)(_buf.payload_rx_nav_pvt.nano * 1e-3f);
+ }
- _got_timeutc = true;
- ret = 1;
- break;
- }
+ _gps_position->timestamp_time = hrt_absolute_time();
+ _gps_position->timestamp_velocity = hrt_absolute_time();
+ _gps_position->timestamp_variance = hrt_absolute_time();
+ _gps_position->timestamp_position = hrt_absolute_time();
- case UBX_MESSAGE_NAV_SVINFO: {
- //printf("GOT NAV_SVINFO\n");
- const int length_part1 = 8;
- gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer;
- const int length_part2 = 12;
- gps_bin_nav_svinfo_part2_packet_t *packet_part2;
-
- uint8_t satellites_used = 0;
- int i;
-
- //printf("Number of Channels: %d\n", packet_part1->numCh);
- for (i = 0; i < packet_part1->numCh; i++) {
- /* set pointer to sattelite_i information */
- packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) & (_rx_buffer[length_part1 + i * length_part2]);
-
- /* write satellite information to global storage */
- uint8_t sv_used = packet_part2->flags & 0x01;
-
- if (sv_used) {
- /* count SVs used for NAV */
- satellites_used++;
- }
-
- /* record info for all channels, whether or not the SV is used for NAV */
- _gps_position->satellite_used[i] = sv_used;
- _gps_position->satellite_snr[i] = packet_part2->cno;
- _gps_position->satellite_elevation[i] = (uint8_t)(packet_part2->elev);
- _gps_position->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f);
- _gps_position->satellite_prn[i] = packet_part2->svid;
- //printf("SAT %d: %d %d %d %d\n", i, (int)sv_used, (int)packet_part2->cno, (int)(uint8_t)(packet_part2->elev), (int)packet_part2->svid);
- }
-
- for (i = packet_part1->numCh; i < 20; i++) {
- /* unused channels have to be set to zero for e.g. MAVLink */
- _gps_position->satellite_prn[i] = 0;
- _gps_position->satellite_used[i] = 0;
- _gps_position->satellite_snr[i] = 0;
- _gps_position->satellite_elevation[i] = 0;
- _gps_position->satellite_azimuth[i] = 0;
- }
-
- _gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones
-
- if (packet_part1->numCh > 0) {
- _gps_position->satellite_info_available = true;
-
- } else {
- _gps_position->satellite_info_available = false;
- }
-
- _gps_position->timestamp_satellites = hrt_absolute_time();
-
- ret = 1;
- break;
- }
+ _rate_count_vel++;
+ _rate_count_lat_lon++;
- case UBX_MESSAGE_NAV_VELNED: {
- // printf("GOT NAV_VELNED\n");
- gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer;
+ _got_posllh = true;
+ _got_velned = true;
- _gps_position->vel_m_s = (float)packet->speed * 1e-2f;
- _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; /* NED NORTH velocity */
- _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; /* NED EAST velocity */
- _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; /* NED DOWN velocity */
- _gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f;
- _gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f;
- _gps_position->vel_ned_valid = true;
- _gps_position->timestamp_velocity = hrt_absolute_time();
+ ret = 1;
+ break;
- _rate_count_vel++;
+ case UBX_MSG_NAV_POSLLH:
+ UBX_TRACE_RXMSG("Rx NAV-POSLLH\n");
- _got_velned = true;
- ret = 1;
- break;
- }
+ _gps_position->lat = _buf.payload_rx_nav_posllh.lat;
+ _gps_position->lon = _buf.payload_rx_nav_posllh.lon;
+ _gps_position->alt = _buf.payload_rx_nav_posllh.hMSL;
+ _gps_position->eph = (float)_buf.payload_rx_nav_posllh.hAcc * 1e-3f; // from mm to m
+ _gps_position->epv = (float)_buf.payload_rx_nav_posllh.vAcc * 1e-3f; // from mm to m
- default:
- break;
- }
+ _gps_position->timestamp_position = hrt_absolute_time();
- break;
+ _rate_count_lat_lon++;
+ _got_posllh = true;
- case UBX_CLASS_ACK: {
- /* ignore ACK when already configured */
- ret = 1;
- break;
- }
+ ret = 1;
+ break;
- case UBX_CLASS_MON: {
- switch (_message_id) {
- case UBX_MESSAGE_MON_HW: {
+ case UBX_MSG_NAV_SOL:
+ UBX_TRACE_RXMSG("Rx NAV-SOL\n");
- struct gps_bin_mon_hw_packet *p = (struct gps_bin_mon_hw_packet*) _rx_buffer;
+ _gps_position->fix_type = _buf.payload_rx_nav_sol.gpsFix;
+ _gps_position->s_variance_m_s = (float)_buf.payload_rx_nav_sol.sAcc * 1e-2f; // from cm to m
+ _gps_position->satellites_used = _buf.payload_rx_nav_sol.numSV;
- _gps_position->noise_per_ms = p->noisePerMS;
- _gps_position->jamming_indicator = p->jamInd;
+ _gps_position->timestamp_variance = hrt_absolute_time();
- ret = 1;
- break;
- }
+ ret = 1;
+ break;
- default:
- break;
- }
+ case UBX_MSG_NAV_TIMEUTC:
+ UBX_TRACE_RXMSG("Rx NAV-TIMEUTC\n");
+
+ {
+ /* convert to unix timestamp */
+ struct tm timeinfo;
+ timeinfo.tm_year = _buf.payload_rx_nav_timeutc.year - 1900;
+ timeinfo.tm_mon = _buf.payload_rx_nav_timeutc.month - 1;
+ timeinfo.tm_mday = _buf.payload_rx_nav_timeutc.day;
+ timeinfo.tm_hour = _buf.payload_rx_nav_timeutc.hour;
+ timeinfo.tm_min = _buf.payload_rx_nav_timeutc.min;
+ timeinfo.tm_sec = _buf.payload_rx_nav_timeutc.sec;
+ time_t epoch = mktime(&timeinfo);
+
+#ifndef CONFIG_RTC
+ //Since we lack a hardware RTC, set the system time clock based on GPS UTC
+ //TODO generalize this by moving into gps.cpp?
+ timespec ts;
+ ts.tv_sec = epoch;
+ ts.tv_nsec = _buf.payload_rx_nav_timeutc.nano;
+ clock_settime(CLOCK_REALTIME, &ts);
+#endif
+
+ _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
+ _gps_position->time_gps_usec += (uint64_t)(_buf.payload_rx_nav_timeutc.nano * 1e-3f);
}
- default:
+ _gps_position->timestamp_time = hrt_absolute_time();
+
+ ret = 1;
+ break;
+
+ case UBX_MSG_NAV_SVINFO:
+ UBX_TRACE_RXMSG("Rx NAV-SVINFO\n");
+
+ // _satellite_info already populated by payload_rx_add_svinfo(), just add a timestamp
+ _satellite_info->timestamp = hrt_absolute_time();
+
+ ret = 2;
+ break;
+
+ case UBX_MSG_NAV_VELNED:
+ UBX_TRACE_RXMSG("Rx NAV-VELNED\n");
+
+ _gps_position->vel_m_s = (float)_buf.payload_rx_nav_velned.speed * 1e-2f;
+ _gps_position->vel_n_m_s = (float)_buf.payload_rx_nav_velned.velN * 1e-2f; /* NED NORTH velocity */
+ _gps_position->vel_e_m_s = (float)_buf.payload_rx_nav_velned.velE * 1e-2f; /* NED EAST velocity */
+ _gps_position->vel_d_m_s = (float)_buf.payload_rx_nav_velned.velD * 1e-2f; /* NED DOWN velocity */
+ _gps_position->cog_rad = (float)_buf.payload_rx_nav_velned.heading * M_DEG_TO_RAD_F * 1e-5f;
+ _gps_position->c_variance_rad = (float)_buf.payload_rx_nav_velned.cAcc * M_DEG_TO_RAD_F * 1e-5f;
+ _gps_position->vel_ned_valid = true;
+
+ _gps_position->timestamp_velocity = hrt_absolute_time();
+
+ _rate_count_vel++;
+ _got_velned = true;
+
+ ret = 1;
+ break;
+
+ case UBX_MSG_MON_VER:
+ UBX_TRACE_RXMSG("Rx MON-VER\n");
+
+ ret = 1;
+ break;
+
+ case UBX_MSG_MON_HW:
+ UBX_TRACE_RXMSG("Rx MON-HW\n");
+
+ switch (_rx_payload_length) {
+
+ case sizeof(ubx_payload_rx_mon_hw_ubx6_t): /* u-blox 6 msg format */
+ _gps_position->noise_per_ms = _buf.payload_rx_mon_hw_ubx6.noisePerMS;
+ _gps_position->jamming_indicator = _buf.payload_rx_mon_hw_ubx6.jamInd;
+
+ ret = 1;
break;
- }
- if (ret == 0) {
- /* message not handled */
- warnx("ubx: unknown message received: 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id);
+ case sizeof(ubx_payload_rx_mon_hw_ubx7_t): /* u-blox 7+ msg format */
+ _gps_position->noise_per_ms = _buf.payload_rx_mon_hw_ubx7.noisePerMS;
+ _gps_position->jamming_indicator = _buf.payload_rx_mon_hw_ubx7.jamInd;
- hrt_abstime t = hrt_absolute_time();
+ ret = 1;
+ break;
- if (t > _disable_cmd_last + DISABLE_MSG_INTERVAL) {
- /* don't attempt for every message to disable, some might not be disabled */
- _disable_cmd_last = t;
- warnx("ubx: disabling message 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id);
- configure_message_rate(_message_class, _message_id, 0);
- }
+ default: // unexpected payload size:
+ ret = 0; // don't handle message
+ break;
}
+ break;
- } else {
- /* handle only ACK while configuring */
- if (_message_class == UBX_CLASS_ACK) {
- switch (_message_id) {
- case UBX_MESSAGE_ACK_ACK: {
- // printf("GOT ACK_ACK\n");
- gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer;
-
- if (_waiting_for_ack) {
- if (packet->clsID == _message_class_needed && packet->msgID == _message_id_needed) {
- _waiting_for_ack = false;
- ret = 1;
- }
- }
-
- break;
- }
+ case UBX_MSG_ACK_ACK:
+ UBX_TRACE_RXMSG("Rx ACK-ACK\n");
- case UBX_MESSAGE_ACK_NAK: {
- // printf("GOT ACK_NAK\n");
- warnx("ubx: not acknowledged");
- /* configuration obviously not successful */
- _waiting_for_ack = false;
- ret = -1;
- break;
- }
+ if ((_ack_state == UBX_ACK_WAITING) && (_buf.payload_rx_ack_ack.msg == _ack_waiting_msg)) {
+ _ack_state = UBX_ACK_GOT_ACK;
+ }
- default:
- break;
- }
+ ret = 1;
+ break;
+
+ case UBX_MSG_ACK_NAK:
+ UBX_TRACE_RXMSG("Rx ACK-NAK\n");
+
+ if ((_ack_state == UBX_ACK_WAITING) && (_buf.payload_rx_ack_ack.msg == _ack_waiting_msg)) {
+ _ack_state = UBX_ACK_GOT_NAK;
}
+
+ ret = 1;
+ break;
+
+ default:
+ break;
}
- decode_init();
return ret;
}
void
UBX::decode_init(void)
{
+ _decode_state = UBX_DECODE_SYNC1;
_rx_ck_a = 0;
_rx_ck_b = 0;
- _rx_count = 0;
- _decode_state = UBX_DECODE_UNINIT;
- _payload_size = 0;
- /* don't reset _message_class, _message_id, _rx_buffer leave it for message handler */
+ _rx_payload_length = 0;
+ _rx_payload_index = 0;
}
void
-UBX::add_byte_to_checksum(uint8_t b)
+UBX::add_byte_to_checksum(const uint8_t b)
{
_rx_ck_a = _rx_ck_a + b;
_rx_ck_b = _rx_ck_b + _rx_ck_a;
}
void
-UBX::add_checksum_to_message(uint8_t *message, const unsigned length)
+UBX::calc_checksum(const uint8_t *buffer, const uint16_t length, ubx_checksum_t *checksum)
{
- uint8_t ck_a = 0;
- uint8_t ck_b = 0;
- unsigned i;
-
- for (i = 0; i < length - 2; i++) {
- ck_a = ck_a + message[i];
- ck_b = ck_b + ck_a;
+ for (uint16_t i = 0; i < length; i++) {
+ checksum->ck_a = checksum->ck_a + buffer[i];
+ checksum->ck_b = checksum->ck_b + checksum->ck_a;
}
-
- /* the checksum is written to the last to bytes of a message */
- message[length - 2] = ck_a;
- message[length - 1] = ck_b;
}
void
-UBX::add_checksum(uint8_t *message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b)
+UBX::configure_message_rate(const uint16_t msg, const uint8_t rate)
{
- for (unsigned i = 0; i < length; i++) {
- ck_a = ck_a + message[i];
- ck_b = ck_b + ck_a;
- }
+ ubx_payload_tx_cfg_msg_t cfg_msg; // don't use _buf (allow interleaved operation)
+
+ cfg_msg.msg = msg;
+ cfg_msg.rate = rate;
+
+ send_message(UBX_MSG_CFG_MSG, (uint8_t *)&cfg_msg, sizeof(cfg_msg));
}
void
-UBX::configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
+UBX::send_message(const uint16_t msg, const uint8_t *payload, const uint16_t length)
{
- struct ubx_cfg_msg_rate msg;
- msg.msg_class = msg_class;
- msg.msg_id = msg_id;
- msg.rate = rate;
- send_message(UBX_CLASS_CFG, UBX_MESSAGE_CFG_MSG, &msg, sizeof(msg));
+ ubx_header_t header = {UBX_SYNC1, UBX_SYNC2};
+ ubx_checksum_t checksum = {0, 0};
+
+ // Populate header
+ header.msg = msg;
+ header.length = length;
+
+ // Calculate checksum
+ calc_checksum(((uint8_t*)&header) + 2, sizeof(header) - 2, &checksum); // skip 2 sync bytes
+ if (payload != nullptr)
+ calc_checksum(payload, length, &checksum);
+
+ // Send message
+ write(_fd, (const void *)&header, sizeof(header));
+ if (payload != nullptr)
+ write(_fd, (const void *)payload, length);
+ write(_fd, (const void *)&checksum, sizeof(checksum));
}
-void
-UBX::send_config_packet(const int &fd, uint8_t *packet, const unsigned length)
+uint32_t
+UBX::fnv1_32_str(uint8_t *str, uint32_t hval)
{
- ssize_t ret = 0;
-
- /* calculate the checksum now */
- add_checksum_to_message(packet, length);
-
- const uint8_t sync_bytes[] = {UBX_SYNC1, UBX_SYNC2};
+ uint8_t *s = str;
+
+ /*
+ * FNV-1 hash each octet in the buffer
+ */
+ while (*s) {
+
+ /* multiply by the 32 bit FNV magic prime mod 2^32 */
+#if defined(NO_FNV_GCC_OPTIMIZATION)
+ hval *= FNV1_32_PRIME;
+#else
+ hval += (hval<<1) + (hval<<4) + (hval<<7) + (hval<<8) + (hval<<24);
+#endif
- /* start with the two sync bytes */
- ret += write(fd, sync_bytes, sizeof(sync_bytes));
- ret += write(fd, packet, length);
+ /* xor the bottom with the current octet */
+ hval ^= (uint32_t)*s++;
+ }
- if (ret != (int)length + (int)sizeof(sync_bytes)) // XXX is there a neater way to get rid of the unsigned signed warning?
- warnx("ubx: configuration write fail");
+ /* return our new hash value */
+ return hval;
}
-void
-UBX::send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size)
-{
- struct ubx_header header;
- uint8_t ck_a = 0, ck_b = 0;
- header.sync1 = UBX_SYNC1;
- header.sync2 = UBX_SYNC2;
- header.msg_class = msg_class;
- header.msg_id = msg_id;
- header.length = size;
-
- add_checksum((uint8_t *)&header.msg_class, sizeof(header) - 2, ck_a, ck_b);
- add_checksum((uint8_t *)msg, size, ck_a, ck_b);
-
- /* configure ACK check */
- _message_class_needed = msg_class;
- _message_id_needed = msg_id;
-
- write(_fd, (const char *)&header, sizeof(header));
- write(_fd, (const char *)msg, size);
- write(_fd, (const char *)&ck_a, 1);
- write(_fd, (const char *)&ck_b, 1);
-}
diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h
index 43d688893..219a5762a 100644
--- a/src/drivers/gps/ubx.h
+++ b/src/drivers/gps/ubx.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 2013, 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
@@ -34,13 +34,16 @@
/**
* @file ubx.h
*
- * U-Blox protocol definition. Following u-blox 6/7 Receiver Description
+ * U-Blox protocol definition. Following u-blox 6/7/8 Receiver Description
* including Prototol Specification.
*
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
*
+ * @author Hannes Delago
+ * (rework, add ubx7+ compatibility)
+ *
*/
#ifndef UBX_H_
@@ -51,319 +54,433 @@
#define UBX_SYNC1 0xB5
#define UBX_SYNC2 0x62
-/* ClassIDs (the ones that are used) */
-#define UBX_CLASS_NAV 0x01
-//#define UBX_CLASS_RXM 0x02
-#define UBX_CLASS_ACK 0x05
-#define UBX_CLASS_CFG 0x06
-#define UBX_CLASS_MON 0x0A
-
-/* MessageIDs (the ones that are used) */
-#define UBX_MESSAGE_NAV_POSLLH 0x02
-//#define UBX_MESSAGE_NAV_DOP 0x04
-#define UBX_MESSAGE_NAV_SOL 0x06
-#define UBX_MESSAGE_NAV_VELNED 0x12
-//#define UBX_MESSAGE_RXM_SVSI 0x20
-#define UBX_MESSAGE_NAV_TIMEUTC 0x21
-#define UBX_MESSAGE_NAV_SVINFO 0x30
-#define UBX_MESSAGE_ACK_NAK 0x00
-#define UBX_MESSAGE_ACK_ACK 0x01
-#define UBX_MESSAGE_CFG_PRT 0x00
-#define UBX_MESSAGE_CFG_MSG 0x01
-#define UBX_MESSAGE_CFG_RATE 0x08
-#define UBX_MESSAGE_CFG_NAV5 0x24
-
-#define UBX_MESSAGE_MON_HW 0x09
-
-#define UBX_CFG_PRT_LENGTH 20
-#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */
-#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
-#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< choose 38400 as GPS baudrate */
-#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< UBX in */
-#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */
-
-#define UBX_CFG_RATE_LENGTH 6
-#define UBX_CFG_RATE_PAYLOAD_MEASINTERVAL 200 /**< 200ms for 5Hz */
-#define UBX_CFG_RATE_PAYLOAD_NAVRATE 1 /**< cannot be changed */
-#define UBX_CFG_RATE_PAYLOAD_TIMEREF 0 /**< 0: UTC, 1: GPS time */
-
-
-#define UBX_CFG_NAV5_LENGTH 36
-#define UBX_CFG_NAV5_PAYLOAD_MASK 0x0005 /**< XXX only update dynamic model and fix mode */
-#define UBX_CFG_NAV5_PAYLOAD_DYNMODEL 7 /**< 0: portable, 2: stationary, 3: pedestrian, 4: automotive, 5: sea, 6: airborne <1g, 7: airborne <2g, 8: airborne <4g */
-#define UBX_CFG_NAV5_PAYLOAD_FIXMODE 2 /**< 1: 2D only, 2: 3D only, 3: Auto 2D/3D */
-
-#define UBX_CFG_MSG_LENGTH 8
-#define UBX_CFG_MSG_PAYLOAD_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
-#define UBX_CFG_MSG_PAYLOAD_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
-#define UBX_CFG_MSG_PAYLOAD_RATE1_05HZ 10
-
-#define UBX_MAX_PAYLOAD_LENGTH 500
-
-// ************
-/** the structures of the binary packets */
+/* Message Classes */
+#define UBX_CLASS_NAV 0x01
+#define UBX_CLASS_ACK 0x05
+#define UBX_CLASS_CFG 0x06
+#define UBX_CLASS_MON 0x0A
+
+/* Message IDs */
+#define UBX_ID_NAV_POSLLH 0x02
+#define UBX_ID_NAV_SOL 0x06
+#define UBX_ID_NAV_PVT 0x07
+#define UBX_ID_NAV_VELNED 0x12
+#define UBX_ID_NAV_TIMEUTC 0x21
+#define UBX_ID_NAV_SVINFO 0x30
+#define UBX_ID_ACK_NAK 0x00
+#define UBX_ID_ACK_ACK 0x01
+#define UBX_ID_CFG_PRT 0x00
+#define UBX_ID_CFG_MSG 0x01
+#define UBX_ID_CFG_RATE 0x08
+#define UBX_ID_CFG_NAV5 0x24
+#define UBX_ID_MON_VER 0x04
+#define UBX_ID_MON_HW 0x09
+
+/* Message Classes & IDs */
+#define UBX_MSG_NAV_POSLLH ((UBX_CLASS_NAV) | UBX_ID_NAV_POSLLH << 8)
+#define UBX_MSG_NAV_SOL ((UBX_CLASS_NAV) | UBX_ID_NAV_SOL << 8)
+#define UBX_MSG_NAV_PVT ((UBX_CLASS_NAV) | UBX_ID_NAV_PVT << 8)
+#define UBX_MSG_NAV_VELNED ((UBX_CLASS_NAV) | UBX_ID_NAV_VELNED << 8)
+#define UBX_MSG_NAV_TIMEUTC ((UBX_CLASS_NAV) | UBX_ID_NAV_TIMEUTC << 8)
+#define UBX_MSG_NAV_SVINFO ((UBX_CLASS_NAV) | UBX_ID_NAV_SVINFO << 8)
+#define UBX_MSG_ACK_NAK ((UBX_CLASS_ACK) | UBX_ID_ACK_NAK << 8)
+#define UBX_MSG_ACK_ACK ((UBX_CLASS_ACK) | UBX_ID_ACK_ACK << 8)
+#define UBX_MSG_CFG_PRT ((UBX_CLASS_CFG) | UBX_ID_CFG_PRT << 8)
+#define UBX_MSG_CFG_MSG ((UBX_CLASS_CFG) | UBX_ID_CFG_MSG << 8)
+#define UBX_MSG_CFG_RATE ((UBX_CLASS_CFG) | UBX_ID_CFG_RATE << 8)
+#define UBX_MSG_CFG_NAV5 ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8)
+#define UBX_MSG_MON_HW ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8)
+#define UBX_MSG_MON_VER ((UBX_CLASS_MON) | UBX_ID_MON_VER << 8)
+
+/* RX NAV-PVT message content details */
+/* Bitfield "valid" masks */
+#define UBX_RX_NAV_PVT_VALID_VALIDDATE 0x01 /**< validDate (Valid UTC Date) */
+#define UBX_RX_NAV_PVT_VALID_VALIDTIME 0x02 /**< validTime (Valid UTC Time) */
+#define UBX_RX_NAV_PVT_VALID_FULLYRESOLVED 0x04 /**< fullyResolved (1 = UTC Time of Day has been fully resolved (no seconds uncertainty)) */
+
+/* Bitfield "flags" masks */
+#define UBX_RX_NAV_PVT_FLAGS_GNSSFIXOK 0x01 /**< gnssFixOK (A valid fix (i.e within DOP & accuracy masks)) */
+#define UBX_RX_NAV_PVT_FLAGS_DIFFSOLN 0x02 /**< diffSoln (1 if differential corrections were applied) */
+#define UBX_RX_NAV_PVT_FLAGS_PSMSTATE 0x1C /**< psmState (Power Save Mode state (see Power Management)) */
+#define UBX_RX_NAV_PVT_FLAGS_HEADVEHVALID 0x20 /**< headVehValid (Heading of vehicle is valid) */
+
+/* RX NAV-TIMEUTC message content details */
+/* Bitfield "valid" masks */
+#define UBX_RX_NAV_TIMEUTC_VALID_VALIDTOW 0x01 /**< validTOW (1 = Valid Time of Week) */
+#define UBX_RX_NAV_TIMEUTC_VALID_VALIDKWN 0x02 /**< validWKN (1 = Valid Week Number) */
+#define UBX_RX_NAV_TIMEUTC_VALID_VALIDUTC 0x04 /**< validUTC (1 = Valid UTC Time) */
+#define UBX_RX_NAV_TIMEUTC_VALID_UTCSTANDARD 0xF0 /**< utcStandard (0..15 = UTC standard identifier) */
+
+/* TX CFG-PRT message contents */
+#define UBX_TX_CFG_PRT_PORTID 0x01 /**< UART1 */
+#define UBX_TX_CFG_PRT_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
+#define UBX_TX_CFG_PRT_BAUDRATE 38400 /**< choose 38400 as GPS baudrate */
+#define UBX_TX_CFG_PRT_INPROTOMASK 0x01 /**< UBX in */
+#define UBX_TX_CFG_PRT_OUTPROTOMASK 0x01 /**< UBX out */
+
+/* TX CFG-RATE message contents */
+#define UBX_TX_CFG_RATE_MEASINTERVAL 200 /**< 200ms for 5Hz */
+#define UBX_TX_CFG_RATE_NAVRATE 1 /**< cannot be changed */
+#define UBX_TX_CFG_RATE_TIMEREF 0 /**< 0: UTC, 1: GPS time */
+
+/* TX CFG-NAV5 message contents */
+#define UBX_TX_CFG_NAV5_MASK 0x0005 /**< Only update dynamic model and fix mode */
+#define UBX_TX_CFG_NAV5_DYNMODEL 7 /**< 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g */
+#define UBX_TX_CFG_NAV5_FIXMODE 2 /**< 1 2D only, 2 3D only, 3 Auto 2D/3D */
+
+/* TX CFG-MSG message contents */
+#define UBX_TX_CFG_MSG_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
+#define UBX_TX_CFG_MSG_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
+#define UBX_TX_CFG_MSG_RATE1_05HZ 10
+
+
+/*** u-blox protocol binary message and payload definitions ***/
#pragma pack(push, 1)
-struct ubx_header {
- uint8_t sync1;
- uint8_t sync2;
- uint8_t msg_class;
- uint8_t msg_id;
- uint16_t length;
-};
-
+/* General: Header */
typedef struct {
- uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
- int32_t lon; /**< Longitude * 1e-7, deg */
- int32_t lat; /**< Latitude * 1e-7, deg */
- int32_t height; /**< Height above Ellipsoid, mm */
- int32_t height_msl; /**< Height above mean sea level, mm */
- uint32_t hAcc; /**< Horizontal Accuracy Estimate, mm */
- uint32_t vAcc; /**< Vertical Accuracy Estimate, mm */
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_nav_posllh_packet_t;
+ uint8_t sync1;
+ uint8_t sync2;
+ uint16_t msg;
+ uint16_t length;
+} ubx_header_t;
+/* General: Checksum */
typedef struct {
- uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
- int32_t time_nanoseconds; /**< Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 */
- int16_t week; /**< GPS week (GPS time) */
- uint8_t gpsFix; /**< GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */
- uint8_t flags;
- int32_t ecefX;
- int32_t ecefY;
- int32_t ecefZ;
- uint32_t pAcc;
- int32_t ecefVX;
- int32_t ecefVY;
- int32_t ecefVZ;
- uint32_t sAcc;
- uint16_t pDOP;
- uint8_t reserved1;
- uint8_t numSV;
- uint32_t reserved2;
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_nav_sol_packet_t;
+ uint8_t ck_a;
+ uint8_t ck_b;
+} ubx_checksum_t ;
+/* Rx NAV-POSLLH */
typedef struct {
- uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
- uint32_t time_accuracy; /**< Time Accuracy Estimate, ns */
- int32_t time_nanoseconds; /**< Nanoseconds of second, range -1e9 .. 1e9 (UTC) */
- uint16_t year; /**< Year, range 1999..2099 (UTC) */
- uint8_t month; /**< Month, range 1..12 (UTC) */
- uint8_t day; /**< Day of Month, range 1..31 (UTC) */
- uint8_t hour; /**< Hour of Day, range 0..23 (UTC) */
- uint8_t min; /**< Minute of Hour, range 0..59 (UTC) */
- uint8_t sec; /**< Seconds of Minute, range 0..59 (UTC) */
- uint8_t valid_flag; /**< Validity Flags (see ubx documentation) */
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_nav_timeutc_packet_t;
-
-//typedef struct {
-// uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
-// uint16_t gDOP; /**< Geometric DOP (scaling 0.01) */
-// uint16_t pDOP; /**< Position DOP (scaling 0.01) */
-// uint16_t tDOP; /**< Time DOP (scaling 0.01) */
-// uint16_t vDOP; /**< Vertical DOP (scaling 0.01) */
-// uint16_t hDOP; /**< Horizontal DOP (scaling 0.01) */
-// uint16_t nDOP; /**< Northing DOP (scaling 0.01) */
-// uint16_t eDOP; /**< Easting DOP (scaling 0.01) */
-// uint8_t ck_a;
-// uint8_t ck_b;
-//} gps_bin_nav_dop_packet_t;
-
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ int32_t lon; /**< Longitude [1e-7 deg] */
+ int32_t lat; /**< Latitude [1e-7 deg] */
+ int32_t height; /**< Height above ellipsoid [mm] */
+ int32_t hMSL; /**< Height above mean sea level [mm] */
+ uint32_t hAcc; /**< Horizontal accuracy estimate [mm] */
+ uint32_t vAcc; /**< Vertical accuracy estimate [mm] */
+} ubx_payload_rx_nav_posllh_t;
+
+/* Rx NAV-SOL */
typedef struct {
- uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
- uint8_t numCh; /**< Number of channels */
- uint8_t globalFlags;
- uint16_t reserved2;
-
-} gps_bin_nav_svinfo_part1_packet_t;
-
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ int32_t fTOW; /**< Fractional part of iTOW (range: +/-500000) [ns] */
+ int16_t week; /**< GPS week */
+ uint8_t gpsFix; /**< GPSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */
+ uint8_t flags;
+ int32_t ecefX;
+ int32_t ecefY;
+ int32_t ecefZ;
+ uint32_t pAcc;
+ int32_t ecefVX;
+ int32_t ecefVY;
+ int32_t ecefVZ;
+ uint32_t sAcc;
+ uint16_t pDOP;
+ uint8_t reserved1;
+ uint8_t numSV; /**< Number of SVs used in Nav Solution */
+ uint32_t reserved2;
+} ubx_payload_rx_nav_sol_t;
+
+/* Rx NAV-PVT (ubx8) */
typedef struct {
- uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */
- uint8_t svid; /**< Satellite ID */
- uint8_t flags;
- uint8_t quality;
- uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength), dbHz */
- int8_t elev; /**< Elevation in integer degrees */
- int16_t azim; /**< Azimuth in integer degrees */
- int32_t prRes; /**< Pseudo range residual in centimetres */
-
-} gps_bin_nav_svinfo_part2_packet_t;
-
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ uint16_t year; /**< Year (UTC)*/
+ uint8_t month; /**< Month, range 1..12 (UTC) */
+ uint8_t day; /**< Day of month, range 1..31 (UTC) */
+ uint8_t hour; /**< Hour of day, range 0..23 (UTC) */
+ uint8_t min; /**< Minute of hour, range 0..59 (UTC) */
+ uint8_t sec; /**< Seconds of minute, range 0..60 (UTC) */
+ uint8_t valid; /**< Validity flags (see UBX_RX_NAV_PVT_VALID_...) */
+ uint32_t tAcc; /**< Time accuracy estimate (UTC) [ns] */
+ int32_t nano; /**< Fraction of second (UTC) [-1e9...1e9 ns] */
+ uint8_t fixType; /**< GNSSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GNSS + dead reckoning, 5 = time only fix */
+ uint8_t flags; /**< Fix Status Flags (see UBX_RX_NAV_PVT_FLAGS_...) */
+ uint8_t reserved1;
+ uint8_t numSV; /**< Number of SVs used in Nav Solution */
+ int32_t lon; /**< Longitude [1e-7 deg] */
+ int32_t lat; /**< Latitude [1e-7 deg] */
+ int32_t height; /**< Height above ellipsoid [mm] */
+ int32_t hMSL; /**< Height above mean sea level [mm] */
+ uint32_t hAcc; /**< Horizontal accuracy estimate [mm] */
+ uint32_t vAcc; /**< Vertical accuracy estimate [mm] */
+ int32_t velN; /**< NED north velocity [mm/s]*/
+ int32_t velE; /**< NED east velocity [mm/s]*/
+ int32_t velD; /**< NED down velocity [mm/s]*/
+ int32_t gSpeed; /**< Ground Speed (2-D) [mm/s] */
+ int32_t headMot; /**< Heading of motion (2-D) [1e-5 deg] */
+ uint32_t sAcc; /**< Speed accuracy estimate [mm/s] */
+ uint32_t headAcc; /**< Heading accuracy estimate (motion and vehicle) [1e-5 deg] */
+ uint16_t pDOP; /**< Position DOP [0.01] */
+ uint16_t reserved2;
+ uint32_t reserved3;
+ int32_t headVeh; /**< (ubx8+ only) Heading of vehicle (2-D) [1e-5 deg] */
+ uint32_t reserved4; /**< (ubx8+ only) */
+} ubx_payload_rx_nav_pvt_t;
+#define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7 (sizeof(ubx_payload_rx_nav_pvt_t) - 8)
+#define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8 (sizeof(ubx_payload_rx_nav_pvt_t))
+
+/* Rx NAV-TIMEUTC */
typedef struct {
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_nav_svinfo_part3_packet_t;
-
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ uint32_t tAcc; /**< Time accuracy estimate (UTC) [ns] */
+ int32_t nano; /**< Fraction of second, range -1e9 .. 1e9 (UTC) [ns] */
+ uint16_t year; /**< Year, range 1999..2099 (UTC) */
+ uint8_t month; /**< Month, range 1..12 (UTC) */
+ uint8_t day; /**< Day of month, range 1..31 (UTC) */
+ uint8_t hour; /**< Hour of day, range 0..23 (UTC) */
+ uint8_t min; /**< Minute of hour, range 0..59 (UTC) */
+ uint8_t sec; /**< Seconds of minute, range 0..60 (UTC) */
+ uint8_t valid; /**< Validity Flags (see UBX_RX_NAV_TIMEUTC_VALID_...) */
+} ubx_payload_rx_nav_timeutc_t;
+
+/* Rx NAV-SVINFO Part 1 */
typedef struct {
- uint32_t time_milliseconds; // GPS Millisecond Time of Week
- int32_t velN; //NED north velocity, cm/s
- int32_t velE; //NED east velocity, cm/s
- int32_t velD; //NED down velocity, cm/s
- uint32_t speed; //Speed (3-D), cm/s
- uint32_t gSpeed; //Ground Speed (2-D), cm/s
- int32_t heading; //Heading of motion 2-D, deg, scaling: 1e-5
- uint32_t sAcc; //Speed Accuracy Estimate, cm/s
- uint32_t cAcc; //Course / Heading Accuracy Estimate, scaling: 1e-5
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_nav_velned_packet_t;
-
-struct gps_bin_mon_hw_packet {
- uint32_t pinSel;
- uint32_t pinBank;
- uint32_t pinDir;
- uint32_t pinVal;
- uint16_t noisePerMS;
- uint16_t agcCnt;
- uint8_t aStatus;
- uint8_t aPower;
- uint8_t flags;
- uint8_t __reserved1;
- uint32_t usedMask;
- uint8_t VP[25];
- uint8_t jamInd;
- uint16_t __reserved3;
- uint32_t pinIrq;
- uint32_t pulLH;
- uint32_t pullL;
-};
-
-
-//typedef struct {
-// int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */
-// int16_t week; /**< Measurement GPS week number */
-// uint8_t numVis; /**< Number of visible satellites */
-//
-// //... rest of package is not used in this implementation
-//
-//} gps_bin_rxm_svsi_packet_t;
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ uint8_t numCh; /**< Number of channels */
+ uint8_t globalFlags;
+ uint16_t reserved2;
+} ubx_payload_rx_nav_svinfo_part1_t;
+/* Rx NAV-SVINFO Part 2 (repeated) */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_ack_ack_packet_t;
-
+ uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */
+ uint8_t svid; /**< Satellite ID */
+ uint8_t flags;
+ uint8_t quality;
+ uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength) [dbHz] */
+ int8_t elev; /**< Elevation [deg] */
+ int16_t azim; /**< Azimuth [deg] */
+ int32_t prRes; /**< Pseudo range residual [cm] */
+} ubx_payload_rx_nav_svinfo_part2_t;
+
+/* Rx NAV-VELNED */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_ack_nak_packet_t;
-
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ int32_t velN; /**< North velocity component [cm/s]*/
+ int32_t velE; /**< East velocity component [cm/s]*/
+ int32_t velD; /**< Down velocity component [cm/s]*/
+ uint32_t speed; /**< Speed (3-D) [cm/s] */
+ uint32_t gSpeed; /**< Ground speed (2-D) [cm/s] */
+ int32_t heading; /**< Heading of motion 2-D [1e-5 deg] */
+ uint32_t sAcc; /**< Speed accuracy estimate [cm/s] */
+ uint32_t cAcc; /**< Course / Heading accuracy estimate [1e-5 deg] */
+} ubx_payload_rx_nav_velned_t;
+
+/* Rx MON-HW (ubx6) */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint8_t portID;
- uint8_t res0;
- uint16_t res1;
- uint32_t mode;
- uint32_t baudRate;
- uint16_t inProtoMask;
- uint16_t outProtoMask;
- uint16_t flags;
- uint16_t pad;
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_prt_packet_t;
-
+ uint32_t pinSel;
+ uint32_t pinBank;
+ uint32_t pinDir;
+ uint32_t pinVal;
+ uint16_t noisePerMS;
+ uint16_t agcCnt;
+ uint8_t aStatus;
+ uint8_t aPower;
+ uint8_t flags;
+ uint8_t reserved1;
+ uint32_t usedMask;
+ uint8_t VP[25];
+ uint8_t jamInd;
+ uint16_t reserved3;
+ uint32_t pinIrq;
+ uint32_t pullH;
+ uint32_t pullL;
+} ubx_payload_rx_mon_hw_ubx6_t;
+
+/* Rx MON-HW (ubx7+) */
+typedef struct {
+ uint32_t pinSel;
+ uint32_t pinBank;
+ uint32_t pinDir;
+ uint32_t pinVal;
+ uint16_t noisePerMS;
+ uint16_t agcCnt;
+ uint8_t aStatus;
+ uint8_t aPower;
+ uint8_t flags;
+ uint8_t reserved1;
+ uint32_t usedMask;
+ uint8_t VP[17];
+ uint8_t jamInd;
+ uint16_t reserved3;
+ uint32_t pinIrq;
+ uint32_t pullH;
+ uint32_t pullL;
+} ubx_payload_rx_mon_hw_ubx7_t;
+
+/* Rx MON-VER Part 1 */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint16_t measRate;
- uint16_t navRate;
- uint16_t timeRef;
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_rate_packet_t;
+ uint8_t swVersion[30];
+ uint8_t hwVersion[10];
+} ubx_payload_rx_mon_ver_part1_t;
+/* Rx MON-VER Part 2 (repeated) */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint16_t mask;
- uint8_t dynModel;
- uint8_t fixMode;
- int32_t fixedAlt;
- uint32_t fixedAltVar;
- int8_t minElev;
- uint8_t drLimit;
- uint16_t pDop;
- uint16_t tDop;
- uint16_t pAcc;
- uint16_t tAcc;
- uint8_t staticHoldThresh;
- uint8_t dgpsTimeOut;
- uint32_t reserved2;
- uint32_t reserved3;
- uint32_t reserved4;
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_nav5_packet_t;
+ uint8_t extension[30];
+} ubx_payload_rx_mon_ver_part2_t;
+
+/* Rx ACK-ACK */
+typedef union {
+ uint16_t msg;
+ struct {
+ uint8_t clsID;
+ uint8_t msgID;
+ };
+} ubx_payload_rx_ack_ack_t;
+
+/* Rx ACK-NAK */
+typedef union {
+ uint16_t msg;
+ struct {
+ uint8_t clsID;
+ uint8_t msgID;
+ };
+} ubx_payload_rx_ack_nak_t;
+
+/* Tx CFG-PRT */
+typedef struct {
+ uint8_t portID;
+ uint8_t reserved0;
+ uint16_t txReady;
+ uint32_t mode;
+ uint32_t baudRate;
+ uint16_t inProtoMask;
+ uint16_t outProtoMask;
+ uint16_t flags;
+ uint16_t reserved5;
+} ubx_payload_tx_cfg_prt_t;
+
+/* Tx CFG-RATE */
+typedef struct {
+ uint16_t measRate; /**< Measurement Rate, GPS measurements are taken every measRate milliseconds */
+ uint16_t navRate; /**< Navigation Rate, in number of measurement cycles. This parameter cannot be changed, and must be set to 1 */
+ uint16_t timeRef; /**< Alignment to reference time: 0 = UTC time, 1 = GPS time */
+} ubx_payload_tx_cfg_rate_t;
+/* Tx CFG-NAV5 */
+typedef struct {
+ uint16_t mask;
+ uint8_t dynModel; /**< Dynamic Platform model: 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g */
+ uint8_t fixMode; /**< Position Fixing Mode: 1 2D only, 2 3D only, 3 Auto 2D/3D */
+ int32_t fixedAlt;
+ uint32_t fixedAltVar;
+ int8_t minElev;
+ uint8_t drLimit;
+ uint16_t pDop;
+ uint16_t tDop;
+ uint16_t pAcc;
+ uint16_t tAcc;
+ uint8_t staticHoldThresh;
+ uint8_t dgpsTimeOut;
+ uint8_t cnoThreshNumSVs; /**< (ubx7+ only, else 0) */
+ uint8_t cnoThresh; /**< (ubx7+ only, else 0) */
+ uint16_t reserved;
+ uint16_t staticHoldMaxDist; /**< (ubx8+ only, else 0) */
+ uint8_t utcStandard; /**< (ubx8+ only, else 0) */
+ uint8_t reserved3;
+ uint32_t reserved4;
+} ubx_payload_tx_cfg_nav5_t;
+
+/* Tx CFG-MSG */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint8_t msgClass_payload;
- uint8_t msgID_payload;
+ union {
+ uint16_t msg;
+ struct {
+ uint8_t msgClass;
+ uint8_t msgID;
+ };
+ };
uint8_t rate;
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_msg_packet_t;
+} ubx_payload_tx_cfg_msg_t;
+
+/* General message and payload buffer union */
+typedef union {
+ ubx_payload_rx_nav_pvt_t payload_rx_nav_pvt;
+ ubx_payload_rx_nav_posllh_t payload_rx_nav_posllh;
+ ubx_payload_rx_nav_sol_t payload_rx_nav_sol;
+ ubx_payload_rx_nav_timeutc_t payload_rx_nav_timeutc;
+ ubx_payload_rx_nav_svinfo_part1_t payload_rx_nav_svinfo_part1;
+ ubx_payload_rx_nav_svinfo_part2_t payload_rx_nav_svinfo_part2;
+ ubx_payload_rx_nav_velned_t payload_rx_nav_velned;
+ ubx_payload_rx_mon_hw_ubx6_t payload_rx_mon_hw_ubx6;
+ ubx_payload_rx_mon_hw_ubx7_t payload_rx_mon_hw_ubx7;
+ ubx_payload_rx_mon_ver_part1_t payload_rx_mon_ver_part1;
+ ubx_payload_rx_mon_ver_part2_t payload_rx_mon_ver_part2;
+ ubx_payload_rx_ack_ack_t payload_rx_ack_ack;
+ ubx_payload_rx_ack_nak_t payload_rx_ack_nak;
+ ubx_payload_tx_cfg_prt_t payload_tx_cfg_prt;
+ ubx_payload_tx_cfg_rate_t payload_tx_cfg_rate;
+ ubx_payload_tx_cfg_nav5_t payload_tx_cfg_nav5;
+ ubx_payload_tx_cfg_msg_t payload_tx_cfg_msg;
+ uint8_t raw[];
+} ubx_buf_t;
-struct ubx_cfg_msg_rate {
- uint8_t msg_class;
- uint8_t msg_id;
- uint8_t rate;
-};
-
-
-// END the structures of the binary packets
-// ************
+#pragma pack(pop)
+/*** END OF u-blox protocol binary message and payload definitions ***/
+/* Decoder state */
typedef enum {
- UBX_DECODE_UNINIT = 0,
- UBX_DECODE_GOT_SYNC1,
- UBX_DECODE_GOT_SYNC2,
- UBX_DECODE_GOT_CLASS,
- UBX_DECODE_GOT_MESSAGEID,
- UBX_DECODE_GOT_LENGTH1,
- UBX_DECODE_GOT_LENGTH2
+ UBX_DECODE_SYNC1 = 0,
+ UBX_DECODE_SYNC2,
+ UBX_DECODE_CLASS,
+ UBX_DECODE_ID,
+ UBX_DECODE_LENGTH1,
+ UBX_DECODE_LENGTH2,
+ UBX_DECODE_PAYLOAD,
+ UBX_DECODE_CHKSUM1,
+ UBX_DECODE_CHKSUM2
} ubx_decode_state_t;
-//typedef type_gps_bin_ubx_state gps_bin_ubx_state_t;
-#pragma pack(pop)
+/* Rx message state */
+typedef enum {
+ UBX_RXMSG_IGNORE = 0,
+ UBX_RXMSG_HANDLE,
+ UBX_RXMSG_DISABLE,
+ UBX_RXMSG_ERROR_LENGTH
+} ubx_rxmsg_state_t;
+
+/* ACK state */
+typedef enum {
+ UBX_ACK_IDLE = 0,
+ UBX_ACK_WAITING,
+ UBX_ACK_GOT_ACK,
+ UBX_ACK_GOT_NAK
+} ubx_ack_state_t;
-#define RECV_BUFFER_SIZE 300 //The NAV-SOL messages really need such a big buffer
class UBX : public GPS_Helper
{
public:
- UBX(const int &fd, struct vehicle_gps_position_s *gps_position);
+ UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info);
~UBX();
- int receive(unsigned timeout);
+ int receive(const unsigned timeout);
int configure(unsigned &baudrate);
private:
/**
- * Parse the binary MTK packet
+ * Parse the binary UBX packet
+ */
+ int parse_char(const uint8_t b);
+
+ /**
+ * Start payload rx
*/
- int parse_char(uint8_t b);
+ int payload_rx_init(void);
/**
- * Handle the package once it has arrived
+ * Add payload rx byte
*/
- int handle_message(void);
+ int payload_rx_add(const uint8_t b);
+ int payload_rx_add_nav_svinfo(const uint8_t b);
+ int payload_rx_add_mon_ver(const uint8_t b);
+
+ /**
+ * Finish payload rx
+ */
+ int payload_rx_done(void);
/**
* Reset the parse state machine for a fresh start
@@ -373,44 +490,53 @@ private:
/**
* While parsing add every byte (except the sync bytes) to the checksum
*/
- void add_byte_to_checksum(uint8_t);
+ void add_byte_to_checksum(const uint8_t);
/**
- * Add the two checksum bytes to an outgoing message
+ * Send a message
*/
- void add_checksum_to_message(uint8_t *message, const unsigned length);
+ void send_message(const uint16_t msg, const uint8_t *payload, const uint16_t length);
/**
- * Helper to send a config packet
+ * Configure message rate
*/
- void send_config_packet(const int &fd, uint8_t *packet, const unsigned length);
+ void configure_message_rate(const uint16_t msg, const uint8_t rate);
- void configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
-
- void send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size);
+ /**
+ * Calculate & add checksum for given buffer
+ */
+ void calc_checksum(const uint8_t *buffer, const uint16_t length, ubx_checksum_t *checksum);
- void add_checksum(uint8_t *message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b);
+ /**
+ * Wait for message acknowledge
+ */
+ int wait_for_ack(const uint16_t msg, const unsigned timeout, const bool report);
- int wait_for_ack(unsigned timeout);
+ /**
+ * Calculate FNV1 hash
+ */
+ uint32_t fnv1_32_str(uint8_t *str, uint32_t hval);
int _fd;
struct vehicle_gps_position_s *_gps_position;
+ struct satellite_info_s *_satellite_info;
+ bool _enable_sat_info;
bool _configured;
- bool _waiting_for_ack;
+ ubx_ack_state_t _ack_state;
bool _got_posllh;
bool _got_velned;
- bool _got_timeutc;
- uint8_t _message_class_needed;
- uint8_t _message_id_needed;
ubx_decode_state_t _decode_state;
- uint8_t _rx_buffer[RECV_BUFFER_SIZE];
- unsigned _rx_count;
+ uint16_t _rx_msg;
+ ubx_rxmsg_state_t _rx_state;
+ uint16_t _rx_payload_length;
+ uint16_t _rx_payload_index;
uint8_t _rx_ck_a;
uint8_t _rx_ck_b;
- uint8_t _message_class;
- uint8_t _message_id;
- unsigned _payload_size;
hrt_abstime _disable_cmd_last;
+ uint16_t _ack_waiting_msg;
+ ubx_buf_t _buf;
+ uint32_t _ubx_version;
+ bool _use_nav_pvt;
};
#endif /* UBX_H_ */
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index 55cc077fb..f17e99e9d 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -229,7 +229,7 @@ HIL::init()
_task = task_spawn_cmd("fmuhil",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 1200,
(main_t)&HIL::task_main_trampoline,
nullptr);
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index be8e14807..ad1770300 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -71,13 +71,16 @@
#include <uORB/topics/subsystem_info.h>
#include <float.h>
+#include <getopt.h>
+#include <lib/conversion/rotation.h>
/*
* HMC5883 internal constants and data structures.
*/
#define HMC5883L_ADDRESS PX4_I2C_OBDEV_HMC5883
-#define HMC5883L_DEVICE_PATH "/dev/hmc5883"
+#define HMC5883L_DEVICE_PATH_INT "/dev/hmc5883_int"
+#define HMC5883L_DEVICE_PATH_EXT "/dev/hmc5883_ext"
/* Max measurement rate is 160Hz, however with 160 it will be set to 166 Hz, therefore workaround using 150 */
#define HMC5883_CONVERSION_INTERVAL (1000000 / 150) /* microseconds */
@@ -130,7 +133,7 @@ static const int ERROR = -1;
class HMC5883 : public device::I2C
{
public:
- HMC5883(int bus);
+ HMC5883(int bus, const char *path, enum Rotation rotation);
virtual ~HMC5883();
virtual int init();
@@ -163,15 +166,21 @@ private:
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
+ perf_counter_t _range_errors;
+ perf_counter_t _conf_errors;
/* status reporting */
bool _sensor_ok; /**< sensor was found and reports ok */
bool _calibrated; /**< the calibration is valid */
int _bus; /**< the bus the device is connected to */
+ enum Rotation _rotation;
struct mag_report _last_report; /**< used for info() */
+ uint8_t _range_bits;
+ uint8_t _conf_reg;
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -230,6 +239,23 @@ private:
int set_range(unsigned range);
/**
+ * check the sensor range.
+ *
+ * checks that the range of the sensor is correctly set, to
+ * cope with communication errors causing the range to change
+ */
+ void check_range(void);
+
+ /**
+ * check the sensor configuration.
+ *
+ * checks that the config of the sensor is correctly set, to
+ * cope with communication errors causing the configuration to
+ * change
+ */
+ void check_conf(void);
+
+ /**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
*
@@ -319,23 +345,31 @@ private:
extern "C" __EXPORT int hmc5883_main(int argc, char *argv[]);
-HMC5883::HMC5883(int bus) :
- I2C("HMC5883", HMC5883L_DEVICE_PATH, bus, HMC5883L_ADDRESS, 400000),
+HMC5883::HMC5883(int bus, const char *path, enum Rotation rotation) :
+ I2C("HMC5883", path, bus, HMC5883L_ADDRESS, 400000),
_measure_ticks(0),
_reports(nullptr),
_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),
- _class_instance(-1),
_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")),
+ _range_errors(perf_alloc(PC_COUNT, "hmc5883_range_errors")),
+ _conf_errors(perf_alloc(PC_COUNT, "hmc5883_conf_errors")),
_sensor_ok(false),
_calibrated(false),
- _bus(bus)
+ _bus(bus),
+ _rotation(rotation),
+ _last_report{0},
+ _range_bits(0),
+ _conf_reg(0)
{
+ _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_HMC5883;
+
// enable debug() calls
_debug_enabled = false;
@@ -366,6 +400,8 @@ HMC5883::~HMC5883()
perf_free(_sample_perf);
perf_free(_comms_errors);
perf_free(_buffer_overflows);
+ perf_free(_range_errors);
+ perf_free(_conf_errors);
}
int
@@ -396,45 +432,43 @@ out:
int HMC5883::set_range(unsigned range)
{
- uint8_t range_bits;
-
if (range < 1) {
- range_bits = 0x00;
+ _range_bits = 0x00;
_range_scale = 1.0f / 1370.0f;
_range_ga = 0.88f;
} else if (range <= 1) {
- range_bits = 0x01;
+ _range_bits = 0x01;
_range_scale = 1.0f / 1090.0f;
_range_ga = 1.3f;
} else if (range <= 2) {
- range_bits = 0x02;
+ _range_bits = 0x02;
_range_scale = 1.0f / 820.0f;
_range_ga = 1.9f;
} else if (range <= 3) {
- range_bits = 0x03;
+ _range_bits = 0x03;
_range_scale = 1.0f / 660.0f;
_range_ga = 2.5f;
} else if (range <= 4) {
- range_bits = 0x04;
+ _range_bits = 0x04;
_range_scale = 1.0f / 440.0f;
_range_ga = 4.0f;
} else if (range <= 4.7f) {
- range_bits = 0x05;
+ _range_bits = 0x05;
_range_scale = 1.0f / 390.0f;
_range_ga = 4.7f;
} else if (range <= 5.6f) {
- range_bits = 0x06;
+ _range_bits = 0x06;
_range_scale = 1.0f / 330.0f;
_range_ga = 5.6f;
} else {
- range_bits = 0x07;
+ _range_bits = 0x07;
_range_scale = 1.0f / 230.0f;
_range_ga = 8.1f;
}
@@ -444,7 +478,7 @@ int HMC5883::set_range(unsigned range)
/*
* Send the command to set the range
*/
- ret = write_reg(ADDR_CONF_B, (range_bits << 5));
+ ret = write_reg(ADDR_CONF_B, (_range_bits << 5));
if (OK != ret)
perf_count(_comms_errors);
@@ -455,7 +489,53 @@ int HMC5883::set_range(unsigned range)
if (OK != ret)
perf_count(_comms_errors);
- return !(range_bits_in == (range_bits << 5));
+ return !(range_bits_in == (_range_bits << 5));
+}
+
+/**
+ check that the range register has the right value. This is done
+ periodically to cope with I2C bus noise causing the range of the
+ compass changing.
+ */
+void HMC5883::check_range(void)
+{
+ int ret;
+
+ uint8_t range_bits_in;
+ ret = read_reg(ADDR_CONF_B, range_bits_in);
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ return;
+ }
+ if (range_bits_in != (_range_bits<<5)) {
+ perf_count(_range_errors);
+ ret = write_reg(ADDR_CONF_B, (_range_bits << 5));
+ if (OK != ret)
+ perf_count(_comms_errors);
+ }
+}
+
+/**
+ check that the configuration register has the right value. This is
+ done periodically to cope with I2C bus noise causing the
+ configuration of the compass to change.
+ */
+void HMC5883::check_conf(void)
+{
+ int ret;
+
+ uint8_t conf_reg_in;
+ ret = read_reg(ADDR_CONF_A, conf_reg_in);
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ return;
+ }
+ if (conf_reg_in != _conf_reg) {
+ perf_count(_conf_errors);
+ ret = write_reg(ADDR_CONF_A, _conf_reg);
+ if (OK != ret)
+ perf_count(_comms_errors);
+ }
}
int
@@ -789,7 +869,7 @@ HMC5883::collect()
} report;
int ret = -EIO;
uint8_t cmd;
-
+ uint8_t check_counter;
perf_begin(_sample_perf);
struct mag_report new_report;
@@ -862,6 +942,9 @@ HMC5883::collect()
/* z remains z */
new_report.z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
+ // 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 (_mag_topic != -1) {
@@ -885,6 +968,21 @@ HMC5883::collect()
/* notify anyone waiting for data */
poll_notify(POLLIN);
+ /*
+ periodically check the range register and configuration
+ registers. With a bad I2C cable it is possible for the
+ registers to become corrupt, leading to bad readings. It
+ doesn't happen often, but given the poor cables some
+ vehicles have it is worth checking for.
+ */
+ check_counter = perf_event_count(_sample_perf) % 256;
+ if (check_counter == 0) {
+ check_range();
+ }
+ if (check_counter == 128) {
+ check_conf();
+ }
+
ret = OK;
out:
@@ -1158,25 +1256,24 @@ int HMC5883::set_excitement(unsigned enable)
{
int ret;
/* arm the excitement strap */
- uint8_t conf_reg;
- ret = read_reg(ADDR_CONF_A, conf_reg);
+ ret = read_reg(ADDR_CONF_A, _conf_reg);
if (OK != ret)
perf_count(_comms_errors);
if (((int)enable) < 0) {
- conf_reg |= 0x01;
+ _conf_reg |= 0x01;
} else if (enable > 0) {
- conf_reg |= 0x02;
+ _conf_reg |= 0x02;
} else {
- conf_reg &= ~0x03;
+ _conf_reg &= ~0x03;
}
- // ::printf("set_excitement enable=%d regA=0x%x\n", (int)enable, (unsigned)conf_reg);
+ // ::printf("set_excitement enable=%d regA=0x%x\n", (int)enable, (unsigned)_conf_reg);
- ret = write_reg(ADDR_CONF_A, conf_reg);
+ ret = write_reg(ADDR_CONF_A, _conf_reg);
if (OK != ret)
perf_count(_comms_errors);
@@ -1186,7 +1283,7 @@ int HMC5883::set_excitement(unsigned enable)
//print_info();
- return !(conf_reg == conf_reg_ret);
+ return !(_conf_reg == conf_reg_ret);
}
int
@@ -1228,7 +1325,7 @@ HMC5883::print_info()
printf("offsets (%.2f %.2f %.2f)\n", (double)_scale.x_offset, (double)_scale.y_offset, (double)_scale.z_offset);
printf("scaling (%.2f %.2f %.2f) 1/range_scale %.2f range_ga %.2f\n",
(double)_scale.x_scale, (double)_scale.y_scale, (double)_scale.z_scale,
- (double)1.0/_range_scale, (double)_range_ga);
+ (double)(1.0f/_range_scale), (double)_range_ga);
_reports->print_info("report queue");
}
@@ -1244,63 +1341,87 @@ namespace hmc5883
#endif
const int ERROR = -1;
-HMC5883 *g_dev;
+HMC5883 *g_dev_int;
+HMC5883 *g_dev_ext;
-void start();
-void test();
-void reset();
-void info();
-int calibrate();
+void start(int bus, enum Rotation rotation);
+void test(int bus);
+void reset(int bus);
+void info(int bus);
+int calibrate(int bus);
+void usage();
/**
* Start the driver.
*/
void
-start()
+start(int bus, enum Rotation rotation)
{
int fd;
- if (g_dev != nullptr)
- /* if already started, the still command succeeded */
- errx(0, "already started");
-
/* create the driver, attempt expansion bus first */
- g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION);
- if (g_dev != nullptr && OK != g_dev->init()) {
- delete g_dev;
- g_dev = nullptr;
+ if (bus == -1 || bus == PX4_I2C_BUS_EXPANSION) {
+ if (g_dev_ext != nullptr)
+ errx(0, "already started external");
+ g_dev_ext = new HMC5883(PX4_I2C_BUS_EXPANSION, HMC5883L_DEVICE_PATH_EXT, rotation);
+ if (g_dev_ext != nullptr && OK != g_dev_ext->init()) {
+ delete g_dev_ext;
+ g_dev_ext = nullptr;
+ }
}
#ifdef PX4_I2C_BUS_ONBOARD
/* if this failed, attempt onboard sensor */
- if (g_dev == nullptr) {
- g_dev = new HMC5883(PX4_I2C_BUS_ONBOARD);
- if (g_dev != nullptr && OK != g_dev->init()) {
+ if (bus == -1 || bus == PX4_I2C_BUS_ONBOARD) {
+ if (g_dev_int != nullptr)
+ 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()) {
+ if (bus == PX4_I2C_BUS_ONBOARD) {
+ goto fail;
+ }
+ }
+ if (g_dev_int == nullptr && bus == PX4_I2C_BUS_ONBOARD) {
goto fail;
}
}
#endif
- if (g_dev == nullptr)
+ if (g_dev_int == nullptr && g_dev_ext == nullptr)
goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
+ if (g_dev_int != nullptr) {
+ fd = open(HMC5883L_DEVICE_PATH_INT, O_RDONLY);
+ if (fd < 0)
+ goto fail;
- if (fd < 0)
- goto fail;
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ goto fail;
+ close(fd);
+ }
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
- goto fail;
+ if (g_dev_ext != nullptr) {
+ fd = open(HMC5883L_DEVICE_PATH_EXT, O_RDONLY);
+ if (fd < 0)
+ goto fail;
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ goto fail;
+ close(fd);
+ }
exit(0);
fail:
-
- if (g_dev != nullptr) {
- delete g_dev;
- g_dev = nullptr;
+ if (g_dev_int != nullptr && (bus == -1 || bus == PX4_I2C_BUS_ONBOARD)) {
+ delete g_dev_int;
+ g_dev_int = nullptr;
+ }
+ if (g_dev_ext != nullptr && (bus == -1 || bus == PX4_I2C_BUS_EXPANSION)) {
+ delete g_dev_ext;
+ g_dev_ext = nullptr;
}
errx(1, "driver start failed");
@@ -1312,16 +1433,17 @@ fail:
* and automatic modes.
*/
void
-test()
+test(int bus)
{
struct mag_report report;
ssize_t sz;
int ret;
+ const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT);
- int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
+ int fd = open(path, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", HMC5883L_DEVICE_PATH);
+ err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", path);
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
@@ -1414,14 +1536,15 @@ test()
* configuration register A back to 00 (Normal Measurement Mode), e.g. 0x10.
* Using the self test method described above, the user can scale sensor
*/
-int calibrate()
+int calibrate(int bus)
{
int ret;
+ const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT);
- int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
+ int fd = open(path, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", HMC5883L_DEVICE_PATH);
+ err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", path);
if (OK != (ret = ioctl(fd, MAGIOCCALIBRATE, fd))) {
warnx("failed to enable sensor calibration mode");
@@ -1441,9 +1564,11 @@ int calibrate()
* Reset the driver.
*/
void
-reset()
+reset(int bus)
{
- int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
+ const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT);
+
+ int fd = open(path, O_RDONLY);
if (fd < 0)
err(1, "failed ");
@@ -1461,8 +1586,9 @@ reset()
* Print a little info about the driver.
*/
void
-info()
+info(int bus)
{
+ HMC5883 *g_dev = (bus == PX4_I2C_BUS_ONBOARD?g_dev_int:g_dev_ext);
if (g_dev == nullptr)
errx(1, "driver not running");
@@ -1472,40 +1598,91 @@ info()
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'info', 'test', 'reset', 'info', 'calibrate'");
+ warnx("options:");
+ warnx(" -R rotation");
+ warnx(" -C calibrate on start");
+ warnx(" -X only external bus");
+#ifdef PX4_I2C_BUS_ONBOARD
+ warnx(" -I only internal bus");
+#endif
+}
+
} // namespace
int
hmc5883_main(int argc, char *argv[])
{
+ int ch;
+ int bus = -1;
+ enum Rotation rotation = ROTATION_NONE;
+ bool calibrate = false;
+
+ while ((ch = getopt(argc, argv, "XIR:C")) != EOF) {
+ switch (ch) {
+ case 'R':
+ rotation = (enum Rotation)atoi(optarg);
+ break;
+#ifdef PX4_I2C_BUS_ONBOARD
+ case 'I':
+ bus = PX4_I2C_BUS_ONBOARD;
+ break;
+#endif
+ case 'X':
+ bus = PX4_I2C_BUS_EXPANSION;
+ break;
+ case 'C':
+ calibrate = true;
+ break;
+ default:
+ hmc5883::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
- hmc5883::start();
+ if (!strcmp(verb, "start")) {
+ hmc5883::start(bus, rotation);
+ if (calibrate) {
+ if (hmc5883::calibrate(bus) == 0) {
+ errx(0, "calibration successful");
+
+ } else {
+ errx(1, "calibration failed");
+ }
+ }
+ }
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
- hmc5883::test();
+ if (!strcmp(verb, "test"))
+ hmc5883::test(bus);
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
- hmc5883::reset();
+ if (!strcmp(verb, "reset"))
+ hmc5883::reset(bus);
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
- hmc5883::info();
+ if (!strcmp(verb, "info") || !strcmp(verb, "status"))
+ hmc5883::info(bus);
/*
* Autocalibrate the scaling
*/
- if (!strcmp(argv[1], "calibrate")) {
- if (hmc5883::calibrate() == 0) {
+ if (!strcmp(verb, "calibrate")) {
+ if (hmc5883::calibrate(bus) == 0) {
errx(0, "calibration successful");
} else {
diff --git a/src/drivers/hott/hott_sensors/module.mk b/src/drivers/hott/hott_sensors/module.mk
index b5f5762ba..47aea6caf 100644
--- a/src/drivers/hott/hott_sensors/module.mk
+++ b/src/drivers/hott/hott_sensors/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = hott_sensors
SRCS = hott_sensors.cpp \
../messages.cpp \
../comms.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/hott/hott_telemetry/module.mk b/src/drivers/hott/hott_telemetry/module.mk
index b19cbd14c..cd7bdbc85 100644
--- a/src/drivers/hott/hott_telemetry/module.mk
+++ b/src/drivers/hott/hott_telemetry/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = hott_telemetry
SRCS = hott_telemetry.cpp \
../messages.cpp \
../comms.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
index 1e779e8dc..086132573 100644
--- a/src/drivers/hott/messages.cpp
+++ b/src/drivers/hott/messages.cpp
@@ -226,7 +226,7 @@ build_gps_response(uint8_t *buffer, size_t *size)
msg.sensor_id = GPS_SENSOR_ID;
msg.sensor_text_id = GPS_SENSOR_TEXT_ID;
- msg.gps_num_sat = gps.satellites_visible;
+ msg.gps_num_sat = gps.satellites_used;
/* The GPS fix type: 0 = none, 2 = 2D, 3 = 3D */
msg.gps_fix_char = (uint8_t)(gps.fix_type + 48);
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 2fcbdc0ad..9e5eb00db 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -54,6 +54,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <getopt.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@@ -68,6 +69,7 @@
#include <board_config.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
+#include <lib/conversion/rotation.h>
#define L3GD20_DEVICE_PATH "/dev/l3gd20"
@@ -184,7 +186,7 @@ extern "C" { __EXPORT int l3gd20_main(int argc, char *argv[]); }
class L3GD20 : public device::SPI
{
public:
- L3GD20(int bus, const char* path, spi_dev_e device);
+ L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotation);
virtual ~L3GD20();
virtual int init();
@@ -229,6 +231,8 @@ private:
/* true if an L3G4200D is detected */
bool _is_l3g4200d;
+ enum Rotation _rotation;
+
/**
* Start automatic measurement.
*/
@@ -328,7 +332,7 @@ private:
int self_test();
};
-L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
+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_interval(0),
_reports(nullptr),
@@ -345,7 +349,8 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
_gyro_filter_x(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
_gyro_filter_y(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
_gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
- _is_l3g4200d(false)
+ _is_l3g4200d(false),
+ _rotation(rotation)
{
// enable debug() calls
_debug_enabled = true;
@@ -823,7 +828,7 @@ L3GD20::measure()
// if the gyro doesn't have any data ready then re-schedule
// for 100 microseconds later. This ensures we don't double
// read a value and then miss the next value
- if (stm32_gpioread(GPIO_EXTI_GYRO_DRDY) == 0) {
+ if (_bus == PX4_SPI_BUS_SENSORS && stm32_gpioread(GPIO_EXTI_GYRO_DRDY) == 0) {
perf_count(_reschedules);
hrt_call_delay(&_call, 100);
return;
@@ -916,6 +921,9 @@ L3GD20::measure()
report.y = _gyro_filter_y.apply(report.y);
report.z = _gyro_filter_z.apply(report.z);
+ // apply user specified rotation
+ rotate_3f(_rotation, report.x, report.y, report.z);
+
report.scaling = _gyro_range_scale;
report.range_rad_s = _gyro_range_rad_s;
@@ -984,7 +992,8 @@ namespace l3gd20
L3GD20 *g_dev;
-void start();
+void usage();
+void start(bool external_bus, enum Rotation rotation);
void test();
void reset();
void info();
@@ -993,7 +1002,7 @@ void info();
* Start the driver.
*/
void
-start()
+start(bool external_bus, enum Rotation rotation)
{
int fd;
@@ -1001,7 +1010,15 @@ start()
errx(0, "already started");
/* create the driver */
- g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
+ if (external_bus) {
+#ifdef PX4_SPI_BUS_EXT
+ g_dev = new L3GD20(PX4_SPI_BUS_EXT, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_EXT_GYRO, rotation);
+#else
+ errx(0, "External SPI not available");
+#endif
+ } else {
+ g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO, rotation);
+ }
if (g_dev == nullptr)
goto fail;
@@ -1113,35 +1130,64 @@ info()
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'info', 'test', 'reset'");
+ warnx("options:");
+ warnx(" -X (external bus)");
+ warnx(" -R rotation");
+}
} // namespace
int
l3gd20_main(int argc, char *argv[])
{
+ bool external_bus = false;
+ int ch;
+ enum Rotation rotation = ROTATION_NONE;
+
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc, argv, "XR:")) != EOF) {
+ switch (ch) {
+ case 'X':
+ external_bus = true;
+ break;
+ case 'R':
+ rotation = (enum Rotation)atoi(optarg);
+ break;
+ default:
+ l3gd20::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
- l3gd20::start();
+ if (!strcmp(verb, "start"))
+ l3gd20::start(external_bus, rotation);
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
+ if (!strcmp(verb, "test"))
l3gd20::test();
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
+ if (!strcmp(verb, "reset"))
l3gd20::reset();
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info"))
+ if (!strcmp(verb, "info"))
l3gd20::info();
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp
new file mode 100644
index 000000000..a69e6ee55
--- /dev/null
+++ b/src/drivers/ll40ls/ll40ls.cpp
@@ -0,0 +1,882 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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 ll40ls.cpp
+ * @author Allyson Kreft
+ *
+ * Driver for the PulsedLight Lidar-Lite range finders connected via I2C.
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <string.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <errno.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_range_finder.h>
+#include <drivers/device/ringbuffer.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/subsystem_info.h>
+
+#include <board_config.h>
+
+/* Configuration Constants */
+#define LL40LS_BUS PX4_I2C_BUS_EXPANSION
+#define LL40LS_BASEADDR 0x42 /* 7-bit address */
+#define LL40LS_DEVICE_PATH "/dev/ll40ls"
+
+/* LL40LS Registers addresses */
+
+#define LL40LS_MEASURE_REG 0x00 /* Measure range register */
+#define LL40LS_MSRREG_ACQUIRE 0x04 /* Value to initiate a measurement, varies based on sensor revision */
+#define LL40LS_DISTHIGH_REG 0x8F /* High byte of distance register, auto increment */
+
+/* Device limits */
+#define LL40LS_MIN_DISTANCE (0.00f)
+#define LL40LS_MAX_DISTANCE (14.00f)
+
+#define LL40LS_CONVERSION_INTERVAL 100000 /* 100ms */
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error This requires CONFIG_SCHED_WORKQUEUE.
+#endif
+
+class LL40LS : public device::I2C
+{
+public:
+ LL40LS(int bus = LL40LS_BUS, int address = LL40LS_BASEADDR);
+ virtual ~LL40LS();
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ /**
+ * Diagnostics - print some basic information about the driver.
+ */
+ void print_info();
+
+protected:
+ virtual int probe();
+
+private:
+ float _min_distance;
+ float _max_distance;
+ work_s _work;
+ RingBuffer *_reports;
+ bool _sensor_ok;
+ int _measure_ticks;
+ bool _collect_phase;
+ int _class_instance;
+
+ orb_advert_t _range_finder_topic;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+ perf_counter_t _buffer_overflows;
+
+ /**
+ * Test whether the device supported by the driver is present at a
+ * specific address.
+ *
+ * @param address The I2C bus address to probe.
+ * @return True if the device is present.
+ */
+ int probe_address(uint8_t address);
+
+ /**
+ * Initialise the automatic measurement state machine and start it.
+ *
+ * @note This function is called at open and error time. It might make sense
+ * to make it more aggressive about resetting the bus in case of errors.
+ */
+ void start();
+
+ /**
+ * Stop the automatic measurement state machine.
+ */
+ void stop();
+
+ /**
+ * Set the min and max distance thresholds if you want the end points of the sensors
+ * range to be brought in at all, otherwise it will use the defaults LL40LS_MIN_DISTANCE
+ * and LL40LS_MAX_DISTANCE
+ */
+ void set_minimum_distance(float min);
+ void set_maximum_distance(float max);
+ float get_minimum_distance();
+ float get_maximum_distance();
+
+ /**
+ * Perform a poll cycle; collect from the previous measurement
+ * and start a new one.
+ */
+ void cycle();
+ int measure();
+ int collect();
+ /**
+ * Static trampoline from the workq context; because we don't have a
+ * generic workq wrapper yet.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void cycle_trampoline(void *arg);
+
+
+};
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int ll40ls_main(int argc, char *argv[]);
+
+LL40LS::LL40LS(int bus, int address) :
+ I2C("LL40LS", LL40LS_DEVICE_PATH, bus, address, 100000),
+ _min_distance(LL40LS_MIN_DISTANCE),
+ _max_distance(LL40LS_MAX_DISTANCE),
+ _reports(nullptr),
+ _sensor_ok(false),
+ _measure_ticks(0),
+ _collect_phase(false),
+ _class_instance(-1),
+ _range_finder_topic(-1),
+ _sample_perf(perf_alloc(PC_ELAPSED, "ll40ls_read")),
+ _comms_errors(perf_alloc(PC_COUNT, "ll40ls_comms_errors")),
+ _buffer_overflows(perf_alloc(PC_COUNT, "ll40ls_buffer_overflows"))
+{
+ // up the retries since the device misses the first measure attempts
+ I2C::_retries = 3;
+
+ // enable debug() calls
+ _debug_enabled = false;
+
+ // work_cancel in the dtor will explode if we don't do this...
+ memset(&_work, 0, sizeof(_work));
+}
+
+LL40LS::~LL40LS()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ /* free any existing reports */
+ if (_reports != nullptr) {
+ delete _reports;
+ }
+
+ if (_class_instance != -1) {
+ unregister_class_devname(RANGE_FINDER_DEVICE_PATH, _class_instance);
+ }
+
+ // free perf counters
+ perf_free(_sample_perf);
+ perf_free(_comms_errors);
+ perf_free(_buffer_overflows);
+}
+
+int
+LL40LS::init()
+{
+ int ret = ERROR;
+
+ /* do I2C init (and probe) first */
+ if (I2C::init() != OK) {
+ goto out;
+ }
+
+ /* allocate basic report buffers */
+ _reports = new RingBuffer(2, sizeof(range_finder_report));
+
+ if (_reports == nullptr) {
+ goto out;
+ }
+
+ _class_instance = register_class_devname(RANGE_FINDER_DEVICE_PATH);
+
+ if (_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* get a publish handle on the range finder topic */
+ struct range_finder_report rf_report;
+ measure();
+ _reports->get(&rf_report);
+ _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &rf_report);
+
+ if (_range_finder_topic < 0) {
+ debug("failed to create sensor_range_finder object. Did you start uOrb?");
+ }
+ }
+
+ ret = OK;
+ /* sensor is ok, but we don't really know if it is within range */
+ _sensor_ok = true;
+out:
+ return ret;
+}
+
+int
+LL40LS::probe()
+{
+ return measure();
+}
+
+void
+LL40LS::set_minimum_distance(float min)
+{
+ _min_distance = min;
+}
+
+void
+LL40LS::set_maximum_distance(float max)
+{
+ _max_distance = max;
+}
+
+float
+LL40LS::get_minimum_distance()
+{
+ return _min_distance;
+}
+
+float
+LL40LS::get_maximum_distance()
+{
+ return _max_distance;
+}
+
+int
+LL40LS::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case SENSORIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _measure_ticks = 0;
+ return OK;
+
+ /* external signalling (DRDY) not supported */
+ case SENSOR_POLLRATE_EXTERNAL:
+
+ /* zero would be bad */
+ case 0:
+ return -EINVAL;
+
+ /* set default/max polling rate */
+ case SENSOR_POLLRATE_MAX:
+ case SENSOR_POLLRATE_DEFAULT: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* set interval for next measurement to minimum legal value */
+ _measure_ticks = USEC2TICK(LL40LS_CONVERSION_INTERVAL);
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start) {
+ start();
+ }
+
+ return OK;
+ }
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* convert hz to tick interval via microseconds */
+ unsigned ticks = USEC2TICK(1000000 / arg);
+
+ /* check against maximum rate */
+ if (ticks < USEC2TICK(LL40LS_CONVERSION_INTERVAL)) {
+ return -EINVAL;
+ }
+
+ /* update interval for next measurement */
+ _measure_ticks = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start) {
+ start();
+ }
+
+ return OK;
+ }
+ }
+ }
+
+ case SENSORIOCGPOLLRATE:
+ if (_measure_ticks == 0) {
+ return SENSOR_POLLRATE_MANUAL;
+ }
+
+ return (1000 / _measure_ticks);
+
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100)) {
+ return -EINVAL;
+ }
+
+ irqstate_t flags = irqsave();
+
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+
+ irqrestore(flags);
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _reports->size();
+
+ case SENSORIOCRESET:
+ /* XXX implement this */
+ return -EINVAL;
+
+ case RANGEFINDERIOCSETMINIUMDISTANCE: {
+ set_minimum_distance(*(float *)arg);
+ return 0;
+ }
+ break;
+
+ case RANGEFINDERIOCSETMAXIUMDISTANCE: {
+ set_maximum_distance(*(float *)arg);
+ return 0;
+ }
+ break;
+
+ default:
+ /* give it to the superclass */
+ return I2C::ioctl(filp, cmd, arg);
+ }
+}
+
+ssize_t
+LL40LS::read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct range_finder_report);
+ struct range_finder_report *rbuf = reinterpret_cast<struct range_finder_report *>(buffer);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1) {
+ return -ENOSPC;
+ }
+
+ /* if automatic measurement is enabled */
+ if (_measure_ticks > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ * Note that we may be pre-empted by the workq thread while we are doing this;
+ * we are careful to avoid racing with them.
+ */
+ while (count--) {
+ if (_reports->get(rbuf)) {
+ ret += sizeof(*rbuf);
+ rbuf++;
+ }
+ }
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement - run one conversion */
+ do {
+ _reports->flush();
+
+ /* trigger a measurement */
+ if (OK != measure()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* wait for it to complete */
+ usleep(LL40LS_CONVERSION_INTERVAL);
+
+ /* run the collection phase */
+ if (OK != collect()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* state machine will have generated a report, copy it out */
+ if (_reports->get(rbuf)) {
+ ret = sizeof(*rbuf);
+ }
+
+ } while (0);
+
+ return ret;
+}
+
+int
+LL40LS::measure()
+{
+ int ret;
+
+ /*
+ * Send the command to begin a measurement.
+ */
+ const uint8_t cmd[2] = { LL40LS_MEASURE_REG, LL40LS_MSRREG_ACQUIRE };
+ ret = transfer(cmd, sizeof(cmd), nullptr, 0);
+
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+ return ret;
+ }
+
+ ret = OK;
+
+ return ret;
+}
+
+int
+LL40LS::collect()
+{
+ int ret = -EIO;
+
+ /* read from the sensor */
+ uint8_t val[2] = {0, 0};
+
+ perf_begin(_sample_perf);
+
+ // read the high and low byte distance registers
+ uint8_t distance_reg = LL40LS_DISTHIGH_REG;
+ ret = transfer(&distance_reg, 1, &val[0], sizeof(val));
+
+ if (ret < 0) {
+ log("error reading from sensor: %d", ret);
+ perf_count(_comms_errors);
+ perf_end(_sample_perf);
+ return ret;
+ }
+
+ uint16_t distance = (val[0] << 8) | val[1];
+ float si_units = distance * 0.01f; /* cm to m */
+ struct range_finder_report report;
+
+ /* this should be fairly close to the end of the measurement, so the best approximation of the time */
+ report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
+ report.distance = si_units;
+ if (si_units > get_minimum_distance() && si_units < get_maximum_distance()) {
+ report.valid = 1;
+ }
+ else {
+ report.valid = 0;
+ }
+
+ /* publish it, if we are the primary */
+ if (_range_finder_topic >= 0) {
+ orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
+ }
+
+ if (_reports->force(&report)) {
+ perf_count(_buffer_overflows);
+ }
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ ret = OK;
+
+ perf_end(_sample_perf);
+ return ret;
+}
+
+void
+LL40LS::start()
+{
+ /* reset the report ring and state machine */
+ _collect_phase = false;
+ _reports->flush();
+
+ /* schedule a cycle to start things */
+ work_queue(HPWORK, &_work, (worker_t)&LL40LS::cycle_trampoline, this, 1);
+
+ /* notify about state change */
+ struct subsystem_info_s info = {
+ true,
+ true,
+ true,
+ SUBSYSTEM_TYPE_RANGEFINDER
+ };
+ static orb_advert_t pub = -1;
+
+ if (pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), pub, &info);
+
+ } else {
+ pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ }
+}
+
+void
+LL40LS::stop()
+{
+ work_cancel(HPWORK, &_work);
+}
+
+void
+LL40LS::cycle_trampoline(void *arg)
+{
+ LL40LS *dev = (LL40LS *)arg;
+
+ dev->cycle();
+}
+
+void
+LL40LS::cycle()
+{
+ /* collection phase? */
+ if (_collect_phase) {
+
+ /* perform collection */
+ if (OK != collect()) {
+ log("collection error");
+ /* restart the measurement state machine */
+ start();
+ return;
+ }
+
+ /* next phase is measurement */
+ _collect_phase = false;
+
+ /*
+ * Is there a collect->measure gap?
+ */
+ if (_measure_ticks > USEC2TICK(LL40LS_CONVERSION_INTERVAL)) {
+
+ /* schedule a fresh cycle call when we are ready to measure again */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&LL40LS::cycle_trampoline,
+ this,
+ _measure_ticks - USEC2TICK(LL40LS_CONVERSION_INTERVAL));
+
+ return;
+ }
+ }
+
+ /* measurement phase */
+ if (OK != measure()) {
+ log("measure error");
+ }
+
+ /* next phase is collection */
+ _collect_phase = true;
+
+ /* schedule a fresh cycle call when the measurement is done */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&LL40LS::cycle_trampoline,
+ this,
+ USEC2TICK(LL40LS_CONVERSION_INTERVAL));
+}
+
+void
+LL40LS::print_info()
+{
+ perf_print_counter(_sample_perf);
+ perf_print_counter(_comms_errors);
+ perf_print_counter(_buffer_overflows);
+ printf("poll interval: %u ticks\n", _measure_ticks);
+ _reports->print_info("report queue");
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace ll40ls
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+const int ERROR = -1;
+
+LL40LS *g_dev;
+
+void start();
+void stop();
+void test();
+void reset();
+void info();
+
+/**
+ * Start the driver.
+ */
+void
+start()
+{
+ int fd;
+
+ if (g_dev != nullptr) {
+ errx(1, "already started");
+ }
+
+ /* create the driver */
+ g_dev = new LL40LS(LL40LS_BUS);
+
+ if (g_dev == nullptr) {
+ goto fail;
+ }
+
+ if (OK != g_dev->init()) {
+ goto fail;
+ }
+
+ /* set the poll rate to default, starts automatic data collection */
+ fd = open(LL40LS_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ goto fail;
+ }
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
+ goto fail;
+ }
+
+ exit(0);
+
+fail:
+
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+ }
+
+ errx(1, "driver start failed");
+}
+
+/**
+ * Stop the driver
+ */
+void stop()
+{
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+
+ } else {
+ errx(1, "driver not running");
+ }
+
+ exit(0);
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ */
+void
+test()
+{
+ struct range_finder_report report;
+ ssize_t sz;
+ int ret;
+
+ int fd = open(LL40LS_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ err(1, "%s open failed (try 'll40ls start' if the driver is not running", LL40LS_DEVICE_PATH);
+ }
+
+ /* do a simple demand read */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report)) {
+ err(1, "immediate read failed");
+ }
+
+ warnx("single read");
+ warnx("measurement: %0.2f m", (double)report.distance);
+ warnx("time: %lld", report.timestamp);
+
+ /* start the sensor polling at 2Hz */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
+ errx(1, "failed to set 2Hz poll rate");
+ }
+
+ /* read the sensor 5x and report each value */
+ for (unsigned i = 0; i < 5; i++) {
+ struct pollfd fds;
+
+ /* wait for data to be ready */
+ fds.fd = fd;
+ fds.events = POLLIN;
+ ret = poll(&fds, 1, 2000);
+
+ if (ret != 1) {
+ errx(1, "timed out waiting for sensor data");
+ }
+
+ /* now go get it */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report)) {
+ err(1, "periodic read failed");
+ }
+
+ warnx("periodic read %u", i);
+ warnx("measurement: %0.3f", (double)report.distance);
+ warnx("time: %lld", report.timestamp);
+ }
+
+ /* reset the sensor polling to default rate */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
+ errx(1, "failed to set default poll rate");
+ }
+
+ errx(0, "PASS");
+}
+
+/**
+ * Reset the driver.
+ */
+void
+reset()
+{
+ int fd = open(LL40LS_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ err(1, "failed ");
+ }
+
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
+ err(1, "driver reset failed");
+ }
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
+ err(1, "driver poll restart failed");
+ }
+
+ exit(0);
+}
+
+/**
+ * Print a little info about the driver.
+ */
+void
+info()
+{
+ if (g_dev == nullptr) {
+ errx(1, "driver not running");
+ }
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ exit(0);
+}
+
+} // namespace
+
+int
+ll40ls_main(int argc, char *argv[])
+{
+ /*
+ * Start/load the driver.
+ */
+ if (!strcmp(argv[1], "start")) {
+ ll40ls::start();
+ }
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop")) {
+ ll40ls::stop();
+ }
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test")) {
+ ll40ls::test();
+ }
+
+ /*
+ * Reset the driver.
+ */
+ if (!strcmp(argv[1], "reset")) {
+ ll40ls::reset();
+ }
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
+ ll40ls::info();
+ }
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
+}
diff --git a/src/drivers/ll40ls/module.mk b/src/drivers/ll40ls/module.mk
new file mode 100644
index 000000000..fb627afee
--- /dev/null
+++ b/src/drivers/ll40ls/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2013 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.
+#
+############################################################################
+
+#
+# Makefile to build the PulsedLight Lidar-Lite driver.
+#
+
+MODULE_COMMAND = ll40ls
+
+SRCS = ll40ls.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 8a14aca4b..ff0eda60b 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -52,6 +52,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <getopt.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@@ -68,6 +69,7 @@
#include <board_config.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
+#include <lib/conversion/rotation.h>
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -75,12 +77,17 @@
#endif
static const int ERROR = -1;
+// enable this to debug the buggy lsm303d sensor in very early
+// prototype pixhawk boards
+#define CHECK_EXTREMES 0
+
/* SPI protocol address bits */
#define DIR_READ (1<<7)
#define DIR_WRITE (0<<7)
#define ADDR_INCREMENT (1<<6)
#define LSM303D_DEVICE_PATH_ACCEL "/dev/lsm303d_accel"
+#define LSM303D_DEVICE_PATH_ACCEL_EXT "/dev/lsm303d_accel_ext"
#define LSM303D_DEVICE_PATH_MAG "/dev/lsm303d_mag"
/* register addresses: A: accel, M: mag, T: temp */
@@ -216,7 +223,7 @@ class LSM303D_mag;
class LSM303D : public device::SPI
{
public:
- LSM303D(int bus, const char* path, spi_dev_e device);
+ LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rotation);
virtual ~LSM303D();
virtual int init();
@@ -305,7 +312,8 @@ private:
uint64_t _last_log_us;
uint64_t _last_log_sync_us;
uint64_t _last_log_reg_us;
- uint64_t _last_log_alarm_us;
+ uint64_t _last_log_alarm_us;
+ enum Rotation _rotation;
/**
* Start automatic measurement.
@@ -485,7 +493,7 @@ private:
};
-LSM303D::LSM303D(int bus, const char* path, spi_dev_e device) :
+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)),
_call_accel_interval(0),
@@ -519,8 +527,11 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device) :
_last_log_us(0),
_last_log_sync_us(0),
_last_log_reg_us(0),
- _last_log_alarm_us(0)
+ _last_log_alarm_us(0),
+ _rotation(rotation)
{
+ _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LSM303D;
+
// enable debug() calls
_debug_enabled = true;
@@ -841,7 +852,9 @@ LSM303D::read(struct file *filp, char *buffer, size_t buflen)
*/
while (count--) {
if (_accel_reports->get(arb)) {
+#if CHECK_EXTREMES
check_extremes(arb);
+#endif
ret += sizeof(*arb);
arb++;
}
@@ -1544,6 +1557,9 @@ LSM303D::measure()
accel_report.y = _accel_filter_y.apply(y_in_new);
accel_report.z = _accel_filter_z.apply(z_in_new);
+ // apply user specified rotation
+ rotate_3f(_rotation, accel_report.x, accel_report.y, accel_report.z);
+
accel_report.scaling = _accel_range_scale;
accel_report.range_m_s2 = _accel_range_m_s2;
@@ -1628,6 +1644,9 @@ LSM303D::mag_measure()
mag_report.scaling = _mag_range_scale;
mag_report.range_ga = (float)_mag_range_ga;
+ // apply user specified rotation
+ rotate_3f(_rotation, mag_report.x, mag_report.y, mag_report.z);
+
_mag_reports->force(&mag_report);
/* XXX please check this poll_notify, is it the right one? */
@@ -1801,26 +1820,34 @@ namespace lsm303d
LSM303D *g_dev;
-void start();
+void start(bool external_bus, enum Rotation rotation);
void test();
void reset();
void info();
void regdump();
void logging();
+void usage();
/**
* Start the driver.
*/
void
-start()
+start(bool external_bus, enum Rotation rotation)
{
int fd, fd_mag;
-
if (g_dev != nullptr)
errx(0, "already started");
/* create the driver */
- g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
+ if (external_bus) {
+ #ifdef PX4_SPI_BUS_EXT
+ g_dev = new LSM303D(PX4_SPI_BUS_EXT, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_EXT_ACCEL_MAG, rotation);
+ #else
+ errx(0, "External SPI not available");
+ #endif
+ } else {
+ g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG, rotation);
+ }
if (g_dev == nullptr) {
warnx("failed instantiating LSM303D obj");
@@ -2016,47 +2043,76 @@ logging()
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'info', 'test', 'reset', 'regdump', 'logging'");
+ warnx("options:");
+ warnx(" -X (external bus)");
+ warnx(" -R rotation");
+}
} // namespace
int
lsm303d_main(int argc, char *argv[])
{
+ bool external_bus = false;
+ int ch;
+ enum Rotation rotation = ROTATION_NONE;
+
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc, argv, "XR:")) != EOF) {
+ switch (ch) {
+ case 'X':
+ external_bus = true;
+ break;
+ case 'R':
+ rotation = (enum Rotation)atoi(optarg);
+ break;
+ default:
+ lsm303d::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
- lsm303d::start();
+ if (!strcmp(verb, "start"))
+ lsm303d::start(external_bus, rotation);
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
+ if (!strcmp(verb, "test"))
lsm303d::test();
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
+ if (!strcmp(verb, "reset"))
lsm303d::reset();
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info"))
+ if (!strcmp(verb, "info"))
lsm303d::info();
/*
* dump device registers
*/
- if (!strcmp(argv[1], "regdump"))
+ if (!strcmp(verb, "regdump"))
lsm303d::regdump();
/*
* dump device registers
*/
- if (!strcmp(argv[1], "logging"))
+ if (!strcmp(verb, "logging"))
lsm303d::logging();
errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info', 'logging' or 'regdump'");
diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp
index 5adb8cf69..beb6c8e35 100644
--- a/src/drivers/mb12xx/mb12xx.cpp
+++ b/src/drivers/mb12xx/mb12xx.cpp
@@ -74,6 +74,7 @@
/* Configuration Constants */
#define MB12XX_BUS PX4_I2C_BUS_EXPANSION
#define MB12XX_BASEADDR 0x70 /* 7-bit address. 8-bit address is 0xE0 */
+#define MB12XX_DEVICE_PATH "/dev/mb12xx"
/* MB12xx Registers addresses */
@@ -124,6 +125,7 @@ private:
bool _sensor_ok;
int _measure_ticks;
bool _collect_phase;
+ int _class_instance;
orb_advert_t _range_finder_topic;
@@ -187,13 +189,14 @@ private:
extern "C" __EXPORT int mb12xx_main(int argc, char *argv[]);
MB12XX::MB12XX(int bus, int address) :
- I2C("MB12xx", RANGE_FINDER_DEVICE_PATH, bus, address, 100000),
+ I2C("MB12xx", MB12XX_DEVICE_PATH, bus, address, 100000),
_min_distance(MB12XX_MIN_DISTANCE),
_max_distance(MB12XX_MAX_DISTANCE),
_reports(nullptr),
_sensor_ok(false),
_measure_ticks(0),
_collect_phase(false),
+ _class_instance(-1),
_range_finder_topic(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "mb12xx_read")),
_comms_errors(perf_alloc(PC_COUNT, "mb12xx_comms_errors")),
@@ -215,6 +218,15 @@ MB12XX::~MB12XX()
if (_reports != nullptr) {
delete _reports;
}
+
+ if (_class_instance != -1) {
+ unregister_class_devname(RANGE_FINDER_DEVICE_PATH, _class_instance);
+ }
+
+ // free perf counters
+ perf_free(_sample_perf);
+ perf_free(_comms_errors);
+ perf_free(_buffer_overflows);
}
int
@@ -234,13 +246,18 @@ MB12XX::init()
goto out;
}
- /* get a publish handle on the range finder topic */
- struct range_finder_report zero_report;
- memset(&zero_report, 0, sizeof(zero_report));
- _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &zero_report);
+ _class_instance = register_class_devname(RANGE_FINDER_DEVICE_PATH);
- if (_range_finder_topic < 0) {
- debug("failed to create sensor_range_finder object. Did you start uOrb?");
+ if (_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* get a publish handle on the range finder topic */
+ struct range_finder_report rf_report;
+ measure();
+ _reports->get(&rf_report);
+ _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &rf_report);
+
+ if (_range_finder_topic < 0) {
+ debug("failed to create sensor_range_finder object. Did you start uOrb?");
+ }
}
ret = OK;
@@ -505,8 +522,10 @@ MB12XX::collect()
report.distance = si_units;
report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
- /* publish it */
- orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
+ /* publish it, if we are the primary */
+ if (_range_finder_topic >= 0) {
+ orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
+ }
if (_reports->force(&report)) {
perf_count(_buffer_overflows);
@@ -665,7 +684,7 @@ start()
}
/* set the poll rate to default, starts automatic data collection */
- fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
+ fd = open(MB12XX_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
goto fail;
@@ -715,10 +734,10 @@ test()
ssize_t sz;
int ret;
- int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
+ int fd = open(MB12XX_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
- err(1, "%s open failed (try 'mb12xx start' if the driver is not running", RANGE_FINDER_DEVICE_PATH);
+ err(1, "%s open failed (try 'mb12xx start' if the driver is not running", MB12XX_DEVICE_PATH);
}
/* do a simple demand read */
@@ -776,7 +795,7 @@ test()
void
reset()
{
- int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
+ int fd = open(MB12XX_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
err(1, "failed ");
diff --git a/src/drivers/mb12xx/module.mk b/src/drivers/mb12xx/module.mk
index 4e00ada02..d751e93e4 100644
--- a/src/drivers/mb12xx/module.mk
+++ b/src/drivers/mb12xx/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = mb12xx
SRCS = mb12xx.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
index c0f3c28e0..07611f903 100644
--- a/src/drivers/meas_airspeed/meas_airspeed.cpp
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -225,7 +225,10 @@ MEASAirspeed::collect()
// correct for 5V rail voltage if possible
voltage_correction(diff_press_pa_raw, temperature);
- float diff_press_pa = fabsf(diff_press_pa_raw - _diff_pres_offset);
+ // the raw value still should be compensated for the known offset
+ diff_press_pa_raw -= _diff_pres_offset;
+
+ float diff_press_pa = fabsf(diff_press_pa_raw);
/*
note that we return both the absolute value with offset
@@ -265,7 +268,6 @@ MEASAirspeed::collect()
}
report.differential_pressure_raw_pa = diff_press_pa_raw;
- report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
if (_airspeed_pub > 0 && !(_pub_blocked)) {
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index 5954c40da..3996b76a6 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -131,8 +131,8 @@ public:
int set_motor_count(unsigned count);
int set_motor_test(bool motortest);
int set_overrideSecurityChecks(bool overrideSecurityChecks);
- int set_px4mode(int px4mode);
- int set_frametype(int frametype);
+ void set_px4mode(int px4mode);
+ void set_frametype(int frametype);
unsigned int mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C);
private:
@@ -222,15 +222,15 @@ MK::MK(int bus, const char *_device_path) :
_task(-1),
_t_actuators(-1),
_t_actuator_armed(-1),
+ _motor(-1),
+ _px4mode(MAPPING_MK),
+ _frametype(FRAME_PLUS),
_t_outputs(0),
_t_esc_status(0),
_num_outputs(0),
+ _primary_pwm_device(false),
_motortest(false),
_overrideSecurityChecks(false),
- _motor(-1),
- _px4mode(MAPPING_MK),
- _frametype(FRAME_PLUS),
- _primary_pwm_device(false),
_task_should_exit(false),
_armed(false),
_mixers(nullptr)
@@ -330,13 +330,13 @@ MK::set_update_rate(unsigned rate)
return OK;
}
-int
+void
MK::set_px4mode(int px4mode)
{
_px4mode = px4mode;
}
-int
+void
MK::set_frametype(int frametype)
{
_frametype = frametype;
@@ -440,9 +440,6 @@ MK::scaling(float val, float inMin, float inMax, float outMin, float outMax)
void
MK::task_main()
{
- long update_rate_in_us = 0;
- float tmpVal = 0;
-
/*
* Subscribe to the appropriate PWM output topic based on whether we are the
* primary PWM output or not.
@@ -483,7 +480,6 @@ MK::task_main()
/* handle update rate changes */
if (_current_update_rate != _update_rate) {
int update_rate_in_ms = int(1000 / _update_rate);
- update_rate_in_us = long(1000000 / _update_rate);
/* reject faster than 500 Hz updates */
if (update_rate_in_ms < 2) {
@@ -735,7 +731,6 @@ MK::mk_servo_set(unsigned int chan, short val)
_retries = 0;
uint8_t result[3] = { 0, 0, 0 };
uint8_t msg[2] = { 0, 0 };
- uint8_t rod = 0;
uint8_t bytesToSendBL2 = 2;
tmpVal = val;
@@ -824,7 +819,7 @@ MK::mk_servo_set(unsigned int chan, short val)
if (debugCounter == 2000) {
debugCounter = 0;
- for (int i = 0; i < _num_outputs; i++) {
+ for (unsigned int i = 0; i < _num_outputs; i++) {
if (Motor[i].State & MOTOR_STATE_PRESENT_MASK) {
fprintf(stderr, "[mkblctrl] #%i:\tVer: %i\tVal: %i\tCurr: %i\tMaxPWM: %i\tTemp: %i\tState: %i\n", i, Motor[i].Version, Motor[i].SetPoint, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature, Motor[i].State);
}
@@ -1169,7 +1164,7 @@ mk_new_mode(int update_rate, int motorcount, bool motortest, int px4mode, int fr
}
int
-mk_start(unsigned motors, char *device_path)
+mk_start(unsigned motors, const char *device_path)
{
int ret;
@@ -1228,7 +1223,7 @@ mkblctrl_main(int argc, char *argv[])
bool overrideSecurityChecks = false;
bool showHelp = false;
bool newMode = false;
- char *devicepath = "";
+ const char *devicepath = "";
/*
* optional parameters
diff --git a/src/drivers/mkblctrl/module.mk b/src/drivers/mkblctrl/module.mk
index 3ac263b00..6daa14aa5 100644
--- a/src/drivers/mkblctrl/module.mk
+++ b/src/drivers/mkblctrl/module.mk
@@ -37,6 +37,8 @@
MODULE_COMMAND = mkblctrl
-SRCS = mkblctrl.cpp
+SRCS = mkblctrl.cpp
INCLUDE_DIRS += $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 10966e2d0..25fd7d8a8 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -55,6 +55,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <getopt.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@@ -71,12 +72,15 @@
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
+#include <lib/conversion/rotation.h>
#define DIR_READ 0x80
#define DIR_WRITE 0x00
#define MPU_DEVICE_PATH_ACCEL "/dev/mpu6000_accel"
#define MPU_DEVICE_PATH_GYRO "/dev/mpu6000_gyro"
+#define MPU_DEVICE_PATH_ACCEL_EXT "/dev/mpu6000_accel_ext"
+#define MPU_DEVICE_PATH_GYRO_EXT "/dev/mpu6000_gyro_ext"
// MPU 6000 registers
#define MPUREG_WHOAMI 0x75
@@ -177,7 +181,7 @@ class MPU6000_gyro;
class MPU6000 : public device::SPI
{
public:
- MPU6000(int bus, spi_dev_e device);
+ MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device, enum Rotation rotation);
virtual ~MPU6000();
virtual int init();
@@ -232,6 +236,8 @@ private:
math::LowPassFilter2p _gyro_filter_y;
math::LowPassFilter2p _gyro_filter_z;
+ enum Rotation _rotation;
+
/**
* Start automatic measurement.
*/
@@ -345,7 +351,7 @@ private:
class MPU6000_gyro : public device::CDev
{
public:
- MPU6000_gyro(MPU6000 *parent);
+ MPU6000_gyro(MPU6000 *parent, const char *path);
~MPU6000_gyro();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
@@ -368,9 +374,9 @@ private:
/** driver 'main' command */
extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); }
-MPU6000::MPU6000(int bus, spi_dev_e device) :
- SPI("MPU6000", MPU_DEVICE_PATH_ACCEL, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED),
- _gyro(new MPU6000_gyro(this)),
+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),
+ _gyro(new MPU6000_gyro(this, path_gyro)),
_product(0),
_call_interval(0),
_accel_reports(nullptr),
@@ -391,7 +397,8 @@ MPU6000::MPU6000(int bus, spi_dev_e device) :
_accel_filter_z(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
_gyro_filter_x(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ),
_gyro_filter_y(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ),
- _gyro_filter_z(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ)
+ _gyro_filter_z(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ),
+ _rotation(rotation)
{
// disable debug() calls
_debug_enabled = false;
@@ -557,7 +564,7 @@ void MPU6000::reset()
write_reg(MPUREG_USER_CTRL, BIT_I2C_IF_DIS);
irqrestore(state);
- up_udelay(1000);
+ usleep(1000);
// SAMPLE RATE
_set_sample_rate(_sample_rate);
@@ -679,7 +686,9 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz)
/*
choose next highest filter frequency available
*/
- if (frequency_hz <= 5) {
+ if (frequency_hz == 0) {
+ filter = BITS_DLPF_CFG_2100HZ_NOLPF;
+ } else if (frequency_hz <= 5) {
filter = BITS_DLPF_CFG_5HZ;
} else if (frequency_hz <= 10) {
filter = BITS_DLPF_CFG_10HZ;
@@ -935,10 +944,11 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
return _accel_filter_x.get_cutoff_freq();
case ACCELIOCSLOWPASS:
-
- // XXX decide on relationship of both filters
- // i.e. disable the on-chip filter
- //_set_dlpf_filter((uint16_t)arg);
+ if (arg == 0) {
+ // allow disabling of on-chip filter using
+ // zero as desired filter frequency
+ _set_dlpf_filter(0);
+ }
_accel_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_accel_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_accel_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
@@ -1022,8 +1032,11 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
_gyro_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_gyro_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_gyro_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
- // XXX check relation to the internal lowpass
- //_set_dlpf_filter((uint16_t)arg);
+ if (arg == 0) {
+ // allow disabling of on-chip filter using 0
+ // as desired frequency
+ _set_dlpf_filter(0);
+ }
return OK;
case GYROIOCSSCALE:
@@ -1308,6 +1321,9 @@ MPU6000::measure()
arb.y = _accel_filter_y.apply(y_in_new);
arb.z = _accel_filter_z.apply(z_in_new);
+ // apply user specified rotation
+ rotate_3f(_rotation, arb.x, arb.y, arb.z);
+
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
@@ -1326,6 +1342,9 @@ MPU6000::measure()
grb.y = _gyro_filter_y.apply(y_gyro_in_new);
grb.z = _gyro_filter_z.apply(z_gyro_in_new);
+ // apply user specified rotation
+ rotate_3f(_rotation, grb.x, grb.y, grb.z);
+
grb.scaling = _gyro_range_scale;
grb.range_rad_s = _gyro_range_rad_s;
@@ -1379,8 +1398,8 @@ MPU6000::print_info()
_gyro_reports->print_info("gyro queue");
}
-MPU6000_gyro::MPU6000_gyro(MPU6000 *parent) :
- CDev("MPU6000_gyro", MPU_DEVICE_PATH_GYRO),
+MPU6000_gyro::MPU6000_gyro(MPU6000 *parent, const char *path) :
+ CDev("MPU6000_gyro", path),
_parent(parent),
_gyro_topic(-1),
_gyro_class_instance(-1)
@@ -1436,36 +1455,49 @@ MPU6000_gyro::ioctl(struct file *filp, int cmd, unsigned long arg)
namespace mpu6000
{
-MPU6000 *g_dev;
+MPU6000 *g_dev_int; // on internal bus
+MPU6000 *g_dev_ext; // on external bus
-void start();
-void test();
-void reset();
-void info();
+void start(bool, enum Rotation);
+void test(bool);
+void reset(bool);
+void info(bool);
+void usage();
/**
* Start the driver.
*/
void
-start()
+start(bool external_bus, enum Rotation rotation)
{
int fd;
+ MPU6000 **g_dev_ptr = external_bus?&g_dev_ext:&g_dev_int;
+ const char *path_accel = external_bus?MPU_DEVICE_PATH_ACCEL_EXT:MPU_DEVICE_PATH_ACCEL;
+ const char *path_gyro = external_bus?MPU_DEVICE_PATH_GYRO_EXT:MPU_DEVICE_PATH_GYRO;
- if (g_dev != nullptr)
+ if (*g_dev_ptr != nullptr)
/* if already started, the still command succeeded */
errx(0, "already started");
/* create the driver */
- g_dev = new MPU6000(1 /* XXX magic number */, (spi_dev_e)PX4_SPIDEV_MPU);
+ if (external_bus) {
+#ifdef PX4_SPI_BUS_EXT
+ *g_dev_ptr = new MPU6000(PX4_SPI_BUS_EXT, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_EXT_MPU, rotation);
+#else
+ errx(0, "External SPI not available");
+#endif
+ } else {
+ *g_dev_ptr = new MPU6000(PX4_SPI_BUS_SENSORS, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_MPU, rotation);
+ }
- if (g_dev == nullptr)
+ if (*g_dev_ptr == nullptr)
goto fail;
- if (OK != g_dev->init())
+ if (OK != (*g_dev_ptr)->init())
goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
+ fd = open(path_accel, O_RDONLY);
if (fd < 0)
goto fail;
@@ -1478,9 +1510,9 @@ start()
exit(0);
fail:
- if (g_dev != nullptr) {
- delete g_dev;
- g_dev = nullptr;
+ if (*g_dev_ptr != nullptr) {
+ delete (*g_dev_ptr);
+ *g_dev_ptr = nullptr;
}
errx(1, "driver start failed");
@@ -1492,24 +1524,26 @@ fail:
* and automatic modes.
*/
void
-test()
+test(bool external_bus)
{
+ const char *path_accel = external_bus?MPU_DEVICE_PATH_ACCEL_EXT:MPU_DEVICE_PATH_ACCEL;
+ const char *path_gyro = external_bus?MPU_DEVICE_PATH_GYRO_EXT:MPU_DEVICE_PATH_GYRO;
accel_report a_report;
gyro_report g_report;
ssize_t sz;
/* get the driver */
- int fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
+ int fd = open(path_accel, O_RDONLY);
if (fd < 0)
err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)",
- MPU_DEVICE_PATH_ACCEL);
+ path_accel);
/* get the driver */
- int fd_gyro = open(MPU_DEVICE_PATH_GYRO, O_RDONLY);
+ int fd_gyro = open(path_gyro, O_RDONLY);
if (fd_gyro < 0)
- err(1, "%s open failed", MPU_DEVICE_PATH_GYRO);
+ err(1, "%s open failed", path_gyro);
/* reset to manual polling */
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0)
@@ -1557,7 +1591,7 @@ test()
/* XXX add poll-rate tests here too */
- reset();
+ reset(external_bus);
errx(0, "PASS");
}
@@ -1565,9 +1599,10 @@ test()
* Reset the driver.
*/
void
-reset()
+reset(bool external_bus)
{
- int fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
+ const char *path_accel = external_bus?MPU_DEVICE_PATH_ACCEL_EXT:MPU_DEVICE_PATH_ACCEL;
+ int fd = open(path_accel, O_RDONLY);
if (fd < 0)
err(1, "failed ");
@@ -1587,47 +1622,77 @@ reset()
* Print a little info about the driver.
*/
void
-info()
+info(bool external_bus)
{
- if (g_dev == nullptr)
+ MPU6000 **g_dev_ptr = external_bus?&g_dev_ext:&g_dev_int;
+ if (*g_dev_ptr == nullptr)
errx(1, "driver not running");
- printf("state @ %p\n", g_dev);
- g_dev->print_info();
+ printf("state @ %p\n", *g_dev_ptr);
+ (*g_dev_ptr)->print_info();
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'info', 'test', 'reset'");
+ warnx("options:");
+ warnx(" -X (external bus)");
+ warnx(" -R rotation");
+}
} // namespace
int
mpu6000_main(int argc, char *argv[])
{
+ bool external_bus = false;
+ int ch;
+ enum Rotation rotation = ROTATION_NONE;
+
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc, argv, "XR:")) != EOF) {
+ switch (ch) {
+ case 'X':
+ external_bus = true;
+ break;
+ case 'R':
+ rotation = (enum Rotation)atoi(optarg);
+ break;
+ default:
+ mpu6000::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
- mpu6000::start();
+ if (!strcmp(verb, "start"))
+ mpu6000::start(external_bus, rotation);
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
- mpu6000::test();
+ if (!strcmp(verb, "test"))
+ mpu6000::test(external_bus);
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
- mpu6000::reset();
+ if (!strcmp(verb, "reset"))
+ mpu6000::reset(external_bus);
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info"))
- mpu6000::info();
+ if (!strcmp(verb, "info"))
+ mpu6000::info(external_bus);
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
}
diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 2d85a5e0d..873fa62c4 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -50,6 +50,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <getopt.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
@@ -788,11 +789,12 @@ namespace ms5611
MS5611 *g_dev;
-void start();
+void start(bool external_bus);
void test();
void reset();
void info();
void calibrate(unsigned altitude);
+void usage();
/**
* MS5611 crc4 cribbed from the datasheet
@@ -845,7 +847,7 @@ crc4(uint16_t *n_prom)
* Start the driver.
*/
void
-start()
+start(bool external_bus)
{
int fd;
prom_u prom_buf;
@@ -858,7 +860,7 @@ start()
/* create the driver, try SPI first, fall back to I2C if unsuccessful */
if (MS5611_spi_interface != nullptr)
- interface = MS5611_spi_interface(prom_buf);
+ interface = MS5611_spi_interface(prom_buf, external_bus);
if (interface == nullptr && (MS5611_i2c_interface != nullptr))
interface = MS5611_i2c_interface(prom_buf);
@@ -1069,43 +1071,68 @@ calibrate(unsigned altitude)
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'info', 'test', 'test2', 'reset', 'calibrate'");
+ warnx("options:");
+ warnx(" -X (external bus)");
+}
+
} // namespace
int
ms5611_main(int argc, char *argv[])
{
+ bool external_bus = false;
+ int ch;
+
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc, argv, "X")) != EOF) {
+ switch (ch) {
+ case 'X':
+ external_bus = true;
+ break;
+ default:
+ ms5611::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
- ms5611::start();
+ if (!strcmp(verb, "start"))
+ ms5611::start(external_bus);
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
+ if (!strcmp(verb, "test"))
ms5611::test();
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
+ if (!strcmp(verb, "reset"))
ms5611::reset();
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info"))
+ if (!strcmp(verb, "info"))
ms5611::info();
/*
* Perform MSL pressure calibration given an altitude in metres
*/
- if (!strcmp(argv[1], "calibrate")) {
+ if (!strcmp(verb, "calibrate")) {
if (argc < 2)
errx(1, "missing altitude");
- long altitude = strtol(argv[2], nullptr, 10);
+ long altitude = strtol(argv[optind+1], nullptr, 10);
ms5611::calibrate(altitude);
}
diff --git a/src/drivers/ms5611/ms5611.h b/src/drivers/ms5611/ms5611.h
index 76fb84de8..f0b3fd61d 100644
--- a/src/drivers/ms5611/ms5611.h
+++ b/src/drivers/ms5611/ms5611.h
@@ -80,6 +80,6 @@ extern bool crc4(uint16_t *n_prom);
} /* namespace */
/* interface factories */
-extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf) weak_function;
+extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus) weak_function;
extern device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf) weak_function;
diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp
index 8759d16a1..5234ce8d6 100644
--- a/src/drivers/ms5611/ms5611_spi.cpp
+++ b/src/drivers/ms5611/ms5611_spi.cpp
@@ -62,7 +62,7 @@
#ifdef PX4_SPIDEV_BARO
-device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf);
+device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus);
class MS5611_SPI : public device::SPI
{
@@ -115,9 +115,17 @@ private:
};
device::Device *
-MS5611_spi_interface(ms5611::prom_u &prom_buf)
+MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus)
{
- return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
+ if (external_bus) {
+ #ifdef PX4_SPI_BUS_EXT
+ return new MS5611_SPI(PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_BARO, prom_buf);
+ #else
+ return nullptr;
+ #endif
+ } else {
+ return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
+ }
}
MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) :
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 8a4bfa18c..8cc1141aa 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -240,8 +240,6 @@ PX4FMU::PX4FMU() :
_pwm_alt_rate_channels(0),
_current_update_rate(0),
_task(-1),
- _control_subs({-1}),
- _poll_fds_num(0),
_armed_sub(-1),
_outputs_pub(-1),
_num_outputs(0),
@@ -252,10 +250,12 @@ PX4FMU::PX4FMU() :
_mixers(nullptr),
_groups_required(0),
_groups_subscribed(0),
- _failsafe_pwm({0}),
- _disarmed_pwm({0}),
- _num_failsafe_set(0),
- _num_disarmed_set(0)
+ _control_subs{-1},
+ _poll_fds_num(0),
+ _failsafe_pwm{0},
+ _disarmed_pwm{0},
+ _num_failsafe_set(0),
+ _num_disarmed_set(0)
{
for (unsigned i = 0; i < _max_actuators; i++) {
_min_pwm[i] = PWM_DEFAULT_MIN;
@@ -329,7 +329,7 @@ PX4FMU::init()
_task = task_spawn_cmd("fmuservo",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 1600,
(main_t)&PX4FMU::task_main_trampoline,
nullptr);
@@ -741,7 +741,7 @@ PX4FMU::task_main()
}
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
- if (_control_subs > 0) {
+ if (_control_subs[i] > 0) {
::close(_control_subs[i]);
_control_subs[i] = -1;
}
@@ -1784,7 +1784,7 @@ fmu_main(int argc, char *argv[])
}
if (!strcmp(verb, "id")) {
- char id[12];
+ uint8_t id[12];
(void)get_board_serial(id);
errx(0, "Board serial:\n %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X",
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 972f45148..7d78b0d27 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -72,6 +72,7 @@
#include <systemlib/systemlib.h>
#include <systemlib/scheduling_priorities.h>
#include <systemlib/param/param.h>
+#include <systemlib/circuit_breaker.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
@@ -197,8 +198,10 @@ public:
* Print IO status.
*
* Print all relevant IO status information
+ *
+ * @param extended_status Shows more verbose information (in particular RC config)
*/
- void print_status();
+ void print_status(bool extended_status);
/**
* Fetch and print debug console output.
@@ -1010,6 +1013,19 @@ PX4IO::task_main()
}
}
+ int32_t safety_param_val;
+ param_t safety_param = param_find("RC_FAILS_THR");
+
+ if (safety_param != PARAM_INVALID) {
+
+ param_get(safety_param, &safety_param_val);
+
+ if (safety_param_val == PX4IO_FORCE_SAFETY_MAGIC) {
+ /* disable IO safety if circuit breaker asked for it */
+ (void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, safety_param_val);
+ }
+ }
+
}
}
@@ -1367,7 +1383,7 @@ void
PX4IO::io_handle_battery(uint16_t vbatt, uint16_t ibatt)
{
/* only publish if battery has a valid minimum voltage */
- if (vbatt <= 3300) {
+ if (vbatt <= 4900) {
return;
}
@@ -1850,7 +1866,7 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
}
void
-PX4IO::print_status()
+PX4IO::print_status(bool extended_status)
{
/* basic configuration */
printf("protocol %u hardware %u bootloader %u buffer %uB crc 0x%04x%04x\n",
@@ -2013,19 +2029,21 @@ PX4IO::print_status()
printf("\n");
}
- for (unsigned i = 0; i < _max_rc_input; i++) {
- unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
- uint16_t options = io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_OPTIONS);
- printf("input %u min %u center %u max %u deadzone %u assigned %u options 0x%04x%s%s\n",
- i,
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MIN),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_CENTER),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MAX),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_DEADZONE),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_ASSIGNMENT),
- options,
- ((options & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) ? " ENABLED" : ""),
- ((options & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) ? " REVERSED" : ""));
+ if (extended_status) {
+ for (unsigned i = 0; i < _max_rc_input; i++) {
+ unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
+ uint16_t options = io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_OPTIONS);
+ printf("input %u min %u center %u max %u deadzone %u assigned %u options 0x%04x%s%s\n",
+ i,
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MIN),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_CENTER),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MAX),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_DEADZONE),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_ASSIGNMENT),
+ options,
+ ((options & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) ? " ENABLED" : ""),
+ ((options & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) ? " REVERSED" : ""));
+ }
}
printf("failsafe");
@@ -2853,7 +2871,7 @@ monitor(void)
if (g_dev != nullptr) {
printf("\033[2J\033[H"); /* move cursor home and clear screen */
- (void)g_dev->print_status();
+ (void)g_dev->print_status(false);
(void)g_dev->print_debug();
printf("\n\n\n[ Use 'px4io debug <N>' for more output. Hit <enter> three times to exit monitor mode ]\n");
@@ -3119,7 +3137,7 @@ px4io_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
printf("[px4io] loaded\n");
- g_dev->print_status();
+ g_dev->print_status(true);
exit(0);
}
diff --git a/src/drivers/px4io/px4io_i2c.cpp b/src/drivers/px4io/px4io_i2c.cpp
index 19776c40a..c57ddf65b 100644..100755
--- a/src/drivers/px4io/px4io_i2c.cpp
+++ b/src/drivers/px4io/px4io_i2c.cpp
@@ -79,7 +79,7 @@ device::Device
}
PX4IO_I2C::PX4IO_I2C(int bus, uint8_t address) :
- I2C("PX4IO_i2c", nullptr, bus, address, 320000)
+ I2C("PX4IO_i2c", nullptr, bus, address, 400000)
{
_retries = 3;
}
diff --git a/src/drivers/px4io/px4io_serial.cpp b/src/drivers/px4io/px4io_serial.cpp
index 3b210ac59..c39494fb0 100644
--- a/src/drivers/px4io/px4io_serial.cpp
+++ b/src/drivers/px4io/px4io_serial.cpp
@@ -639,7 +639,7 @@ PX4IO_serial::_do_interrupt()
if (_rx_dma_status == _dma_status_waiting) {
/* verify that the received packet is complete */
- int length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
+ size_t length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
if ((length < 1) || (length < PKT_SIZE(_dma_buffer))) {
perf_count(_pc_badidle);
diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp
index 28ec62356..d134c0246 100644
--- a/src/drivers/px4io/px4io_uploader.cpp
+++ b/src/drivers/px4io/px4io_uploader.cpp
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
#include <assert.h>
@@ -240,9 +241,9 @@ PX4IO_Uploader::upload(const char *filenames[])
close(_io_fd);
_io_fd = -1;
- // sleep for enough time for the IO chip to boot. This makes
- // forceupdate more reliably startup IO again after update
- up_udelay(100*1000);
+ // sleep for enough time for the IO chip to boot. This makes
+ // forceupdate more reliably startup IO again after update
+ up_udelay(100*1000);
return ret;
}
@@ -413,11 +414,17 @@ static int read_with_retry(int fd, void *buf, size_t n)
int
PX4IO_Uploader::program(size_t fw_size)
{
- uint8_t file_buf[PROG_MULTI_MAX];
+ uint8_t *file_buf;
ssize_t count;
int ret;
size_t sent = 0;
+ file_buf = (uint8_t *)malloc(PROG_MULTI_MAX);
+ if (!file_buf) {
+ log("Can't allocate program buffer");
+ return -ENOMEM;
+ }
+
log("programming %u bytes...", (unsigned)fw_size);
ret = lseek(_fw_fd, 0, SEEK_SET);
@@ -425,8 +432,8 @@ PX4IO_Uploader::program(size_t fw_size)
while (sent < fw_size) {
/* get more bytes to program */
size_t n = fw_size - sent;
- if (n > sizeof(file_buf)) {
- n = sizeof(file_buf);
+ if (n > PROG_MULTI_MAX) {
+ n = PROG_MULTI_MAX;
}
count = read_with_retry(_fw_fd, file_buf, n);
@@ -438,8 +445,10 @@ PX4IO_Uploader::program(size_t fw_size)
(int)errno);
}
- if (count == 0)
+ if (count == 0) {
+ free(file_buf);
return OK;
+ }
sent += count;
@@ -455,9 +464,12 @@ PX4IO_Uploader::program(size_t fw_size)
ret = get_sync(1000);
- if (ret != OK)
+ if (ret != OK) {
+ free(file_buf);
return ret;
+ }
}
+ free(file_buf);
return OK;
}
diff --git a/src/drivers/roboclaw/RoboClaw.cpp b/src/drivers/roboclaw/RoboClaw.cpp
index dd5e4d3e0..fdaa7f27b 100644
--- a/src/drivers/roboclaw/RoboClaw.cpp
+++ b/src/drivers/roboclaw/RoboClaw.cpp
@@ -182,7 +182,10 @@ float RoboClaw::getMotorPosition(e_motor motor)
return _motor1Position;
} else if (motor == MOTOR_2) {
return _motor2Position;
- }
+ } else {
+ warnx("Unknown motor value passed to RoboClaw::getMotorPosition");
+ return NAN;
+ }
}
float RoboClaw::getMotorSpeed(e_motor motor)
@@ -191,7 +194,10 @@ float RoboClaw::getMotorSpeed(e_motor motor)
return _motor1Speed;
} else if (motor == MOTOR_2) {
return _motor2Speed;
- }
+ } else {
+ warnx("Unknown motor value passed to RoboClaw::getMotorPosition");
+ return NAN;
+ }
}
int RoboClaw::setMotorSpeed(e_motor motor, float value)
diff --git a/src/drivers/sf0x/module.mk b/src/drivers/sf0x/module.mk
index dc93a90e7..dc2c66d56 100644
--- a/src/drivers/sf0x/module.mk
+++ b/src/drivers/sf0x/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = sf0x
SRCS = sf0x.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp
index 9109af14f..bca1715fa 100644
--- a/src/drivers/sf0x/sf0x.cpp
+++ b/src/drivers/sf0x/sf0x.cpp
@@ -616,7 +616,7 @@ SF0X::collect()
}
}
- debug("val (float): %8.4f, raw: %s, valid: %s\n", si_units, _linebuf, ((valid) ? "OK" : "NO"));
+ debug("val (float): %8.4f, raw: %s, valid: %s\n", (double)si_units, _linebuf, ((valid) ? "OK" : "NO"));
/* done with this chunk, resetting - even if invalid */
_linebuf_index = 0;