aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/airspeed/airspeed.cpp9
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c10
-rw-r--r--src/drivers/blinkm/blinkm.cpp103
-rw-r--r--src/drivers/bma180/bma180.cpp2
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h (renamed from src/drivers/boards/px4fmu/px4fmu_internal.h)93
-rw-r--r--src/drivers/boards/px4fmu-v1/module.mk (renamed from src/drivers/boards/px4fmu/module.mk)0
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_can.c (renamed from src/drivers/boards/px4fmu/px4fmu_can.c)2
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_init.c (renamed from src/drivers/boards/px4fmu/px4fmu_init.c)2
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_led.c (renamed from src/drivers/boards/px4fmu/px4fmu_led.c)21
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_pwm_servo.c (renamed from src/drivers/boards/px4fmu/px4fmu_pwm_servo.c)10
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_spi.c (renamed from src/drivers/boards/px4fmu/px4fmu_spi.c)2
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_usb.c (renamed from src/drivers/boards/px4fmu/px4fmu_usb.c)2
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h192
-rw-r--r--src/drivers/boards/px4fmu-v2/module.mk10
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_init.c262
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_led.c97
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_can.c144
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c105
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_spi.c141
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_usb.c108
-rw-r--r--src/drivers/boards/px4io-v1/board_config.h (renamed from src/drivers/boards/px4io/px4io_internal.h)12
-rw-r--r--src/drivers/boards/px4io-v1/module.mk (renamed from src/drivers/boards/px4io/module.mk)0
-rw-r--r--src/drivers/boards/px4io-v1/px4io_init.c (renamed from src/drivers/boards/px4io/px4io_init.c)2
-rw-r--r--src/drivers/boards/px4io-v1/px4io_pwm_servo.c (renamed from src/drivers/boards/px4io/px4io_pwm_servo.c)0
-rw-r--r--src/drivers/boards/px4io-v2/board_config.h138
-rw-r--r--src/drivers/boards/px4io-v2/module.mk6
-rw-r--r--src/drivers/boards/px4io-v2/px4iov2_init.c162
-rw-r--r--src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c123
-rw-r--r--src/drivers/drv_gpio.h42
-rw-r--r--src/drivers/drv_led.h3
-rw-r--r--src/drivers/drv_mag.h26
-rw-r--r--src/drivers/drv_rgbled.h126
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp2
-rw-r--r--src/drivers/hil/hil.cpp1
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp143
-rw-r--r--src/drivers/hott/messages.cpp2
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp217
-rw-r--r--src/drivers/led/led.cpp12
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp1659
-rw-r--r--src/drivers/lsm303d/module.mk8
-rw-r--r--src/drivers/mb12xx/mb12xx.cpp4
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp2
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp56
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp91
-rw-r--r--src/drivers/ms5611/module.mk2
-rw-r--r--src/drivers/ms5611/ms5611.cpp407
-rw-r--r--src/drivers/ms5611/ms5611.h85
-rw-r--r--src/drivers/ms5611/ms5611_i2c.cpp278
-rw-r--r--src/drivers/ms5611/ms5611_spi.cpp273
-rw-r--r--src/drivers/px4fmu/fmu.cpp288
-rw-r--r--src/drivers/px4io/module.mk7
-rw-r--r--src/drivers/px4io/px4io.cpp819
-rw-r--r--src/drivers/px4io/px4io_i2c.cpp169
-rw-r--r--src/drivers/px4io/px4io_serial.cpp673
-rw-r--r--src/drivers/px4io/px4io_uploader.cpp (renamed from src/drivers/px4io/uploader.cpp)75
-rw-r--r--src/drivers/rgbled/module.mk6
-rw-r--r--src/drivers/rgbled/rgbled.cpp566
-rw-r--r--src/drivers/stm32/adc/adc.cpp14
-rw-r--r--src/drivers/stm32/drv_hrt.c2
-rw-r--r--src/drivers/stm32/tone_alarm/tone_alarm.cpp24
60 files changed, 6890 insertions, 950 deletions
diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp
index 5a8157deb..277d8249a 100644
--- a/src/drivers/airspeed/airspeed.cpp
+++ b/src/drivers/airspeed/airspeed.cpp
@@ -146,7 +146,14 @@ out:
int
Airspeed::probe()
{
- return measure();
+ /* on initial power up the device needs more than one retry
+ for detection. Once it is running then retries aren't
+ needed
+ */
+ _retries = 4;
+ int ret = measure();
+ _retries = 0;
+ return ret;
}
int
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index 735bdb41a..b88f61ce8 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -53,8 +53,10 @@
#include <sys/prctl.h>
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/safety.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <systemlib/systemlib.h>
@@ -243,16 +245,14 @@ int ardrone_interface_thread_main(int argc, char *argv[])
int led_counter = 0;
/* declare and safely initialize all structs */
- struct vehicle_status_s state;
- memset(&state, 0, sizeof(state));
struct actuator_controls_s actuator_controls;
memset(&actuator_controls, 0, sizeof(actuator_controls));
struct actuator_armed_s armed;
+ //XXX is this necessairy?
armed.armed = false;
/* subscribe to attitude, motor setpoints and system state */
int actuator_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
- int state_sub = orb_subscribe(ORB_ID(vehicle_status));
int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
printf("[ardrone_interface] Motors initialized - ready.\n");
@@ -322,8 +322,6 @@ int ardrone_interface_thread_main(int argc, char *argv[])
} else {
/* MAIN OPERATION MODE */
- /* get a local copy of the vehicle state */
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
/* get a local copy of the actuator controls */
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_controls_sub, &actuator_controls);
orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 3fabfd9a5..490002254 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -92,9 +92,6 @@
#include <nuttx/config.h>
-#include <arch/board/board.h>
-#include <drivers/device/i2c.h>
-
#include <sys/types.h>
#include <stdint.h>
#include <string.h>
@@ -104,18 +101,23 @@
#include <unistd.h>
#include <stdio.h>
#include <ctype.h>
-
-#include <drivers/drv_blinkm.h>
+#include <poll.h>
#include <nuttx/wqueue.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
-
#include <systemlib/systemlib.h>
-#include <poll.h>
+
+#include <board_config.h>
+
+#include <drivers/device/i2c.h>
+#include <drivers/drv_blinkm.h>
+
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/vehicle_gps_position.h>
static const float MAX_CELL_VOLTAGE = 4.3f;
@@ -375,7 +377,9 @@ BlinkM::led()
{
static int vehicle_status_sub_fd;
+ static int vehicle_control_mode_sub_fd;
static int vehicle_gps_position_sub_fd;
+ static int actuator_armed_sub_fd;
static int num_of_cells = 0;
static int detected_cells_runcount = 0;
@@ -386,6 +390,8 @@ BlinkM::led()
static int led_interval = 1000;
static int no_data_vehicle_status = 0;
+ static int no_data_vehicle_control_mode = 0;
+ static int no_data_actuator_armed = 0;
static int no_data_vehicle_gps_position = 0;
static bool topic_initialized = false;
@@ -398,6 +404,12 @@ BlinkM::led()
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
orb_set_interval(vehicle_status_sub_fd, 1000);
+ vehicle_control_mode_sub_fd = orb_subscribe(ORB_ID(vehicle_control_mode));
+ orb_set_interval(vehicle_control_mode_sub_fd, 1000);
+
+ actuator_armed_sub_fd = orb_subscribe(ORB_ID(actuator_armed));
+ orb_set_interval(actuator_armed_sub_fd, 1000);
+
vehicle_gps_position_sub_fd = orb_subscribe(ORB_ID(vehicle_gps_position));
orb_set_interval(vehicle_gps_position_sub_fd, 1000);
@@ -452,12 +464,16 @@ BlinkM::led()
if (led_thread_runcount == 15) {
/* obtained data for the first file descriptor */
struct vehicle_status_s vehicle_status_raw;
+ struct vehicle_control_mode_s vehicle_control_mode;
+ struct actuator_armed_s actuator_armed;
struct vehicle_gps_position_s vehicle_gps_position_raw;
memset(&vehicle_status_raw, 0, sizeof(vehicle_status_raw));
memset(&vehicle_gps_position_raw, 0, sizeof(vehicle_gps_position_raw));
bool new_data_vehicle_status;
+ bool new_data_vehicle_control_mode;
+ bool new_data_actuator_armed;
bool new_data_vehicle_gps_position;
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
@@ -471,6 +487,28 @@ BlinkM::led()
no_data_vehicle_status = 3;
}
+ orb_check(vehicle_control_mode_sub_fd, &new_data_vehicle_control_mode);
+
+ if (new_data_vehicle_control_mode) {
+ orb_copy(ORB_ID(vehicle_control_mode), vehicle_control_mode_sub_fd, &vehicle_control_mode);
+ no_data_vehicle_control_mode = 0;
+ } else {
+ no_data_vehicle_control_mode++;
+ if(no_data_vehicle_control_mode >= 3)
+ no_data_vehicle_control_mode = 3;
+ }
+
+ orb_check(actuator_armed_sub_fd, &new_data_actuator_armed);
+
+ if (new_data_actuator_armed) {
+ orb_copy(ORB_ID(actuator_armed), actuator_armed_sub_fd, &actuator_armed);
+ no_data_actuator_armed = 0;
+ } else {
+ no_data_actuator_armed++;
+ if(no_data_actuator_armed >= 3)
+ no_data_actuator_armed = 3;
+ }
+
orb_check(vehicle_gps_position_sub_fd, &new_data_vehicle_gps_position);
if (new_data_vehicle_gps_position) {
@@ -486,19 +524,19 @@ BlinkM::led()
/* get number of used satellites in navigation */
num_of_used_sats = 0;
- //for(int satloop=0; satloop<20; satloop++) {
- for(int satloop=0; satloop<sizeof(vehicle_gps_position_raw.satellite_used); satloop++) {
+
+ 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++;
}
}
- if(new_data_vehicle_status || no_data_vehicle_status < 3){
- if(num_of_cells == 0) {
+ if (new_data_vehicle_status || no_data_vehicle_status < 3) {
+ if (num_of_cells == 0) {
/* looking for lipo cells that are connected */
printf("<blinkm> checking cells\n");
for(num_of_cells = 2; num_of_cells < 7; num_of_cells++) {
- if(vehicle_status_raw.voltage_battery < num_of_cells * MAX_CELL_VOLTAGE) break;
+ if(vehicle_status_raw.battery_voltage < num_of_cells * MAX_CELL_VOLTAGE) break;
}
printf("<blinkm> cells found:%d\n", num_of_cells);
@@ -530,7 +568,7 @@ BlinkM::led()
} else {
/* no battery warnings here */
- if(vehicle_status_raw.flag_system_armed == false) {
+ if(actuator_armed.armed == false) {
/* system not armed */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
@@ -554,27 +592,24 @@ BlinkM::led()
led_color_8 = LED_OFF;
led_blink = LED_BLINK;
- /* handle 4th led - flightmode indicator */
- switch((int)vehicle_status_raw.flight_mode) {
- case VEHICLE_FLIGHT_MODE_MANUAL:
- led_color_4 = LED_AMBER;
- break;
-
- case VEHICLE_FLIGHT_MODE_STAB:
- led_color_4 = LED_YELLOW;
- break;
-
- case VEHICLE_FLIGHT_MODE_HOLD:
- led_color_4 = LED_BLUE;
- break;
+ if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
- case VEHICLE_FLIGHT_MODE_AUTO:
+ //XXX please check
+ if (vehicle_control_mode.flag_control_position_enabled)
led_color_4 = LED_GREEN;
- break;
+ else if (vehicle_control_mode.flag_control_velocity_enabled)
+ led_color_4 = LED_BLUE;
+ else if (vehicle_control_mode.flag_control_attitude_enabled)
+ led_color_4 = LED_YELLOW;
+ else if (vehicle_control_mode.flag_control_manual_enabled)
+ led_color_4 = LED_AMBER;
+ else
+ led_color_4 = LED_OFF;
+
}
if(new_data_vehicle_gps_position || no_data_vehicle_gps_position < 3) {
- /* handling used sat´s */
+ /* handling used sat�s */
if(num_of_used_sats >= 7) {
led_color_1 = LED_OFF;
led_color_2 = LED_OFF;
@@ -831,11 +866,13 @@ BlinkM::get_firmware_version(uint8_t version[2])
return transfer(&msg, sizeof(msg), version, 2);
}
+void blinkm_usage();
+
void blinkm_usage() {
- fprintf(stderr, "missing command: try 'start', 'systemstate', 'ledoff', 'list' or a script name {options}\n");
- fprintf(stderr, "options:\n");
- fprintf(stderr, "\t-b --bus i2cbus (3)\n");
- fprintf(stderr, "\t-a --blinkmaddr blinkmaddr (9)\n");
+ warnx("missing command: try 'start', 'systemstate', 'ledoff', 'list' or a script name {options}");
+ warnx("options:");
+ warnx("\t-b --bus i2cbus (3)");
+ warnx("\t-a --blinkmaddr blinkmaddr (9)");
}
int
diff --git a/src/drivers/bma180/bma180.cpp b/src/drivers/bma180/bma180.cpp
index 4409a8a9c..cfb625670 100644
--- a/src/drivers/bma180/bma180.cpp
+++ b/src/drivers/bma180/bma180.cpp
@@ -59,7 +59,7 @@
#include <nuttx/clock.h>
#include <drivers/drv_hrt.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <drivers/device/spi.h>
#include <drivers/drv_accel.h>
diff --git a/src/drivers/boards/px4fmu/px4fmu_internal.h b/src/drivers/boards/px4fmu-v1/board_config.h
index 383a046ff..27621211a 100644
--- a/src/drivers/boards/px4fmu/px4fmu_internal.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file px4fmu_internal.h
+ * @file board_config.h
*
* PX4FMU internal definitions
*/
@@ -51,13 +51,16 @@ __BEGIN_DECLS
/* these headers are not C++ safe */
#include <stm32.h>
-
+#include <arch/board/board.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
/* Configuration ************************************************************************************/
+/* PX4IO connection configuration */
+#define PX4IO_SERIAL_DEVICE "/dev/ttyS2"
+
//#ifdef CONFIG_STM32_SPI2
//# error "SPI2 is not supported on this board"
//#endif
@@ -74,15 +77,47 @@ __BEGIN_DECLS
/* External interrupts */
#define GPIO_EXTI_COMPASS (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
-// XXX MPU6000 DRDY?
/* SPI chip selects */
-
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
#define GPIO_SPI_CS_ACCEL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
+/*
+ * Use these in place of the spi_dev_e enumeration to
+ * select a specific SPI device on SPI1
+ */
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_ACCEL 2
+#define PX4_SPIDEV_MPU 3
+
+/*
+ * Optional devices on IO's external port
+ */
+#define PX4_SPIDEV_ACCEL_MAG 2
+
+/*
+ * I2C busses
+ */
+#define PX4_I2C_BUS_ESC 1
+#define PX4_I2C_BUS_ONBOARD 2
+#define PX4_I2C_BUS_EXPANSION 3
+#define PX4_I2C_BUS_LED 3
+
+/*
+ * Devices on the onboard bus.
+ *
+ * Note that these are unshifted addresses.
+ */
+#define PX4_I2C_OBDEV_HMC5883 0x1e
+#define PX4_I2C_OBDEV_MS5611 0x76
+#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
+#define PX4_I2C_OBDEV_LED 0x55
+
+#define PX4_I2C_OBDEV_PX4IO_BL 0x18
+#define PX4_I2C_OBDEV_PX4IO 0x1a
+
/* User GPIOs
*
* GPIO0-1 are the buffered high-power GPIOs.
@@ -107,31 +142,45 @@ __BEGIN_DECLS
#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
#define GPIO_GPIO_DIR (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
+/*
+ * Tone alarm output
+ */
+#define TONE_ALARM_TIMER 3 /* timer 3 */
+#define TONE_ALARM_CHANNEL 3 /* channel 3 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
+
+/*
+ * PWM
+ *
+ * Four PWM outputs can be configured on pins otherwise shared with
+ * USART2; two can take the flow control pins if they are not being used.
+ *
+ * Pins:
+ *
+ * CTS - PA0 - TIM2CH1
+ * RTS - PA1 - TIM2CH2
+ * TX - PA2 - TIM2CH3
+ * RX - PA3 - TIM2CH4
+ *
+ */
+#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1
+#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1
+#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1
+#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1
+
/* USB OTG FS
*
* PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
*/
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
-/* PWM
- *
- * The PX4FMU has five PWM outputs, of which only the output on
- * pin PC8 is fixed assigned to this function. The other four possible
- * pwm sources are the TX, RX, RTS and CTS pins of USART2
- *
- * Alternate function mapping:
- * PC8 - BUZZER - TIM8_CH3/SDIO_D0 /TIM3_CH3/ USART6_CK / DCMI_D2
+/* High-resolution timer
*/
-
-#ifdef CONFIG_PWM
-# if defined(CONFIG_STM32_TIM3_PWM)
-# define BUZZER_PWMCHANNEL 3
-# define BUZZER_PWMTIMER 3
-# elif defined(CONFIG_STM32_TIM8_PWM)
-# define BUZZER_PWMCHANNEL 3
-# define BUZZER_PWMTIMER 8
-# endif
-#endif
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
+#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
/****************************************************************************************************
* Public Types
diff --git a/src/drivers/boards/px4fmu/module.mk b/src/drivers/boards/px4fmu-v1/module.mk
index 66b776917..66b776917 100644
--- a/src/drivers/boards/px4fmu/module.mk
+++ b/src/drivers/boards/px4fmu-v1/module.mk
diff --git a/src/drivers/boards/px4fmu/px4fmu_can.c b/src/drivers/boards/px4fmu-v1/px4fmu_can.c
index 187689ff9..1e1f10040 100644
--- a/src/drivers/boards/px4fmu/px4fmu_can.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_can.c
@@ -54,7 +54,7 @@
#include "stm32.h"
#include "stm32_can.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
#ifdef CONFIG_CAN
diff --git a/src/drivers/boards/px4fmu/px4fmu_init.c b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
index 36af2298c..964f5069c 100644
--- a/src/drivers/boards/px4fmu/px4fmu_init.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
@@ -59,7 +59,7 @@
#include <nuttx/analog/adc.h>
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
#include "stm32_uart.h"
#include <arch/board/board.h>
diff --git a/src/drivers/boards/px4fmu/px4fmu_led.c b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
index 31b25984e..ea91f34ad 100644
--- a/src/drivers/boards/px4fmu/px4fmu_led.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
@@ -42,7 +42,7 @@
#include <stdbool.h>
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
#include <arch/board/board.h>
@@ -57,6 +57,7 @@ __BEGIN_DECLS
extern void led_init();
extern void led_on(int led);
extern void led_off(int led);
+extern void led_toggle(int led);
__END_DECLS
__EXPORT void led_init()
@@ -94,3 +95,21 @@ __EXPORT void led_off(int led)
stm32_gpiowrite(GPIO_LED2, true);
}
}
+
+__EXPORT void led_toggle(int led)
+{
+ if (led == 0)
+ {
+ if (stm32_gpioread(GPIO_LED1))
+ stm32_gpiowrite(GPIO_LED1, false);
+ else
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+ if (led == 1)
+ {
+ if (stm32_gpioread(GPIO_LED2))
+ stm32_gpiowrite(GPIO_LED2, false);
+ else
+ stm32_gpiowrite(GPIO_LED2, true);
+ }
+}
diff --git a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmu-v1/px4fmu_pwm_servo.c
index d85131dd8..848e21d79 100644
--- a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_pwm_servo.c
@@ -41,15 +41,15 @@
#include <stdint.h>
-#include <drivers/stm32/drv_pwm_servo.h>
-
-#include <arch/board/board.h>
-#include <drivers/drv_pwm_output.h>
-
#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
+#include <drivers/stm32/drv_pwm_servo.h>
+#include <drivers/drv_pwm_output.h>
+
+#include "board_config.h"
+
__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
{
.base = STM32_TIM2_BASE,
diff --git a/src/drivers/boards/px4fmu/px4fmu_spi.c b/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
index e05ddecf3..17e6862f7 100644
--- a/src/drivers/boards/px4fmu/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
@@ -53,7 +53,7 @@
#include "up_arch.h"
#include "chip.h"
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
/************************************************************************************
* Public Functions
diff --git a/src/drivers/boards/px4fmu/px4fmu_usb.c b/src/drivers/boards/px4fmu-v1/px4fmu_usb.c
index 0be981c1e..0fc8569aa 100644
--- a/src/drivers/boards/px4fmu/px4fmu_usb.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_usb.c
@@ -53,7 +53,7 @@
#include "up_arch.h"
#include "stm32.h"
-#include "px4fmu_internal.h"
+#include "board_config.h"
/************************************************************************************
* Definitions
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
new file mode 100644
index 000000000..ec8dde499
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -0,0 +1,192 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 board_config.h
+ *
+ * PX4FMU internal definitions
+ */
+
+#pragma once
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+__BEGIN_DECLS
+
+/* these headers are not C++ safe */
+#include <stm32.h>
+#include <arch/board/board.h>
+
+/****************************************************************************************************
+ * Definitions
+ ****************************************************************************************************/
+/* Configuration ************************************************************************************/
+
+/* PX4IO connection configuration */
+#define PX4IO_SERIAL_DEVICE "/dev/ttyS4"
+#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
+#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
+#define PX4IO_SERIAL_BASE STM32_USART6_BASE /* hardwired on the board */
+#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
+#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX_2
+#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX_2
+#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
+#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
+
+
+/* PX4FMU GPIOs ***********************************************************************************/
+/* LEDs */
+
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12)
+
+/* External interrupts */
+#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN4)
+
+/* SPI chip selects */
+#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
+#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
+#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
+#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
+
+/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_ACCEL_MAG 2
+#define PX4_SPIDEV_BARO 3
+
+/* I2C busses */
+#define PX4_I2C_BUS_EXPANSION 1
+#define PX4_I2C_BUS_LED 2
+
+/* Devices on the onboard bus.
+ *
+ * Note that these are unshifted addresses.
+ */
+#define PX4_I2C_OBDEV_LED 0x55
+#define PX4_I2C_OBDEV_HMC5883 0x1e
+
+/* User GPIOs
+ *
+ * GPIO0-5 are the PWM servo outputs.
+ */
+#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN14)
+#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN13)
+#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
+#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN9)
+#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
+#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14)
+#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13)
+#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11)
+#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9)
+#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
+
+/* Power supply control and monitoring GPIOs */
+#define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
+#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_VDD_SERVO_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN7)
+#define GPIO_VDD_3V3_SENSORS_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
+#define GPIO_VDD_5V_HIPOWER_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN10)
+#define GPIO_VDD_5V_PERIPH_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15)
+
+/* Tone alarm output */
+#define TONE_ALARM_TIMER 2 /* timer 2 */
+#define TONE_ALARM_CHANNEL 1 /* channel 1 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15)
+
+/* PWM
+ *
+ * Six PWM outputs are configured.
+ *
+ * Pins:
+ *
+ * CH1 : PE14 : TIM1_CH4
+ * CH2 : PE13 : TIM1_CH3
+ * CH3 : PE11 : TIM1_CH2
+ * CH4 : PE9 : TIM1_CH1
+ * CH5 : PD13 : TIM4_CH2
+ * CH6 : PD14 : TIM4_CH3
+ */
+#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2
+#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_2
+#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_2
+#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_2
+#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2
+#define GPIO_TIM4_CH3OUT GPIO_TIM4_CH3OUT_2
+
+/* USB OTG FS
+ *
+ * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
+ */
+#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
+
+/* High-resolution timer */
+#define HRT_TIMER 8 /* use timer8 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public data
+ ****************************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************************
+ * Public Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ****************************************************************************************************/
+
+extern void stm32_spiinitialize(void);
+
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v2/module.mk b/src/drivers/boards/px4fmu-v2/module.mk
new file mode 100644
index 000000000..99d37eeca
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/module.mk
@@ -0,0 +1,10 @@
+#
+# Board-specific startup code for the PX4FMUv2
+#
+
+SRCS = px4fmu_can.c \
+ px4fmu2_init.c \
+ px4fmu_pwm_servo.c \
+ px4fmu_spi.c \
+ px4fmu_usb.c \
+ px4fmu2_led.c
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
new file mode 100644
index 000000000..135767b26
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
@@ -0,0 +1,262 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4fmu_init.c
+ *
+ * PX4FMU-specific early startup code. This file implements the
+ * nsh_archinitialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialisation.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/spi.h>
+#include <nuttx/i2c.h>
+#include <nuttx/sdio.h>
+#include <nuttx/mmcsd.h>
+#include <nuttx/analog/adc.h>
+
+#include <stm32.h>
+#include "board_config.h"
+#include <stm32_uart.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_led.h>
+
+#include <systemlib/cpuload.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+ /* configure SPI interfaces */
+ stm32_spiinitialize();
+
+ /* configure LEDs */
+ up_ledinit();
+}
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+static struct spi_dev_s *spi1;
+static struct spi_dev_s *spi2;
+static struct sdio_dev_s *sdio;
+
+#include <math.h>
+
+#ifdef __cplusplus
+__EXPORT int matherr(struct __exception *e)
+{
+ return 1;
+}
+#else
+__EXPORT int matherr(struct exception *e)
+{
+ return 1;
+}
+#endif
+
+__EXPORT int nsh_archinitialize(void)
+{
+
+ /* configure ADC pins */
+ stm32_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */
+ stm32_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */
+ stm32_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */
+ stm32_configgpio(GPIO_ADC1_IN10); /* unrouted */
+ stm32_configgpio(GPIO_ADC1_IN11); /* unrouted */
+ stm32_configgpio(GPIO_ADC1_IN12); /* unrouted */
+ stm32_configgpio(GPIO_ADC1_IN13); /* FMU_AUX_ADC_1 */
+ stm32_configgpio(GPIO_ADC1_IN14); /* FMU_AUX_ADC_2 */
+ stm32_configgpio(GPIO_ADC1_IN15); /* PRESSURE_SENS */
+
+ /* configure power supply control/sense pins */
+ stm32_configgpio(GPIO_VDD_5V_PERIPH_EN);
+ stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
+ stm32_configgpio(GPIO_VDD_BRICK_VALID);
+ stm32_configgpio(GPIO_VDD_SERVO_VALID);
+ stm32_configgpio(GPIO_VDD_5V_HIPOWER_OC);
+ stm32_configgpio(GPIO_VDD_5V_PERIPH_OC);
+
+ /* configure the high-resolution time/callout interface */
+ hrt_init();
+
+ /* configure CPU load estimation */
+#ifdef CONFIG_SCHED_INSTRUMENTATION
+ cpuload_initialize_once();
+#endif
+
+ /* set up the serial DMA polling */
+ static struct hrt_call serial_dma_call;
+ struct timespec ts;
+
+ /*
+ * Poll at 1ms intervals for received bytes that have not triggered
+ * a DMA event.
+ */
+ ts.tv_sec = 0;
+ ts.tv_nsec = 1000000;
+
+ hrt_call_every(&serial_dma_call,
+ ts_to_abstime(&ts),
+ ts_to_abstime(&ts),
+ (hrt_callout)stm32_serial_dma_poll,
+ NULL);
+
+ /* initial LED state */
+ drv_led_start();
+ led_off(LED_AMBER);
+
+ /* Configure SPI-based devices */
+
+ spi1 = up_spiinitialize(1);
+
+ if (!spi1) {
+ message("[boot] FAILED to initialize SPI port 1\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* Default SPI1 to 1MHz and de-assert the known chip selects. */
+ SPI_SETFREQUENCY(spi1, 10000000);
+ SPI_SETBITS(spi1, 8);
+ SPI_SETMODE(spi1, SPIDEV_MODE3);
+ SPI_SELECT(spi1, PX4_SPIDEV_GYRO, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_ACCEL_MAG, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_BARO, false);
+ up_udelay(20);
+
+ message("[boot] Successfully initialized SPI port 1\n");
+
+ /* Get the SPI port for the FRAM */
+
+ spi2 = up_spiinitialize(2);
+
+ if (!spi2) {
+ message("[boot] FAILED to initialize SPI port 2\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* Default SPI2 to 37.5 MHz (F4 max) and de-assert the known chip selects. */
+ SPI_SETFREQUENCY(spi2, 375000000);
+ SPI_SETBITS(spi2, 8);
+ SPI_SETMODE(spi2, SPIDEV_MODE3);
+ SPI_SELECT(spi2, SPIDEV_FLASH, false);
+
+ message("[boot] Successfully initialized SPI port 2\n");
+
+ #ifdef CONFIG_MMCSD
+ /* First, get an instance of the SDIO interface */
+
+ sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
+ if (!sdio) {
+ message("nsh_archinitialize: Failed to initialize SDIO slot %d\n",
+ CONFIG_NSH_MMCSDSLOTNO);
+ return -ENODEV;
+ }
+
+ /* Now bind the SDIO interface to the MMC/SD driver */
+ int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
+ if (ret != OK) {
+ message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+ return ret;
+ }
+
+ /* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */
+ sdio_mediachange(sdio, true);
+
+ message("[boot] Initialized SDIO\n");
+ #endif
+
+ return OK;
+}
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_led.c b/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
new file mode 100644
index 000000000..a856ccb02
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
@@ -0,0 +1,97 @@
+/****************************************************************************
+ *
+ * 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 px4fmu2_led.c
+ *
+ * PX4FMU LED backend.
+ */
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include "stm32.h"
+#include "board_config.h"
+
+#include <arch/board/board.h>
+
+/*
+ * Ideally we'd be able to get these from up_internal.h,
+ * but since we want to be able to disable the NuttX use
+ * of leds for system indication at will and there is no
+ * separate switch, we need to build independent of the
+ * CONFIG_ARCH_LEDS configuration switch.
+ */
+__BEGIN_DECLS
+extern void led_init();
+extern void led_on(int led);
+extern void led_off(int led);
+extern void led_toggle(int led);
+__END_DECLS
+
+__EXPORT void led_init()
+{
+ /* Configure LED1 GPIO for output */
+
+ stm32_configgpio(GPIO_LED1);
+}
+
+__EXPORT void led_on(int led)
+{
+ if (led == 1)
+ {
+ /* Pull down to switch on */
+ stm32_gpiowrite(GPIO_LED1, false);
+ }
+}
+
+__EXPORT void led_off(int led)
+{
+ if (led == 1)
+ {
+ /* Pull up to switch off */
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+}
+
+__EXPORT void led_toggle(int led)
+{
+ if (led == 1)
+ {
+ if (stm32_gpioread(GPIO_LED1))
+ stm32_gpiowrite(GPIO_LED1, false);
+ else
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+}
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_can.c b/src/drivers/boards/px4fmu-v2/px4fmu_can.c
new file mode 100644
index 000000000..f66c7cd79
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_can.c
@@ -0,0 +1,144 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4fmu_can.c
+ *
+ * Board-specific CAN functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/can.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "stm32.h"
+#include "stm32_can.h"
+#include "board_config.h"
+
+#ifdef CONFIG_CAN
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
+# undef CONFIG_STM32_CAN2
+#endif
+
+#ifdef CONFIG_STM32_CAN1
+# define CAN_PORT 1
+#else
+# define CAN_PORT 2
+#endif
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing CAN */
+
+#ifdef CONFIG_DEBUG_CAN
+# define candbg dbg
+# define canvdbg vdbg
+# define canlldbg lldbg
+# define canllvdbg llvdbg
+#else
+# define candbg(x...)
+# define canvdbg(x...)
+# define canlldbg(x...)
+# define canllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized) {
+ /* Call stm32_caninitialize() to get an instance of the CAN interface */
+
+ can = stm32_caninitialize(CAN_PORT);
+
+ if (can == NULL) {
+ candbg("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+
+ if (ret < 0) {
+ candbg("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif \ No newline at end of file
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c
new file mode 100644
index 000000000..600dfef41
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_pwm_servo.c
@@ -0,0 +1,105 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4fmu_pwm_servo.c
+ *
+ * Configuration data for the stm32 pwm_servo driver.
+ *
+ * Note that these arrays must always be fully-sized.
+ */
+
+#include <stdint.h>
+
+#include <stm32.h>
+#include <stm32_gpio.h>
+#include <stm32_tim.h>
+
+#include <drivers/stm32/drv_pwm_servo.h>
+#include <drivers/drv_pwm_output.h>
+
+#include "board_config.h"
+
+__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
+ {
+ .base = STM32_TIM1_BASE,
+ .clock_register = STM32_RCC_APB2ENR,
+ .clock_bit = RCC_APB2ENR_TIM1EN,
+ .clock_freq = STM32_APB2_TIM1_CLKIN
+ },
+ {
+ .base = STM32_TIM4_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM4EN,
+ .clock_freq = STM32_APB1_TIM4_CLKIN
+ }
+};
+
+__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
+ {
+ .gpio = GPIO_TIM1_CH4OUT,
+ .timer_index = 0,
+ .timer_channel = 4,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM1_CH3OUT,
+ .timer_index = 0,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM1_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM1_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH2OUT,
+ .timer_index = 1,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH3OUT,
+ .timer_index = 1,
+ .timer_channel = 3,
+ .default_value = 1000,
+ }
+};
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
new file mode 100644
index 000000000..09838d02f
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
@@ -0,0 +1,141 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4fmu_spi.c
+ *
+ * Board-specific SPI functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include <up_arch.h>
+#include <chip.h>
+#include <stm32.h>
+#include "board_config.h"
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+__EXPORT void weak_function stm32_spiinitialize(void)
+{
+#ifdef CONFIG_STM32_SPI1
+ stm32_configgpio(GPIO_SPI_CS_GYRO);
+ stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
+ stm32_configgpio(GPIO_SPI_CS_BARO);
+
+ /* De-activate all peripherals,
+ * required for some peripheral
+ * state machines
+ */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+ stm32_configgpio(GPIO_SPI_CS_FRAM);
+ stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
+#endif
+}
+
+__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* SPI select is active low, so write !selected to select the device */
+
+ switch (devid) {
+ case PX4_SPIDEV_GYRO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ break;
+
+ case PX4_SPIDEV_ACCEL_MAG:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ break;
+
+ case PX4_SPIDEV_BARO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
+ break;
+
+ default:
+ break;
+ }
+}
+
+__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+
+
+#ifdef CONFIG_STM32_SPI2
+__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there can only be one device on this bus, so always select it */
+ stm32_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
+}
+
+__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ /* FRAM is always present */
+ return SPI_STATUS_PRESENT;
+}
+#endif
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_usb.c b/src/drivers/boards/px4fmu-v2/px4fmu_usb.c
new file mode 100644
index 000000000..f329e06ff
--- /dev/null
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_usb.c
@@ -0,0 +1,108 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4fmu_usb.c
+ *
+ * Board-specific USB functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/usb/usbdev.h>
+#include <nuttx/usb/usbdev_trace.h>
+
+#include <up_arch.h>
+#include <stm32.h>
+#include "board_config.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_usbinitialize(void)
+{
+ /* The OTG FS has an internal soft pull-up */
+
+ /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
+
+#ifdef CONFIG_STM32_OTGFS
+ stm32_configgpio(GPIO_OTGFS_VBUS);
+ /* XXX We only support device mode
+ stm32_configgpio(GPIO_OTGFS_PWRON);
+ stm32_configgpio(GPIO_OTGFS_OVER);
+ */
+#endif
+}
+
+/************************************************************************************
+ * Name: stm32_usbsuspend
+ *
+ * Description:
+ * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
+ * used. This function is called whenever the USB enters or leaves suspend mode.
+ * This is an opportunity for the board logic to shutdown clocks, power, etc.
+ * while the USB is suspended.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+{
+ ulldbg("resume: %d\n", resume);
+}
+
diff --git a/src/drivers/boards/px4io/px4io_internal.h b/src/drivers/boards/px4io-v1/board_config.h
index 6638e715e..48aadbd76 100644
--- a/src/drivers/boards/px4io/px4io_internal.h
+++ b/src/drivers/boards/px4io-v1/board_config.h
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file px4io_internal.h
+ * @file board_config.h
*
* PX4IO hardware definitions.
*/
@@ -47,7 +47,9 @@
#include <nuttx/compiler.h>
#include <stdint.h>
+/* these headers are not C++ safe */
#include <stm32.h>
+#include <arch/board/board.h>
/************************************************************************************
* Definitions
@@ -83,3 +85,11 @@
#define GPIO_ADC_VBATT (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
#define GPIO_ADC_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
+
+/*
+ * High-resolution timer
+ */
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
+#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
+#define GPIO_PPM_IN GPIO_TIM1_CH1IN
diff --git a/src/drivers/boards/px4io/module.mk b/src/drivers/boards/px4io-v1/module.mk
index 2601a1c15..2601a1c15 100644
--- a/src/drivers/boards/px4io/module.mk
+++ b/src/drivers/boards/px4io-v1/module.mk
diff --git a/src/drivers/boards/px4io/px4io_init.c b/src/drivers/boards/px4io-v1/px4io_init.c
index 15c59e423..8292da9e1 100644
--- a/src/drivers/boards/px4io/px4io_init.c
+++ b/src/drivers/boards/px4io-v1/px4io_init.c
@@ -55,7 +55,7 @@
#include <nuttx/arch.h>
#include "stm32.h"
-#include "px4io_internal.h"
+#include "board_config.h"
#include "stm32_uart.h"
#include <arch/board/board.h>
diff --git a/src/drivers/boards/px4io/px4io_pwm_servo.c b/src/drivers/boards/px4io-v1/px4io_pwm_servo.c
index 6df470da6..6df470da6 100644
--- a/src/drivers/boards/px4io/px4io_pwm_servo.c
+++ b/src/drivers/boards/px4io-v1/px4io_pwm_servo.c
diff --git a/src/drivers/boards/px4io-v2/board_config.h b/src/drivers/boards/px4io-v2/board_config.h
new file mode 100644
index 000000000..818b64436
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/board_config.h
@@ -0,0 +1,138 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4iov2_internal.h
+ *
+ * PX4IOV2 internal definitions
+ */
+
+#pragma once
+
+/******************************************************************************
+ * Included Files
+ ******************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+/* these headers are not C++ safe */
+#include <stm32.h>
+#include <arch/board/board.h>
+
+/******************************************************************************
+ * Definitions
+ ******************************************************************************/
+/* Configuration **************************************************************/
+
+/******************************************************************************
+ * Serial
+ ******************************************************************************/
+#define PX4FMU_SERIAL_BASE STM32_USART2_BASE
+#define PX4FMU_SERIAL_VECTOR STM32_IRQ_USART2
+#define PX4FMU_SERIAL_TX_GPIO GPIO_USART2_TX
+#define PX4FMU_SERIAL_RX_GPIO GPIO_USART2_RX
+#define PX4FMU_SERIAL_TX_DMA DMACHAN_USART2_TX
+#define PX4FMU_SERIAL_RX_DMA DMACHAN_USART2_RX
+#define PX4FMU_SERIAL_CLOCK STM32_PCLK1_FREQUENCY
+#define PX4FMU_SERIAL_BITRATE 1500000
+
+/******************************************************************************
+ * GPIOS
+ ******************************************************************************/
+
+/* LEDS **********************************************************************/
+
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14)
+#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
+#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN13)
+
+/* Safety switch button *******************************************************/
+
+#define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5)
+
+/* Power switch controls ******************************************************/
+
+#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
+
+#define GPIO_SERVO_FAULT_DETECT (GPIO_INPUT|GPIO_CNF_INPULLUP|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
+
+/* Analog inputs **************************************************************/
+
+#define GPIO_ADC_VSERVO (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
+
+/* the same rssi signal goes to both an adc and a timer input */
+#define GPIO_ADC_RSSI (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
+#define GPIO_TIM_RSSI (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
+
+/* PWM pins **************************************************************/
+
+#define GPIO_PPM (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8)
+
+#define GPIO_PWM1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_PWM2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_PWM3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
+#define GPIO_PWM4 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
+#define GPIO_PWM5 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN6)
+#define GPIO_PWM6 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7)
+#define GPIO_PWM7 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_PWM8 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
+
+/* SBUS pins *************************************************************/
+
+/* XXX these should be UART pins */
+#define GPIO_SBUS_INPUT (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_SBUS_OUTPUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_SBUS_OENABLE (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN4)
+
+/*
+ * High-resolution timer
+ */
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
+#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
+#define GPIO_PPM_IN GPIO_TIM1_CH1IN
+
+/* LED definitions ******************************************************************/
+/* PX4 has two LEDs that we will encode as: */
+
+#define LED_STARTED 0 /* LED? */
+#define LED_HEAPALLOCATE 1 /* LED? */
+#define LED_IRQSENABLED 2 /* LED? + LED? */
+#define LED_STACKCREATED 3 /* LED? */
+#define LED_INIRQ 4 /* LED? + LED? */
+#define LED_SIGNAL 5 /* LED? + LED? */
+#define LED_ASSERTION 6 /* LED? + LED? + LED? */
+#define LED_PANIC 7 /* N/C + N/C + N/C + LED? */
+
diff --git a/src/drivers/boards/px4io-v2/module.mk b/src/drivers/boards/px4io-v2/module.mk
new file mode 100644
index 000000000..85f94e8be
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/module.mk
@@ -0,0 +1,6 @@
+#
+# Board-specific startup code for the PX4IOv2
+#
+
+SRCS = px4iov2_init.c \
+ px4iov2_pwm_servo.c
diff --git a/src/drivers/boards/px4io-v2/px4iov2_init.c b/src/drivers/boards/px4io-v2/px4iov2_init.c
new file mode 100644
index 000000000..0ea95bded
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/px4iov2_init.c
@@ -0,0 +1,162 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4iov2_init.c
+ *
+ * PX4FMU-specific early startup code. This file implements the
+ * nsh_archinitialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialisation.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+
+#include <stm32.h>
+#include "board_config.h"
+
+#include <arch/board/board.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void stm32_boardinitialize(void)
+{
+
+ /* configure GPIOs */
+
+ /* LEDS - default to off */
+ stm32_configgpio(GPIO_LED1);
+ stm32_configgpio(GPIO_LED2);
+ stm32_configgpio(GPIO_LED3);
+
+ stm32_configgpio(GPIO_BTN_SAFETY);
+
+ /* spektrum power enable is active high - disable it by default */
+ /* XXX might not want to do this on warm restart? */
+ stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, false);
+ stm32_configgpio(GPIO_SPEKTRUM_PWR_EN);
+
+ stm32_configgpio(GPIO_SERVO_FAULT_DETECT);
+
+ /* RSSI inputs */
+ stm32_configgpio(GPIO_TIM_RSSI); /* xxx alternate function */
+ stm32_configgpio(GPIO_ADC_RSSI);
+
+ /* servo rail voltage */
+ stm32_configgpio(GPIO_ADC_VSERVO);
+
+ stm32_configgpio(GPIO_SBUS_INPUT); /* xxx alternate function */
+
+ stm32_gpiowrite(GPIO_SBUS_OUTPUT, false);
+ stm32_configgpio(GPIO_SBUS_OUTPUT);
+
+ /* sbus output enable is active low - disable it by default */
+ stm32_gpiowrite(GPIO_SBUS_OENABLE, true);
+ stm32_configgpio(GPIO_SBUS_OENABLE);
+
+ stm32_configgpio(GPIO_PPM); /* xxx alternate function */
+
+ stm32_gpiowrite(GPIO_PWM1, false);
+ stm32_configgpio(GPIO_PWM1);
+
+ stm32_gpiowrite(GPIO_PWM2, false);
+ stm32_configgpio(GPIO_PWM2);
+
+ stm32_gpiowrite(GPIO_PWM3, false);
+ stm32_configgpio(GPIO_PWM3);
+
+ stm32_gpiowrite(GPIO_PWM4, false);
+ stm32_configgpio(GPIO_PWM4);
+
+ stm32_gpiowrite(GPIO_PWM5, false);
+ stm32_configgpio(GPIO_PWM5);
+
+ stm32_gpiowrite(GPIO_PWM6, false);
+ stm32_configgpio(GPIO_PWM6);
+
+ stm32_gpiowrite(GPIO_PWM7, false);
+ stm32_configgpio(GPIO_PWM7);
+
+ stm32_gpiowrite(GPIO_PWM8, false);
+ stm32_configgpio(GPIO_PWM8);
+}
diff --git a/src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c b/src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c
new file mode 100644
index 000000000..4f1b9487c
--- /dev/null
+++ b/src/drivers/boards/px4io-v2/px4iov2_pwm_servo.c
@@ -0,0 +1,123 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 px4iov2_pwm_servo.c
+ *
+ * Configuration data for the stm32 pwm_servo driver.
+ *
+ * Note that these arrays must always be fully-sized.
+ */
+
+#include <stdint.h>
+
+#include <drivers/stm32/drv_pwm_servo.h>
+
+#include <arch/board/board.h>
+#include <drivers/drv_pwm_output.h>
+
+#include <stm32.h>
+#include <stm32_gpio.h>
+#include <stm32_tim.h>
+
+__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
+ {
+ .base = STM32_TIM2_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM2EN,
+ .clock_freq = STM32_APB1_TIM2_CLKIN
+ },
+ {
+ .base = STM32_TIM3_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM3EN,
+ .clock_freq = STM32_APB1_TIM3_CLKIN
+ },
+ {
+ .base = STM32_TIM4_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM4EN,
+ .clock_freq = STM32_APB1_TIM4_CLKIN
+ }
+};
+
+__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
+ {
+ .gpio = GPIO_TIM2_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM2_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH3OUT,
+ .timer_index = 2,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM4_CH4OUT,
+ .timer_index = 2,
+ .timer_channel = 4,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH1OUT,
+ .timer_index = 1,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH2OUT,
+ .timer_index = 1,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH3OUT,
+ .timer_index = 1,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM3_CH4OUT,
+ .timer_index = 1,
+ .timer_channel = 4,
+ .default_value = 1000,
+ }
+};
diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h
index 510983d4b..37af26d52 100644
--- a/src/drivers/drv_gpio.h
+++ b/src/drivers/drv_gpio.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012 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
@@ -59,17 +59,47 @@
# define GPIO_CAN_RX (1<<7) /**< CAN2 RX */
/**
- * Default GPIO device - other devices may also support this protocol if
- * they also export GPIO-like things. This is always the GPIOs on the
- * main board.
+ * Device paths for things that support the GPIO ioctl protocol.
*/
# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
# define PX4IO_DEVICE_PATH "/dev/px4io"
#endif
-#ifndef PX4IO_DEVICE_PATH
-# error No GPIO support for this board.
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+/*
+ * PX4FMUv2 GPIO numbers.
+ *
+ * There are no alternate functions on this board.
+ */
+# define GPIO_SERVO_1 (1<<0) /**< servo 1 output */
+# define GPIO_SERVO_2 (1<<1) /**< servo 2 output */
+# define GPIO_SERVO_3 (1<<2) /**< servo 3 output */
+# define GPIO_SERVO_4 (1<<3) /**< servo 4 output */
+# define GPIO_SERVO_5 (1<<4) /**< servo 5 output */
+# define GPIO_SERVO_6 (1<<5) /**< servo 6 output */
+
+# define GPIO_5V_PERIPH_EN (1<<6) /**< PA8 - !VDD_5V_PERIPH_EN */
+# define GPIO_3V3_SENSORS_EN (1<<7) /**< PE3 - VDD_3V3_SENSORS_EN */
+# define GPIO_BRICK_VALID (1<<8) /**< PB5 - !VDD_BRICK_VALID */
+# define GPIO_SERVO_VALID (1<<9) /**< PB7 - !VDD_SERVO_VALID */
+# define GPIO_5V_HIPOWER_OC (1<<10) /**< PE10 - !VDD_5V_HIPOWER_OC */
+# define GPIO_5V_PERIPH_OC (1<<11) /**< PE10 - !VDD_5V_PERIPH_OC */
+
+/**
+ * Device paths for things that support the GPIO ioctl protocol.
+ */
+# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
+# define PX4IO_DEVICE_PATH "/dev/px4io"
+
+#endif
+
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
+/* no GPIO driver on the PX4IOv1 board */
+#endif
+
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+/* no GPIO driver on the PX4IOv2 board */
#endif
/*
diff --git a/src/drivers/drv_led.h b/src/drivers/drv_led.h
index 21044f620..4ce04696e 100644
--- a/src/drivers/drv_led.h
+++ b/src/drivers/drv_led.h
@@ -54,12 +54,13 @@
#define LED_ON _IOC(_LED_BASE, 0)
#define LED_OFF _IOC(_LED_BASE, 1)
+#define LED_TOGGLE _IOC(_LED_BASE, 2)
__BEGIN_DECLS
/*
* Initialise the LED driver.
*/
-__EXPORT extern void drv_led_start(void);
+__EXPORT void drv_led_start(void);
__END_DECLS
diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h
index 9aab995a1..3de5625fd 100644
--- a/src/drivers/drv_mag.h
+++ b/src/drivers/drv_mag.h
@@ -90,25 +90,37 @@ ORB_DECLARE(sensor_mag);
/** set the mag internal sample rate to at least (arg) Hz */
#define MAGIOCSSAMPLERATE _MAGIOC(0)
+/** return the mag internal sample rate in Hz */
+#define MAGIOCGSAMPLERATE _MAGIOC(1)
+
/** set the mag internal lowpass filter to no lower than (arg) Hz */
-#define MAGIOCSLOWPASS _MAGIOC(1)
+#define MAGIOCSLOWPASS _MAGIOC(2)
+
+/** return the mag internal lowpass filter in Hz */
+#define MAGIOCGLOWPASS _MAGIOC(3)
/** set the mag scaling constants to the structure pointed to by (arg) */
-#define MAGIOCSSCALE _MAGIOC(2)
+#define MAGIOCSSCALE _MAGIOC(4)
/** copy the mag scaling constants to the structure pointed to by (arg) */
-#define MAGIOCGSCALE _MAGIOC(3)
+#define MAGIOCGSCALE _MAGIOC(5)
/** set the measurement range to handle (at least) arg Gauss */
-#define MAGIOCSRANGE _MAGIOC(4)
+#define MAGIOCSRANGE _MAGIOC(6)
+
+/** return the current mag measurement range in Gauss */
+#define MAGIOCGRANGE _MAGIOC(7)
/** perform self-calibration, update scale factors to canonical units */
-#define MAGIOCCALIBRATE _MAGIOC(5)
+#define MAGIOCCALIBRATE _MAGIOC(8)
/** excite strap */
-#define MAGIOCEXSTRAP _MAGIOC(6)
+#define MAGIOCEXSTRAP _MAGIOC(9)
/** perform self test and report status */
-#define MAGIOCSELFTEST _MAGIOC(7)
+#define MAGIOCSELFTEST _MAGIOC(10)
+
+/** determine if mag is external or onboard */
+#define MAGIOCGEXTERNAL _MAGIOC(11)
#endif /* _DRV_MAG_H */
diff --git a/src/drivers/drv_rgbled.h b/src/drivers/drv_rgbled.h
new file mode 100644
index 000000000..3c8bdec5d
--- /dev/null
+++ b/src/drivers/drv_rgbled.h
@@ -0,0 +1,126 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-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 drv_rgbled.h
+ *
+ * RGB led device API
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+
+/* more devices will be 1, 2, etc */
+#define RGBLED_DEVICE_PATH "/dev/rgbled0"
+
+/*
+ * ioctl() definitions
+ */
+
+#define _RGBLEDIOCBASE (0x2900)
+#define _RGBLEDIOC(_n) (_IOC(_RGBLEDIOCBASE, _n))
+
+/** play the named script in *(char *)arg, repeating forever */
+#define RGBLED_PLAY_SCRIPT_NAMED _RGBLEDIOC(1)
+
+/** play the numbered script in (arg), repeating forever */
+#define RGBLED_PLAY_SCRIPT _RGBLEDIOC(2)
+
+/**
+ * Set the user script; (arg) is a pointer to an array of script lines,
+ * where each line is an array of four bytes giving <duration>, <command>, arg[0-2]
+ *
+ * The script is terminated by a zero command.
+ */
+#define RGBLED_SET_USER_SCRIPT _RGBLEDIOC(3)
+
+/** set constant RGB values */
+#define RGBLED_SET_RGB _RGBLEDIOC(4)
+
+/** set color */
+#define RGBLED_SET_COLOR _RGBLEDIOC(5)
+
+/** set blink speed */
+#define RGBLED_SET_MODE _RGBLEDIOC(6)
+
+/** set pattern */
+#define RGBLED_SET_PATTERN _RGBLEDIOC(7)
+
+/*
+ structure passed to RGBLED_SET_RGB ioctl()
+ Note that the driver scales the brightness to 0 to 255, regardless
+ of the hardware scaling
+ */
+typedef struct {
+ uint8_t red;
+ uint8_t green;
+ uint8_t blue;
+} rgbled_rgbset_t;
+
+/* enum passed to RGBLED_SET_COLOR ioctl()*/
+typedef enum {
+ RGBLED_COLOR_OFF,
+ RGBLED_COLOR_RED,
+ RGBLED_COLOR_YELLOW,
+ RGBLED_COLOR_PURPLE,
+ RGBLED_COLOR_GREEN,
+ RGBLED_COLOR_BLUE,
+ RGBLED_COLOR_WHITE,
+ RGBLED_COLOR_AMBER,
+ RGBLED_COLOR_DIM_RED,
+ RGBLED_COLOR_DIM_YELLOW,
+ RGBLED_COLOR_DIM_PURPLE,
+ RGBLED_COLOR_DIM_GREEN,
+ RGBLED_COLOR_DIM_BLUE,
+ RGBLED_COLOR_DIM_WHITE,
+ RGBLED_COLOR_DIM_AMBER
+} rgbled_color_t;
+
+/* enum passed to RGBLED_SET_MODE ioctl()*/
+typedef enum {
+ RGBLED_MODE_OFF,
+ RGBLED_MODE_ON,
+ RGBLED_MODE_BLINK_SLOW,
+ RGBLED_MODE_BLINK_NORMAL,
+ RGBLED_MODE_BLINK_FAST,
+ RGBLED_MODE_PATTERN
+} rgbled_mode_t;
+
+#define RGBLED_PATTERN_LENGTH 20
+
+typedef struct {
+ rgbled_color_t color[RGBLED_PATTERN_LENGTH];
+ unsigned duration[RGBLED_PATTERN_LENGTH];
+} rgbled_pattern_t;
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index cd72d9d23..257b41935 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -59,7 +59,7 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <systemlib/airspeed.h>
#include <systemlib/err.h>
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index bd027ce0b..3e30e3292 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -75,6 +75,7 @@
#include <systemlib/mixer/mixer.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/actuator_outputs.h>
#include <systemlib/err.h>
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index ac3bdc132..d77f03bb7 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -58,7 +58,7 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@@ -77,8 +77,8 @@
#define HMC5883L_ADDRESS PX4_I2C_OBDEV_HMC5883
-/* Max measurement rate is 160Hz */
-#define HMC5883_CONVERSION_INTERVAL (1000000 / 160) /* microseconds */
+/* 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 */
#define ADDR_CONF_A 0x00
#define ADDR_CONF_B 0x01
@@ -167,6 +167,8 @@ private:
bool _sensor_ok; /**< sensor was found and reports ok */
bool _calibrated; /**< the calibration is valid */
+ int _bus; /**< the bus the device is connected to */
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -190,6 +192,11 @@ private:
void stop();
/**
+ * Reset the device
+ */
+ int reset();
+
+ /**
* Perform the on-sensor scale calibration routine.
*
* @note The sensor will continue to provide measurements, these
@@ -326,7 +333,8 @@ HMC5883::HMC5883(int bus) :
_comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")),
_buffer_overflows(perf_alloc(PC_COUNT, "hmc5883_buffer_overflows")),
_sensor_ok(false),
- _calibrated(false)
+ _calibrated(false),
+ _bus(bus)
{
// enable debug() calls
_debug_enabled = false;
@@ -362,6 +370,9 @@ HMC5883::init()
if (I2C::init() != OK)
goto out;
+ /* reset the device configuration */
+ reset();
+
/* allocate basic report buffers */
_num_reports = 2;
_reports = new struct mag_report[_num_reports];
@@ -378,9 +389,6 @@ HMC5883::init()
if (_mag_topic < 0)
debug("failed to create sensor_mag object");
- /* set range */
- set_range(_range_ga);
-
ret = OK;
/* sensor is ok, but not calibrated */
_sensor_ok = true;
@@ -539,68 +547,67 @@ int
HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
{
switch (cmd) {
-
case SENSORIOCSPOLLRATE: {
- switch (arg) {
+ switch (arg) {
- /* switching to manual polling */
- case SENSOR_POLLRATE_MANUAL:
- stop();
- _measure_ticks = 0;
- return OK;
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _measure_ticks = 0;
+ return OK;
- /* external signalling (DRDY) not supported */
- case SENSOR_POLLRATE_EXTERNAL:
+ /* external signalling (DRDY) not supported */
+ case SENSOR_POLLRATE_EXTERNAL:
- /* zero would be bad */
- case 0:
- return -EINVAL;
+ /* 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 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(HMC5883_CONVERSION_INTERVAL);
+ /* set interval for next measurement to minimum legal value */
+ _measure_ticks = USEC2TICK(HMC5883_CONVERSION_INTERVAL);
- /* if we need to start the poll state machine, do it */
- if (want_start)
- start();
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
- return OK;
- }
+ return OK;
+ }
- /* adjust to a legal polling interval in Hz */
- default: {
- /* do we need to start internal polling? */
- bool want_start = (_measure_ticks == 0);
+ /* 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);
+ /* convert hz to tick interval via microseconds */
+ unsigned ticks = USEC2TICK(1000000 / arg);
- /* check against maximum rate */
- if (ticks < USEC2TICK(HMC5883_CONVERSION_INTERVAL))
- return -EINVAL;
+ /* check against maximum rate */
+ if (ticks < USEC2TICK(HMC5883_CONVERSION_INTERVAL))
+ return -EINVAL;
- /* update interval for next measurement */
- _measure_ticks = ticks;
+ /* update interval for next measurement */
+ _measure_ticks = ticks;
- /* if we need to start the poll state machine, do it */
- if (want_start)
- start();
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
- return OK;
- }
+ return OK;
}
}
+ }
case SENSORIOCGPOLLRATE:
if (_measure_ticks == 0)
return SENSOR_POLLRATE_MANUAL;
- return (1000 / _measure_ticks);
+ return 1000000/TICK2USEC(_measure_ticks);
case SENSORIOCSQUEUEDEPTH: {
/* add one to account for the sentinel in the ring */
@@ -630,17 +637,24 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
return _num_reports - 1;
case SENSORIOCRESET:
- /* XXX implement this */
- return -EINVAL;
+ return reset();
case MAGIOCSSAMPLERATE:
- /* not supported, always 1 sample per poll */
- return -EINVAL;
+ /* same as pollrate because device is in single measurement mode*/
+ return ioctl(filp, SENSORIOCSPOLLRATE, arg);
+
+ case MAGIOCGSAMPLERATE:
+ /* same as pollrate because device is in single measurement mode*/
+ return 1000000/TICK2USEC(_measure_ticks);
case MAGIOCSRANGE:
return set_range(arg);
+ case MAGIOCGRANGE:
+ return _range_ga;
+
case MAGIOCSLOWPASS:
+ case MAGIOCGLOWPASS:
/* not supported, no internal filtering */
return -EINVAL;
@@ -665,6 +679,12 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
case MAGIOCSELFTEST:
return check_calibration();
+ case MAGIOCGEXTERNAL:
+ if (_bus == PX4_I2C_BUS_EXPANSION)
+ return 1;
+ else
+ return 0;
+
default:
/* give it to the superclass */
return I2C::ioctl(filp, cmd, arg);
@@ -688,6 +708,13 @@ HMC5883::stop()
work_cancel(HPWORK, &_work);
}
+int
+HMC5883::reset()
+{
+ /* set range */
+ return set_range(_range_ga);
+}
+
void
HMC5883::cycle_trampoline(void *arg)
{
@@ -851,10 +878,11 @@ HMC5883::collect()
_reports[_next_report].z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
} else {
#endif
- /* XXX axis assignment of external sensor is yet unknown */
- _reports[_next_report].x = ((report.y * _range_scale) - _scale.x_offset) * _scale.x_scale;
+ /* the standard external mag by 3DR has x pointing to the right, y pointing backwards, and z down,
+ * therefore switch x and y and invert y */
+ _reports[_next_report].x = ((((report.y == -32768) ? 32767 : -report.y) * _range_scale) - _scale.x_offset) * _scale.x_scale;
/* flip axes and negate value for y */
- _reports[_next_report].y = ((((report.x == -32768) ? 32767 : -report.x) * _range_scale) - _scale.y_offset) * _scale.y_scale;
+ _reports[_next_report].y = ((report.x * _range_scale) - _scale.y_offset) * _scale.y_scale;
/* z remains z */
_reports[_next_report].z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
#ifdef PX4_I2C_BUS_ONBOARD
@@ -1293,6 +1321,11 @@ test()
warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
warnx("time: %lld", report.timestamp);
+ /* check if mag is onboard or external */
+ if ((ret = ioctl(fd, MAGIOCGEXTERNAL, 0)) < 0)
+ errx(1, "failed to get if mag is onboard or external");
+ warnx("device active: %s", ret ? "external" : "onboard");
+
/* set the queue depth to 10 */
if (OK != ioctl(fd, SENSORIOCSQUEUEDEPTH, 10))
errx(1, "failed to set queue depth");
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
index 57c256339..bb8d45bea 100644
--- a/src/drivers/hott/messages.cpp
+++ b/src/drivers/hott/messages.cpp
@@ -42,7 +42,7 @@
#include <math.h>
#include <stdio.h>
#include <string.h>
-#include <systemlib/geo/geo.h>
+#include <geo/geo.h>
#include <unistd.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/battery_status.h>
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 744abfa00..5e0a2119a 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -59,11 +59,11 @@
#include <nuttx/clock.h>
#include <drivers/drv_hrt.h>
-#include <arch/board/board.h>
-
#include <drivers/device/spi.h>
#include <drivers/drv_gyro.h>
+#include <board_config.h>
+#include <mathlib/math/filter/LowPassFilter2p.hpp>
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -71,6 +71,12 @@
#endif
static const int ERROR = -1;
+/* Orientation on board */
+#define SENSOR_BOARD_ROTATION_000_DEG 0
+#define SENSOR_BOARD_ROTATION_090_DEG 1
+#define SENSOR_BOARD_ROTATION_180_DEG 2
+#define SENSOR_BOARD_ROTATION_270_DEG 3
+
/* SPI protocol address bits */
#define DIR_READ (1<<7)
#define DIR_WRITE (0<<7)
@@ -78,6 +84,7 @@ static const int ERROR = -1;
/* register addresses */
#define ADDR_WHO_AM_I 0x0F
+#define WHO_I_AM_H 0xD7
#define WHO_I_AM 0xD4
#define ADDR_CTRL_REG1 0x20
@@ -85,8 +92,8 @@ static const int ERROR = -1;
/* keep lowpass low to avoid noise issues */
#define RATE_95HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4))
#define RATE_190HZ_LP_25HZ ((0<<7) | (1<<6) | (1<<5) | (1<<4))
-#define RATE_380HZ_LP_30HZ ((1<<7) | (0<<6) | (1<<5) | (1<<4))
-#define RATE_760HZ_LP_30HZ ((1<<7) | (1<<6) | (1<<5) | (1<<4))
+#define RATE_380HZ_LP_20HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4))
+#define RATE_760HZ_LP_30HZ ((1<<7) | (1<<6) | (0<<5) | (0<<4))
#define ADDR_CTRL_REG2 0x21
#define ADDR_CTRL_REG3 0x22
@@ -147,6 +154,10 @@ static const int ERROR = -1;
#define FIFO_CTRL_STREAM_TO_FIFO_MODE (3<<5)
#define FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
+#define L3GD20_DEFAULT_RATE 760
+#define L3GD20_DEFAULT_RANGE_DPS 2000
+#define L3GD20_DEFAULT_FILTER_FREQ 30
+
extern "C" { __EXPORT int l3gd20_main(int argc, char *argv[]); }
class L3GD20 : public device::SPI
@@ -184,10 +195,16 @@ private:
orb_advert_t _gyro_topic;
unsigned _current_rate;
- unsigned _current_range;
+ unsigned _orientation;
+
+ unsigned _read;
perf_counter_t _sample_perf;
+ math::LowPassFilter2p _gyro_filter_x;
+ math::LowPassFilter2p _gyro_filter_y;
+ math::LowPassFilter2p _gyro_filter_z;
+
/**
* Start automatic measurement.
*/
@@ -199,6 +216,11 @@ private:
void stop();
/**
+ * Reset the driver
+ */
+ void reset();
+
+ /**
* Static trampoline from the hrt_call context; because we don't have a
* generic hrt wrapper yet.
*
@@ -262,6 +284,14 @@ private:
int set_samplerate(unsigned frequency);
/**
+ * Set the lowpass filter of the driver
+ *
+ * @param samplerate The current samplerate
+ * @param frequency The cutoff frequency for the lowpass filter
+ */
+ void set_driver_lowpass_filter(float samplerate, float bandwidth);
+
+ /**
* Self test
*
* @return 0 on success, 1 on failure
@@ -284,8 +314,12 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
_gyro_range_rad_s(0.0f),
_gyro_topic(-1),
_current_rate(0),
- _current_range(0),
- _sample_perf(perf_alloc(PC_ELAPSED, "l3gd20_read"))
+ _orientation(SENSOR_BOARD_ROTATION_270_DEG),
+ _read(0),
+ _sample_perf(perf_alloc(PC_ELAPSED, "l3gd20_read")),
+ _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)
{
// enable debug() calls
_debug_enabled = true;
@@ -333,23 +367,7 @@ L3GD20::init()
memset(&_reports[0], 0, sizeof(_reports[0]));
_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_reports[0]);
- /* set default configuration */
- write_reg(ADDR_CTRL_REG1, REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
- write_reg(ADDR_CTRL_REG2, 0); /* disable high-pass filters */
- write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
- write_reg(ADDR_CTRL_REG4, REG4_BDU);
- write_reg(ADDR_CTRL_REG5, 0);
-
-
- write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
-
- /* disable FIFO. This makes things simpler and ensures we
- * aren't getting stale data. It means we must run the hrt
- * callback fast enough to not miss data. */
- write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE);
-
- set_range(500); /* default to 500dps */
- set_samplerate(0); /* max sample rate */
+ reset();
ret = OK;
out:
@@ -362,9 +380,24 @@ L3GD20::probe()
/* read dummy value to void to clear SPI statemachine on sensor */
(void)read_reg(ADDR_WHO_AM_I);
- /* verify that the device is attached and functioning */
- if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM)
+ /* verify that the device is attached and functioning, accept L3GD20 and L3GD20H */
+ if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
+
+ #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ _orientation = SENSOR_BOARD_ROTATION_270_DEG;
+ #elif CONFIG_ARCH_BOARD_PX4FMU_V2
+ _orientation = SENSOR_BOARD_ROTATION_270_DEG;
+ #else
+ #error This driver needs a board selection, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
+ #endif
+ return OK;
+ }
+
+
+ if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM_H) {
+ _orientation = SENSOR_BOARD_ROTATION_180_DEG;
return OK;
+ }
return -EIO;
}
@@ -434,8 +467,7 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT:
- /* With internal low pass filters enabled, 250 Hz is sufficient */
- return ioctl(filp, SENSORIOCSPOLLRATE, 250);
+ return ioctl(filp, SENSORIOCSPOLLRATE, L3GD20_DEFAULT_RATE);
/* adjust to a legal polling interval in Hz */
default: {
@@ -453,6 +485,11 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
/* XXX this is a bit shady, but no other way to adjust... */
_call.period = _call_interval = ticks;
+ /* adjust filters */
+ float cutoff_freq_hz = _gyro_filter_x.get_cutoff_freq();
+ float sample_rate = 1.0e6f/ticks;
+ set_driver_lowpass_filter(sample_rate, cutoff_freq_hz);
+
/* if we need to start the poll state machine, do it */
if (want_start)
start();
@@ -496,8 +533,8 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
return _num_reports - 1;
case SENSORIOCRESET:
- /* XXX implement */
- return -EINVAL;
+ reset();
+ return OK;
case GYROIOCSSAMPLERATE:
return set_samplerate(arg);
@@ -505,10 +542,16 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
case GYROIOCGSAMPLERATE:
return _current_rate;
- case GYROIOCSLOWPASS:
+ case GYROIOCSLOWPASS: {
+ float cutoff_freq_hz = arg;
+ float sample_rate = 1.0e6f / _call_interval;
+ set_driver_lowpass_filter(sample_rate, cutoff_freq_hz);
+
+ return OK;
+ }
+
case GYROIOCGLOWPASS:
- /* XXX not implemented due to wacky interaction with samplerate */
- return -EINVAL;
+ return _gyro_filter_x.get_cutoff_freq();
case GYROIOCSSCALE:
/* copy scale in */
@@ -521,10 +564,12 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
return OK;
case GYROIOCSRANGE:
+ /* arg should be in dps */
return set_range(arg);
case GYROIOCGRANGE:
- return _current_range;
+ /* convert to dps and round */
+ return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
case GYROIOCSELFTEST:
return self_test();
@@ -573,28 +618,33 @@ int
L3GD20::set_range(unsigned max_dps)
{
uint8_t bits = REG4_BDU;
+ float new_range_scale_dps_digit;
+ float new_range;
- if (max_dps == 0)
+ if (max_dps == 0) {
max_dps = 2000;
-
+ }
if (max_dps <= 250) {
- _current_range = 250;
+ new_range = 250;
bits |= RANGE_250DPS;
+ new_range_scale_dps_digit = 8.75e-3f;
} else if (max_dps <= 500) {
- _current_range = 500;
+ new_range = 500;
bits |= RANGE_500DPS;
+ new_range_scale_dps_digit = 17.5e-3f;
} else if (max_dps <= 2000) {
- _current_range = 2000;
+ new_range = 2000;
bits |= RANGE_2000DPS;
+ new_range_scale_dps_digit = 70e-3f;
} else {
return -EINVAL;
}
- _gyro_range_rad_s = _current_range / 180.0f * M_PI_F;
- _gyro_range_scale = _gyro_range_rad_s / 32768.0f;
+ _gyro_range_rad_s = new_range / 180.0f * M_PI_F;
+ _gyro_range_scale = new_range_scale_dps_digit / 180.0f * M_PI_F;
write_reg(ADDR_CTRL_REG4, bits);
return OK;
@@ -608,19 +658,20 @@ L3GD20::set_samplerate(unsigned frequency)
if (frequency == 0)
frequency = 760;
- if (frequency <= 95) {
+ /* use limits good for H or non-H models */
+ if (frequency <= 100) {
_current_rate = 95;
bits |= RATE_95HZ_LP_25HZ;
- } else if (frequency <= 190) {
+ } else if (frequency <= 200) {
_current_rate = 190;
bits |= RATE_190HZ_LP_25HZ;
- } else if (frequency <= 380) {
+ } else if (frequency <= 400) {
_current_rate = 380;
- bits |= RATE_380HZ_LP_30HZ;
+ bits |= RATE_380HZ_LP_20HZ;
- } else if (frequency <= 760) {
+ } else if (frequency <= 800) {
_current_rate = 760;
bits |= RATE_760HZ_LP_30HZ;
@@ -634,6 +685,14 @@ L3GD20::set_samplerate(unsigned frequency)
}
void
+L3GD20::set_driver_lowpass_filter(float samplerate, float bandwidth)
+{
+ _gyro_filter_x.set_cutoff_frequency(samplerate, bandwidth);
+ _gyro_filter_y.set_cutoff_frequency(samplerate, bandwidth);
+ _gyro_filter_z.set_cutoff_frequency(samplerate, bandwidth);
+}
+
+void
L3GD20::start()
{
/* make sure we are stopped first */
@@ -653,6 +712,30 @@ L3GD20::stop()
}
void
+L3GD20::reset()
+{
+ /* set default configuration */
+ write_reg(ADDR_CTRL_REG1, REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
+ write_reg(ADDR_CTRL_REG2, 0); /* disable high-pass filters */
+ write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
+ write_reg(ADDR_CTRL_REG4, REG4_BDU);
+ write_reg(ADDR_CTRL_REG5, 0);
+
+ write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
+
+ /* disable FIFO. This makes things simpler and ensures we
+ * aren't getting stale data. It means we must run the hrt
+ * callback fast enough to not miss data. */
+ write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE);
+
+ set_samplerate(L3GD20_DEFAULT_RATE);
+ set_range(L3GD20_DEFAULT_RANGE_DPS);
+ set_driver_lowpass_filter(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ);
+
+ _read = 0;
+}
+
+void
L3GD20::measure_trampoline(void *arg)
{
L3GD20 *dev = (L3GD20 *)arg;
@@ -701,14 +784,43 @@ L3GD20::measure()
*/
report->timestamp = hrt_absolute_time();
- /* swap x and y and negate y */
- report->x_raw = raw_report.y;
- report->y_raw = ((raw_report.x == -32768) ? 32767 : -raw_report.x);
+ switch (_orientation) {
+
+ case SENSOR_BOARD_ROTATION_000_DEG:
+ /* keep axes in place */
+ report->x_raw = raw_report.x;
+ report->y_raw = raw_report.y;
+ break;
+
+ case SENSOR_BOARD_ROTATION_090_DEG:
+ /* swap x and y */
+ report->x_raw = raw_report.y;
+ report->y_raw = raw_report.x;
+ break;
+
+ case SENSOR_BOARD_ROTATION_180_DEG:
+ /* swap x and y and negate both */
+ report->x_raw = ((raw_report.x == -32768) ? 32767 : -raw_report.x);
+ report->y_raw = ((raw_report.y == -32768) ? 32767 : -raw_report.y);
+ break;
+
+ case SENSOR_BOARD_ROTATION_270_DEG:
+ /* swap x and y and negate y */
+ report->x_raw = raw_report.y;
+ report->y_raw = ((raw_report.x == -32768) ? 32767 : -raw_report.x);
+ break;
+ }
+
report->z_raw = raw_report.z;
report->x = ((report->x_raw * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
report->y = ((report->y_raw * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
report->z = ((report->z_raw * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
+
+ report->x = _gyro_filter_x.apply(report->x);
+ report->y = _gyro_filter_y.apply(report->y);
+ report->z = _gyro_filter_z.apply(report->z);
+
report->scaling = _gyro_range_scale;
report->range_rad_s = _gyro_range_rad_s;
@@ -726,6 +838,8 @@ L3GD20::measure()
if (_gyro_topic > 0)
orb_publish(ORB_ID(sensor_gyro), _gyro_topic, report);
+ _read++;
+
/* stop the perf counter */
perf_end(_sample_perf);
}
@@ -733,6 +847,7 @@ L3GD20::measure()
void
L3GD20::print_info()
{
+ printf("gyro reads: %u\n", _read);
perf_print_counter(_sample_perf);
printf("report queue: %u (%u/%u @ %p)\n",
_num_reports, _oldest_report, _next_report, _reports);
@@ -782,7 +897,7 @@ start()
int fd;
if (g_dev != nullptr)
- errx(1, "already started");
+ errx(0, "already started");
/* create the driver */
g_dev = new L3GD20(1 /* XXX magic number */, GYRO_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
@@ -871,7 +986,7 @@ reset()
err(1, "driver reset failed");
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
- err(1, "driver poll restart failed");
+ err(1, "accel pollrate reset failed");
exit(0);
}
diff --git a/src/drivers/led/led.cpp b/src/drivers/led/led.cpp
index 04b565358..a37eaca53 100644
--- a/src/drivers/led/led.cpp
+++ b/src/drivers/led/led.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -52,6 +52,7 @@ __BEGIN_DECLS
extern void led_init();
extern void led_on(int led);
extern void led_off(int led);
+extern void led_toggle(int led);
__END_DECLS
class LED : device::CDev
@@ -98,6 +99,11 @@ LED::ioctl(struct file *filp, int cmd, unsigned long arg)
led_off(arg);
break;
+ case LED_TOGGLE:
+ led_toggle(arg);
+ break;
+
+
default:
result = CDev::ioctl(filp, cmd, arg);
}
@@ -110,11 +116,11 @@ LED *gLED;
}
void
-drv_led_start()
+drv_led_start(void)
{
if (gLED == nullptr) {
gLED = new LED;
if (gLED != nullptr)
gLED->init();
}
-} \ No newline at end of file
+}
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
new file mode 100644
index 000000000..cf5f8d94c
--- /dev/null
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -0,0 +1,1659 @@
+/****************************************************************************
+ *
+ * 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 lsm303d.cpp
+ * Driver for the ST LSM303D MEMS accelerometer / magnetometer connected via SPI.
+ */
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stddef.h>
+#include <stdlib.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 <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/clock.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/device/spi.h>
+#include <drivers/drv_accel.h>
+#include <drivers/drv_mag.h>
+
+#include <board_config.h>
+#include <mathlib/math/filter/LowPassFilter2p.hpp>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+/* SPI protocol address bits */
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+
+
+/* register addresses: A: accel, M: mag, T: temp */
+#define ADDR_WHO_AM_I 0x0F
+#define WHO_I_AM 0x49
+
+#define ADDR_OUT_L_T 0x05
+#define ADDR_OUT_H_T 0x06
+#define ADDR_STATUS_M 0x07
+#define ADDR_OUT_X_L_M 0x08
+#define ADDR_OUT_X_H_M 0x09
+#define ADDR_OUT_Y_L_M 0x0A
+#define ADDR_OUT_Y_H_M 0x0B
+#define ADDR_OUT_Z_L_M 0x0C
+#define ADDR_OUT_Z_H_M 0x0D
+
+#define ADDR_OUT_TEMP_A 0x26
+#define ADDR_STATUS_A 0x27
+#define ADDR_OUT_X_L_A 0x28
+#define ADDR_OUT_X_H_A 0x29
+#define ADDR_OUT_Y_L_A 0x2A
+#define ADDR_OUT_Y_H_A 0x2B
+#define ADDR_OUT_Z_L_A 0x2C
+#define ADDR_OUT_Z_H_A 0x2D
+
+#define ADDR_CTRL_REG0 0x1F
+#define ADDR_CTRL_REG1 0x20
+#define ADDR_CTRL_REG2 0x21
+#define ADDR_CTRL_REG3 0x22
+#define ADDR_CTRL_REG4 0x23
+#define ADDR_CTRL_REG5 0x24
+#define ADDR_CTRL_REG6 0x25
+#define ADDR_CTRL_REG7 0x26
+
+#define REG1_RATE_BITS_A ((1<<7) | (1<<6) | (1<<5) | (1<<4))
+#define REG1_POWERDOWN_A ((0<<7) | (0<<6) | (0<<5) | (0<<4))
+#define REG1_RATE_3_125HZ_A ((0<<7) | (0<<6) | (0<<5) | (1<<4))
+#define REG1_RATE_6_25HZ_A ((0<<7) | (0<<6) | (1<<5) | (0<<4))
+#define REG1_RATE_12_5HZ_A ((0<<7) | (0<<6) | (1<<5) | (1<<4))
+#define REG1_RATE_25HZ_A ((0<<7) | (1<<6) | (0<<5) | (0<<4))
+#define REG1_RATE_50HZ_A ((0<<7) | (1<<6) | (0<<5) | (1<<4))
+#define REG1_RATE_100HZ_A ((0<<7) | (1<<6) | (1<<5) | (0<<4))
+#define REG1_RATE_200HZ_A ((0<<7) | (1<<6) | (1<<5) | (1<<4))
+#define REG1_RATE_400HZ_A ((1<<7) | (0<<6) | (0<<5) | (0<<4))
+#define REG1_RATE_800HZ_A ((1<<7) | (0<<6) | (0<<5) | (1<<4))
+#define REG1_RATE_1600HZ_A ((1<<7) | (0<<6) | (1<<5) | (0<<4))
+
+#define REG1_BDU_UPDATE (1<<3)
+#define REG1_Z_ENABLE_A (1<<2)
+#define REG1_Y_ENABLE_A (1<<1)
+#define REG1_X_ENABLE_A (1<<0)
+
+#define REG2_ANTIALIAS_FILTER_BW_BITS_A ((1<<7) | (1<<6))
+#define REG2_AA_FILTER_BW_773HZ_A ((0<<7) | (0<<6))
+#define REG2_AA_FILTER_BW_194HZ_A ((0<<7) | (1<<6))
+#define REG2_AA_FILTER_BW_362HZ_A ((1<<7) | (0<<6))
+#define REG2_AA_FILTER_BW_50HZ_A ((1<<7) | (1<<6))
+
+#define REG2_FULL_SCALE_BITS_A ((1<<5) | (1<<4) | (1<<3))
+#define REG2_FULL_SCALE_2G_A ((0<<5) | (0<<4) | (0<<3))
+#define REG2_FULL_SCALE_4G_A ((0<<5) | (0<<4) | (1<<3))
+#define REG2_FULL_SCALE_6G_A ((0<<5) | (1<<4) | (0<<3))
+#define REG2_FULL_SCALE_8G_A ((0<<5) | (1<<4) | (1<<3))
+#define REG2_FULL_SCALE_16G_A ((1<<5) | (0<<4) | (0<<3))
+
+#define REG5_ENABLE_T (1<<7)
+
+#define REG5_RES_HIGH_M ((1<<6) | (1<<5))
+#define REG5_RES_LOW_M ((0<<6) | (0<<5))
+
+#define REG5_RATE_BITS_M ((1<<4) | (1<<3) | (1<<2))
+#define REG5_RATE_3_125HZ_M ((0<<4) | (0<<3) | (0<<2))
+#define REG5_RATE_6_25HZ_M ((0<<4) | (0<<3) | (1<<2))
+#define REG5_RATE_12_5HZ_M ((0<<4) | (1<<3) | (0<<2))
+#define REG5_RATE_25HZ_M ((0<<4) | (1<<3) | (1<<2))
+#define REG5_RATE_50HZ_M ((1<<4) | (0<<3) | (0<<2))
+#define REG5_RATE_100HZ_M ((1<<4) | (0<<3) | (1<<2))
+#define REG5_RATE_DO_NOT_USE_M ((1<<4) | (1<<3) | (0<<2))
+
+#define REG6_FULL_SCALE_BITS_M ((1<<6) | (1<<5))
+#define REG6_FULL_SCALE_2GA_M ((0<<6) | (0<<5))
+#define REG6_FULL_SCALE_4GA_M ((0<<6) | (1<<5))
+#define REG6_FULL_SCALE_8GA_M ((1<<6) | (0<<5))
+#define REG6_FULL_SCALE_12GA_M ((1<<6) | (1<<5))
+
+#define REG7_CONT_MODE_M ((0<<1) | (0<<0))
+
+
+#define INT_CTRL_M 0x12
+#define INT_SRC_M 0x13
+
+/* default values for this device */
+#define LSM303D_ACCEL_DEFAULT_RANGE_G 8
+#define LSM303D_ACCEL_DEFAULT_RATE 800
+#define LSM303D_ACCEL_DEFAULT_ONCHIP_FILTER_FREQ 50
+#define LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 30
+
+#define LSM303D_MAG_DEFAULT_RANGE_GA 2
+#define LSM303D_MAG_DEFAULT_RATE 100
+
+#define LSM303D_ONE_G 9.80665f
+
+extern "C" { __EXPORT int lsm303d_main(int argc, char *argv[]); }
+
+
+class LSM303D_mag;
+
+class LSM303D : public device::SPI
+{
+public:
+ LSM303D(int bus, const char* path, spi_dev_e device);
+ virtual ~LSM303D();
+
+ 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();
+
+ friend class LSM303D_mag;
+
+ virtual ssize_t mag_read(struct file *filp, char *buffer, size_t buflen);
+ virtual int mag_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+private:
+
+ LSM303D_mag *_mag;
+
+ struct hrt_call _accel_call;
+ struct hrt_call _mag_call;
+
+ unsigned _call_accel_interval;
+ unsigned _call_mag_interval;
+
+ unsigned _num_accel_reports;
+ volatile unsigned _next_accel_report;
+ volatile unsigned _oldest_accel_report;
+ struct accel_report *_accel_reports;
+
+ unsigned _num_mag_reports;
+ volatile unsigned _next_mag_report;
+ volatile unsigned _oldest_mag_report;
+ struct mag_report *_mag_reports;
+
+ struct accel_scale _accel_scale;
+ unsigned _accel_range_m_s2;
+ float _accel_range_scale;
+ unsigned _accel_samplerate;
+ unsigned _accel_onchip_filter_bandwith;
+
+ struct mag_scale _mag_scale;
+ unsigned _mag_range_ga;
+ float _mag_range_scale;
+ unsigned _mag_samplerate;
+
+ orb_advert_t _accel_topic;
+ orb_advert_t _mag_topic;
+
+ unsigned _accel_read;
+ unsigned _mag_read;
+
+ perf_counter_t _accel_sample_perf;
+ perf_counter_t _mag_sample_perf;
+
+ math::LowPassFilter2p _accel_filter_x;
+ math::LowPassFilter2p _accel_filter_y;
+ math::LowPassFilter2p _accel_filter_z;
+
+ /**
+ * Start automatic measurement.
+ */
+ void start();
+
+ /**
+ * Stop automatic measurement.
+ */
+ void stop();
+
+ /**
+ * Reset chip.
+ *
+ * Resets the chip and measurements ranges, but not scale and offset.
+ */
+ void reset();
+
+ /**
+ * Static trampoline from the hrt_call context; because we don't have a
+ * generic hrt wrapper yet.
+ *
+ * Called by the HRT in interrupt context at the specified rate if
+ * automatic polling is enabled.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void measure_trampoline(void *arg);
+
+ /**
+ * Static trampoline for the mag because it runs at a lower rate
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void mag_measure_trampoline(void *arg);
+
+ /**
+ * Fetch accel measurements from the sensor and update the report ring.
+ */
+ void measure();
+
+ /**
+ * Fetch mag measurements from the sensor and update the report ring.
+ */
+ void mag_measure();
+
+ /**
+ * Accel self test
+ *
+ * @return 0 on success, 1 on failure
+ */
+ int accel_self_test();
+
+ /**
+ * Mag self test
+ *
+ * @return 0 on success, 1 on failure
+ */
+ int mag_self_test();
+
+ /**
+ * Read a register from the LSM303D
+ *
+ * @param The register to read.
+ * @return The value that was read.
+ */
+ uint8_t read_reg(unsigned reg);
+
+ /**
+ * Write a register in the LSM303D
+ *
+ * @param reg The register to write.
+ * @param value The new value to write.
+ */
+ void write_reg(unsigned reg, uint8_t value);
+
+ /**
+ * Modify a register in the LSM303D
+ *
+ * Bits are cleared before bits are set.
+ *
+ * @param reg The register to modify.
+ * @param clearbits Bits in the register to clear.
+ * @param setbits Bits in the register to set.
+ */
+ void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
+
+ /**
+ * Set the LSM303D accel measurement range.
+ *
+ * @param max_g The measurement range of the accel is in g (9.81m/s^2)
+ * Zero selects the maximum supported range.
+ * @return OK if the value can be supported, -ERANGE otherwise.
+ */
+ int accel_set_range(unsigned max_g);
+
+ /**
+ * Set the LSM303D mag measurement range.
+ *
+ * @param max_ga The measurement range of the mag is in Ga
+ * Zero selects the maximum supported range.
+ * @return OK if the value can be supported, -ERANGE otherwise.
+ */
+ int mag_set_range(unsigned max_g);
+
+ /**
+ * Set the LSM303D on-chip anti-alias filter bandwith.
+ *
+ * @param bandwidth The anti-alias filter bandwidth in Hz
+ * Zero selects the highest bandwidth
+ * @return OK if the value can be supported, -ERANGE otherwise.
+ */
+ int accel_set_onchip_lowpass_filter_bandwidth(unsigned bandwidth);
+
+ /**
+ * Set the driver lowpass filter bandwidth.
+ *
+ * @param bandwidth The anti-alias filter bandwidth in Hz
+ * Zero selects the highest bandwidth
+ * @return OK if the value can be supported, -ERANGE otherwise.
+ */
+ int accel_set_driver_lowpass_filter(float samplerate, float bandwidth);
+
+ /**
+ * Set the LSM303D internal accel sampling frequency.
+ *
+ * @param frequency The internal accel sampling frequency is set to not less than
+ * this value.
+ * Zero selects the maximum rate supported.
+ * @return OK if the value can be supported.
+ */
+ int accel_set_samplerate(unsigned frequency);
+
+ /**
+ * Set the LSM303D internal mag sampling frequency.
+ *
+ * @param frequency The internal mag sampling frequency is set to not less than
+ * this value.
+ * Zero selects the maximum rate supported.
+ * @return OK if the value can be supported.
+ */
+ int mag_set_samplerate(unsigned frequency);
+};
+
+/**
+ * Helper class implementing the mag driver node.
+ */
+class LSM303D_mag : public device::CDev
+{
+public:
+ LSM303D_mag(LSM303D *parent);
+ ~LSM303D_mag();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+protected:
+ friend class LSM303D;
+
+ void parent_poll_notify();
+private:
+ LSM303D *_parent;
+
+ void measure();
+
+ void measure_trampoline(void *arg);
+};
+
+
+/* helper macro for handling report buffer indices */
+#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
+
+
+LSM303D::LSM303D(int bus, const char* path, spi_dev_e device) :
+ SPI("LSM303D", path, bus, device, SPIDEV_MODE3, 8000000),
+ _mag(new LSM303D_mag(this)),
+ _call_accel_interval(0),
+ _call_mag_interval(0),
+ _num_accel_reports(0),
+ _next_accel_report(0),
+ _oldest_accel_report(0),
+ _accel_reports(nullptr),
+ _num_mag_reports(0),
+ _next_mag_report(0),
+ _oldest_mag_report(0),
+ _mag_reports(nullptr),
+ _accel_range_m_s2(0.0f),
+ _accel_range_scale(0.0f),
+ _accel_samplerate(0),
+ _accel_onchip_filter_bandwith(0),
+ _mag_range_ga(0.0f),
+ _mag_range_scale(0.0f),
+ _mag_samplerate(0),
+ _accel_topic(-1),
+ _mag_topic(-1),
+ _accel_read(0),
+ _mag_read(0),
+ _accel_sample_perf(perf_alloc(PC_ELAPSED, "lsm303d_accel_read")),
+ _mag_sample_perf(perf_alloc(PC_ELAPSED, "lsm303d_mag_read")),
+ _accel_filter_x(LSM303D_ACCEL_DEFAULT_RATE, LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
+ _accel_filter_y(LSM303D_ACCEL_DEFAULT_RATE, LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
+ _accel_filter_z(LSM303D_ACCEL_DEFAULT_RATE, LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ)
+{
+ // enable debug() calls
+ _debug_enabled = true;
+
+ // default scale factors
+ _accel_scale.x_offset = 0.0f;
+ _accel_scale.x_scale = 1.0f;
+ _accel_scale.y_offset = 0.0f;
+ _accel_scale.y_scale = 1.0f;
+ _accel_scale.z_offset = 0.0f;
+ _accel_scale.z_scale = 1.0f;
+
+ _mag_scale.x_offset = 0.0f;
+ _mag_scale.x_scale = 1.0f;
+ _mag_scale.y_offset = 0.0f;
+ _mag_scale.y_scale = 1.0f;
+ _mag_scale.z_offset = 0.0f;
+ _mag_scale.z_scale = 1.0f;
+}
+
+LSM303D::~LSM303D()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ /* free any existing reports */
+ if (_accel_reports != nullptr)
+ delete[] _accel_reports;
+ if (_mag_reports != nullptr)
+ delete[] _mag_reports;
+
+ delete _mag;
+
+ /* delete the perf counter */
+ perf_free(_accel_sample_perf);
+ perf_free(_mag_sample_perf);
+}
+
+int
+LSM303D::init()
+{
+ int ret = ERROR;
+ int mag_ret;
+
+ /* do SPI init (and probe) first */
+ if (SPI::init() != OK)
+ goto out;
+
+ /* allocate basic report buffers */
+ _num_accel_reports = 2;
+ _oldest_accel_report = _next_accel_report = 0;
+ _accel_reports = new struct accel_report[_num_accel_reports];
+
+ if (_accel_reports == nullptr)
+ goto out;
+
+ /* advertise accel topic */
+ memset(&_accel_reports[0], 0, sizeof(_accel_reports[0]));
+ _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_reports[0]);
+
+ _num_mag_reports = 2;
+ _oldest_mag_report = _next_mag_report = 0;
+ _mag_reports = new struct mag_report[_num_mag_reports];
+
+ if (_mag_reports == nullptr)
+ goto out;
+
+ reset();
+
+ /* advertise mag topic */
+ memset(&_mag_reports[0], 0, sizeof(_mag_reports[0]));
+ _mag_topic = orb_advertise(ORB_ID(sensor_mag), &_mag_reports[0]);
+
+ /* do CDev init for the mag device node, keep it optional */
+ mag_ret = _mag->init();
+
+ if (mag_ret != OK) {
+ _mag_topic = -1;
+ }
+
+ ret = OK;
+out:
+ return ret;
+}
+
+void
+LSM303D::reset()
+{
+ /* enable accel*/
+ write_reg(ADDR_CTRL_REG1, REG1_X_ENABLE_A | REG1_Y_ENABLE_A | REG1_Z_ENABLE_A | REG1_BDU_UPDATE);
+
+ /* enable mag */
+ write_reg(ADDR_CTRL_REG7, REG7_CONT_MODE_M);
+ write_reg(ADDR_CTRL_REG5, REG5_RES_HIGH_M);
+
+ accel_set_range(LSM303D_ACCEL_DEFAULT_RANGE_G);
+ accel_set_samplerate(LSM303D_ACCEL_DEFAULT_RATE);
+ accel_set_driver_lowpass_filter((float)LSM303D_ACCEL_DEFAULT_RATE, (float)LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ);
+ accel_set_onchip_lowpass_filter_bandwidth(LSM303D_ACCEL_DEFAULT_ONCHIP_FILTER_FREQ);
+
+ mag_set_range(LSM303D_MAG_DEFAULT_RANGE_GA);
+ mag_set_samplerate(LSM303D_MAG_DEFAULT_RATE);
+
+ _accel_read = 0;
+ _mag_read = 0;
+}
+
+int
+LSM303D::probe()
+{
+ /* read dummy value to void to clear SPI statemachine on sensor */
+ (void)read_reg(ADDR_WHO_AM_I);
+
+ /* verify that the device is attached and functioning */
+ if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM)
+ return OK;
+
+ return -EIO;
+}
+
+ssize_t
+LSM303D::read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct accel_report);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1)
+ return -ENOSPC;
+
+ /* if automatic measurement is enabled */
+ if (_call_accel_interval > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ * Note that we may be pre-empted by the measurement code while we are doing this;
+ * we are careful to avoid racing with it.
+ */
+ while (count--) {
+ if (_oldest_accel_report != _next_accel_report) {
+ memcpy(buffer, _accel_reports + _oldest_accel_report, sizeof(*_accel_reports));
+ ret += sizeof(_accel_reports[0]);
+ INCREMENT(_oldest_accel_report, _num_accel_reports);
+ }
+ }
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement */
+ _oldest_accel_report = _next_accel_report = 0;
+ measure();
+
+ /* measurement will have generated a report, copy it out */
+ memcpy(buffer, _accel_reports, sizeof(*_accel_reports));
+ ret = sizeof(*_accel_reports);
+
+ return ret;
+}
+
+ssize_t
+LSM303D::mag_read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct mag_report);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1)
+ return -ENOSPC;
+
+ /* if automatic measurement is enabled */
+ if (_call_mag_interval > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ * Note that we may be pre-empted by the measurement code while we are doing this;
+ * we are careful to avoid racing with it.
+ */
+ while (count--) {
+ if (_oldest_mag_report != _next_mag_report) {
+ memcpy(buffer, _mag_reports + _oldest_mag_report, sizeof(*_mag_reports));
+ ret += sizeof(_mag_reports[0]);
+ INCREMENT(_oldest_mag_report, _num_mag_reports);
+ }
+ }
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement */
+ _oldest_mag_report = _next_mag_report = 0;
+ measure();
+
+ /* measurement will have generated a report, copy it out */
+ memcpy(buffer, _mag_reports, sizeof(*_mag_reports));
+ ret = sizeof(*_mag_reports);
+
+ return ret;
+}
+
+int
+LSM303D::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case SENSORIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _call_accel_interval = 0;
+ return OK;
+
+ /* external signalling not supported */
+ case SENSOR_POLLRATE_EXTERNAL:
+
+ /* zero would be bad */
+ case 0:
+ return -EINVAL;
+
+ /* set default/max polling rate */
+ case SENSOR_POLLRATE_MAX:
+ return ioctl(filp, SENSORIOCSPOLLRATE, 1600);
+
+ case SENSOR_POLLRATE_DEFAULT:
+ return ioctl(filp, SENSORIOCSPOLLRATE, LSM303D_ACCEL_DEFAULT_RATE);
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_call_accel_interval == 0);
+
+ /* convert hz to hrt interval via microseconds */
+ unsigned ticks = 1000000 / arg;
+
+ /* check against maximum sane rate */
+ if (ticks < 500)
+ return -EINVAL;
+
+ /* adjust filters */
+ accel_set_driver_lowpass_filter((float)arg, _accel_filter_x.get_cutoff_freq());
+
+ /* update interval for next measurement */
+ /* XXX this is a bit shady, but no other way to adjust... */
+ _accel_call.period = _call_accel_interval = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
+
+ return OK;
+ }
+ }
+ }
+
+ case SENSORIOCGPOLLRATE:
+ if (_call_accel_interval == 0)
+ return SENSOR_POLLRATE_MANUAL;
+
+ return 1000000 / _call_accel_interval;
+
+ case SENSORIOCSQUEUEDEPTH: {
+ /* account for sentinel in the ring */
+ arg++;
+
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 2) || (arg > 100))
+ return -EINVAL;
+
+ /* allocate new buffer */
+ struct accel_report *buf = new struct accel_report[arg];
+
+ if (nullptr == buf)
+ return -ENOMEM;
+
+ /* reset the measurement state machine with the new buffer, free the old */
+ stop();
+ delete[] _accel_reports;
+ _num_accel_reports = arg;
+ _accel_reports = buf;
+ start();
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _num_accel_reports - 1;
+
+ case SENSORIOCRESET:
+ reset();
+ return OK;
+
+ case ACCELIOCSSAMPLERATE:
+ return accel_set_samplerate(arg);
+
+ case ACCELIOCGSAMPLERATE:
+ return _accel_samplerate;
+
+ case ACCELIOCSLOWPASS: {
+ return accel_set_driver_lowpass_filter((float)_accel_samplerate, (float)arg);
+ }
+
+ case ACCELIOCGLOWPASS:
+ return _accel_filter_x.get_cutoff_freq();
+
+ case ACCELIOCSSCALE: {
+ /* copy scale, but only if off by a few percent */
+ struct accel_scale *s = (struct accel_scale *) arg;
+ float sum = s->x_scale + s->y_scale + s->z_scale;
+ if (sum > 2.0f && sum < 4.0f) {
+ memcpy(&_accel_scale, s, sizeof(_accel_scale));
+ return OK;
+ } else {
+ return -EINVAL;
+ }
+ }
+
+ case ACCELIOCSRANGE:
+ /* arg needs to be in G */
+ return accel_set_range(arg);
+
+ case ACCELIOCGRANGE:
+ /* convert to m/s^2 and return rounded in G */
+ return (unsigned long)((_accel_range_m_s2)/LSM303D_ONE_G + 0.5f);
+
+ case ACCELIOCGSCALE:
+ /* copy scale out */
+ memcpy((struct accel_scale *) arg, &_accel_scale, sizeof(_accel_scale));
+ return OK;
+
+ case ACCELIOCSELFTEST:
+ return accel_self_test();
+
+ default:
+ /* give it to the superclass */
+ return SPI::ioctl(filp, cmd, arg);
+ }
+}
+
+int
+LSM303D::mag_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case SENSORIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _call_mag_interval = 0;
+ return OK;
+
+ /* external signalling 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:
+ /* 100 Hz is max for mag */
+ return mag_ioctl(filp, SENSORIOCSPOLLRATE, 100);
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_call_mag_interval == 0);
+
+ /* convert hz to hrt interval via microseconds */
+ unsigned ticks = 1000000 / arg;
+
+ /* check against maximum sane rate */
+ if (ticks < 1000)
+ return -EINVAL;
+
+ /* update interval for next measurement */
+ /* XXX this is a bit shady, but no other way to adjust... */
+ _mag_call.period = _call_mag_interval = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
+
+ return OK;
+ }
+ }
+ }
+
+ case SENSORIOCGPOLLRATE:
+ if (_call_mag_interval == 0)
+ return SENSOR_POLLRATE_MANUAL;
+
+ return 1000000 / _call_mag_interval;
+
+ case SENSORIOCSQUEUEDEPTH: {
+ /* account for sentinel in the ring */
+ arg++;
+
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 2) || (arg > 100))
+ return -EINVAL;
+
+ /* allocate new buffer */
+ struct mag_report *buf = new struct mag_report[arg];
+
+ if (nullptr == buf)
+ return -ENOMEM;
+
+ /* reset the measurement state machine with the new buffer, free the old */
+ stop();
+ delete[] _mag_reports;
+ _num_mag_reports = arg;
+ _mag_reports = buf;
+ start();
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _num_mag_reports - 1;
+
+ case SENSORIOCRESET:
+ reset();
+ return OK;
+
+ case MAGIOCSSAMPLERATE:
+ return mag_set_samplerate(arg);
+
+ case MAGIOCGSAMPLERATE:
+ return _mag_samplerate;
+
+ case MAGIOCSLOWPASS:
+ case MAGIOCGLOWPASS:
+ /* not supported, no internal filtering */
+ return -EINVAL;
+
+ case MAGIOCSSCALE:
+ /* copy scale in */
+ memcpy(&_mag_scale, (struct mag_scale *) arg, sizeof(_mag_scale));
+ return OK;
+
+ case MAGIOCGSCALE:
+ /* copy scale out */
+ memcpy((struct mag_scale *) arg, &_mag_scale, sizeof(_mag_scale));
+ return OK;
+
+ case MAGIOCSRANGE:
+ return mag_set_range(arg);
+
+ case MAGIOCGRANGE:
+ return _mag_range_ga;
+
+ case MAGIOCSELFTEST:
+ return mag_self_test();
+
+ case MAGIOCGEXTERNAL:
+ /* no external mag board yet */
+ return 0;
+
+ default:
+ /* give it to the superclass */
+ return SPI::ioctl(filp, cmd, arg);
+ }
+}
+
+int
+LSM303D::accel_self_test()
+{
+ if (_accel_read == 0)
+ return 1;
+
+ /* inspect accel offsets */
+ if (fabsf(_accel_scale.x_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_accel_scale.x_scale - 1.0f) > 0.4f || fabsf(_accel_scale.x_scale - 1.0f) < 0.000001f)
+ return 1;
+
+ if (fabsf(_accel_scale.y_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_accel_scale.y_scale - 1.0f) > 0.4f || fabsf(_accel_scale.y_scale - 1.0f) < 0.000001f)
+ return 1;
+
+ if (fabsf(_accel_scale.z_offset) < 0.000001f)
+ return 1;
+ if (fabsf(_accel_scale.z_scale - 1.0f) > 0.4f || fabsf(_accel_scale.z_scale - 1.0f) < 0.000001f)
+ return 1;
+
+ return 0;
+}
+
+int
+LSM303D::mag_self_test()
+{
+ if (_mag_read == 0)
+ return 1;
+
+ /**
+ * inspect mag offsets
+ * don't check mag scale because it seems this is calibrated on chip
+ */
+ if (fabsf(_mag_scale.x_offset) < 0.000001f)
+ return 1;
+
+ if (fabsf(_mag_scale.y_offset) < 0.000001f)
+ return 1;
+
+ if (fabsf(_mag_scale.z_offset) < 0.000001f)
+ return 1;
+
+ return 0;
+}
+
+uint8_t
+LSM303D::read_reg(unsigned reg)
+{
+ uint8_t cmd[2];
+
+ cmd[0] = reg | DIR_READ;
+
+ transfer(cmd, cmd, sizeof(cmd));
+
+ return cmd[1];
+}
+
+void
+LSM303D::write_reg(unsigned reg, uint8_t value)
+{
+ uint8_t cmd[2];
+
+ cmd[0] = reg | DIR_WRITE;
+ cmd[1] = value;
+
+ transfer(cmd, nullptr, sizeof(cmd));
+}
+
+void
+LSM303D::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
+{
+ uint8_t val;
+
+ val = read_reg(reg);
+ val &= ~clearbits;
+ val |= setbits;
+ write_reg(reg, val);
+}
+
+int
+LSM303D::accel_set_range(unsigned max_g)
+{
+ uint8_t setbits = 0;
+ uint8_t clearbits = REG2_FULL_SCALE_BITS_A;
+ float new_scale_g_digit = 0.0f;
+
+ if (max_g == 0)
+ max_g = 16;
+
+ if (max_g <= 2) {
+ _accel_range_m_s2 = 2.0f*LSM303D_ONE_G;
+ setbits |= REG2_FULL_SCALE_2G_A;
+ new_scale_g_digit = 0.061e-3f;
+
+ } else if (max_g <= 4) {
+ _accel_range_m_s2 = 4.0f*LSM303D_ONE_G;
+ setbits |= REG2_FULL_SCALE_4G_A;
+ new_scale_g_digit = 0.122e-3f;
+
+ } else if (max_g <= 6) {
+ _accel_range_m_s2 = 6.0f*LSM303D_ONE_G;
+ setbits |= REG2_FULL_SCALE_6G_A;
+ new_scale_g_digit = 0.183e-3f;
+
+ } else if (max_g <= 8) {
+ _accel_range_m_s2 = 8.0f*LSM303D_ONE_G;
+ setbits |= REG2_FULL_SCALE_8G_A;
+ new_scale_g_digit = 0.244e-3f;
+
+ } else if (max_g <= 16) {
+ _accel_range_m_s2 = 16.0f*LSM303D_ONE_G;
+ setbits |= REG2_FULL_SCALE_16G_A;
+ new_scale_g_digit = 0.732e-3f;
+
+ } else {
+ return -EINVAL;
+ }
+
+ _accel_range_scale = new_scale_g_digit * LSM303D_ONE_G;
+
+ modify_reg(ADDR_CTRL_REG2, clearbits, setbits);
+
+ return OK;
+}
+
+int
+LSM303D::mag_set_range(unsigned max_ga)
+{
+ uint8_t setbits = 0;
+ uint8_t clearbits = REG6_FULL_SCALE_BITS_M;
+ float new_scale_ga_digit = 0.0f;
+
+ if (max_ga == 0)
+ max_ga = 12;
+
+ if (max_ga <= 2) {
+ _mag_range_ga = 2;
+ setbits |= REG6_FULL_SCALE_2GA_M;
+ new_scale_ga_digit = 0.080e-3f;
+
+ } else if (max_ga <= 4) {
+ _mag_range_ga = 4;
+ setbits |= REG6_FULL_SCALE_4GA_M;
+ new_scale_ga_digit = 0.160e-3f;
+
+ } else if (max_ga <= 8) {
+ _mag_range_ga = 8;
+ setbits |= REG6_FULL_SCALE_8GA_M;
+ new_scale_ga_digit = 0.320e-3f;
+
+ } else if (max_ga <= 12) {
+ _mag_range_ga = 12;
+ setbits |= REG6_FULL_SCALE_12GA_M;
+ new_scale_ga_digit = 0.479e-3f;
+
+ } else {
+ return -EINVAL;
+ }
+
+ _mag_range_scale = new_scale_ga_digit;
+
+ modify_reg(ADDR_CTRL_REG6, clearbits, setbits);
+
+ return OK;
+}
+
+int
+LSM303D::accel_set_onchip_lowpass_filter_bandwidth(unsigned bandwidth)
+{
+ uint8_t setbits = 0;
+ uint8_t clearbits = REG2_ANTIALIAS_FILTER_BW_BITS_A;
+
+ if (bandwidth == 0)
+ bandwidth = 773;
+
+ if (bandwidth <= 50) {
+ setbits |= REG2_AA_FILTER_BW_50HZ_A;
+ _accel_onchip_filter_bandwith = 50;
+
+ } else if (bandwidth <= 194) {
+ setbits |= REG2_AA_FILTER_BW_194HZ_A;
+ _accel_onchip_filter_bandwith = 194;
+
+ } else if (bandwidth <= 362) {
+ setbits |= REG2_AA_FILTER_BW_362HZ_A;
+ _accel_onchip_filter_bandwith = 362;
+
+ } else if (bandwidth <= 773) {
+ setbits |= REG2_AA_FILTER_BW_773HZ_A;
+ _accel_onchip_filter_bandwith = 773;
+
+ } else {
+ return -EINVAL;
+ }
+
+ modify_reg(ADDR_CTRL_REG2, clearbits, setbits);
+
+ return OK;
+}
+
+int
+LSM303D::accel_set_driver_lowpass_filter(float samplerate, float bandwidth)
+{
+ _accel_filter_x.set_cutoff_frequency(samplerate, bandwidth);
+ _accel_filter_y.set_cutoff_frequency(samplerate, bandwidth);
+ _accel_filter_z.set_cutoff_frequency(samplerate, bandwidth);
+
+ return OK;
+}
+
+int
+LSM303D::accel_set_samplerate(unsigned frequency)
+{
+ uint8_t setbits = 0;
+ uint8_t clearbits = REG1_RATE_BITS_A;
+
+ if (frequency == 0)
+ frequency = 1600;
+
+ if (frequency <= 100) {
+ setbits |= REG1_RATE_100HZ_A;
+ _accel_samplerate = 100;
+
+ } else if (frequency <= 200) {
+ setbits |= REG1_RATE_200HZ_A;
+ _accel_samplerate = 200;
+
+ } else if (frequency <= 400) {
+ setbits |= REG1_RATE_400HZ_A;
+ _accel_samplerate = 400;
+
+ } else if (frequency <= 800) {
+ setbits |= REG1_RATE_800HZ_A;
+ _accel_samplerate = 800;
+
+ } else if (frequency <= 1600) {
+ setbits |= REG1_RATE_1600HZ_A;
+ _accel_samplerate = 1600;
+
+ } else {
+ return -EINVAL;
+ }
+
+ modify_reg(ADDR_CTRL_REG1, clearbits, setbits);
+
+ return OK;
+}
+
+int
+LSM303D::mag_set_samplerate(unsigned frequency)
+{
+ uint8_t setbits = 0;
+ uint8_t clearbits = REG5_RATE_BITS_M;
+
+ if (frequency == 0)
+ frequency = 100;
+
+ if (frequency <= 25) {
+ setbits |= REG5_RATE_25HZ_M;
+ _mag_samplerate = 25;
+
+ } else if (frequency <= 50) {
+ setbits |= REG5_RATE_50HZ_M;
+ _mag_samplerate = 50;
+
+ } else if (frequency <= 100) {
+ setbits |= REG5_RATE_100HZ_M;
+ _mag_samplerate = 100;
+
+ } else {
+ return -EINVAL;
+ }
+
+ modify_reg(ADDR_CTRL_REG5, clearbits, setbits);
+
+ return OK;
+}
+
+void
+LSM303D::start()
+{
+ /* make sure we are stopped first */
+ stop();
+
+ /* reset the report ring */
+ _oldest_accel_report = _next_accel_report = 0;
+ _oldest_mag_report = _next_mag_report = 0;
+
+ /* start polling at the specified rate */
+ hrt_call_every(&_accel_call, 1000, _call_accel_interval, (hrt_callout)&LSM303D::measure_trampoline, this);
+ hrt_call_every(&_mag_call, 1000, _call_mag_interval, (hrt_callout)&LSM303D::mag_measure_trampoline, this);
+}
+
+void
+LSM303D::stop()
+{
+ hrt_cancel(&_accel_call);
+ hrt_cancel(&_mag_call);
+}
+
+void
+LSM303D::measure_trampoline(void *arg)
+{
+ LSM303D *dev = (LSM303D *)arg;
+
+ /* make another measurement */
+ dev->measure();
+}
+
+void
+LSM303D::mag_measure_trampoline(void *arg)
+{
+ LSM303D *dev = (LSM303D *)arg;
+
+ /* make another measurement */
+ dev->mag_measure();
+}
+
+void
+LSM303D::measure()
+{
+ /* status register and data as read back from the device */
+
+#pragma pack(push, 1)
+ struct {
+ uint8_t cmd;
+ uint8_t status;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } raw_accel_report;
+#pragma pack(pop)
+
+ accel_report *accel_report = &_accel_reports[_next_accel_report];
+
+ /* start the performance counter */
+ perf_begin(_accel_sample_perf);
+
+ /* fetch data from the sensor */
+ raw_accel_report.cmd = ADDR_STATUS_A | DIR_READ | ADDR_INCREMENT;
+ transfer((uint8_t *)&raw_accel_report, (uint8_t *)&raw_accel_report, sizeof(raw_accel_report));
+
+ /*
+ * 1) Scale raw value to SI units using scaling from datasheet.
+ * 2) Subtract static offset (in SI units)
+ * 3) Scale the statically calibrated values with a linear
+ * dynamically obtained factor
+ *
+ * Note: the static sensor offset is the number the sensor outputs
+ * at a nominally 'zero' input. Therefore the offset has to
+ * be subtracted.
+ *
+ * Example: A gyro outputs a value of 74 at zero angular rate
+ * the offset is 74 from the origin and subtracting
+ * 74 from all measurements centers them around zero.
+ */
+
+
+ accel_report->timestamp = hrt_absolute_time();
+
+ accel_report->x_raw = raw_accel_report.x;
+ accel_report->y_raw = raw_accel_report.y;
+ accel_report->z_raw = raw_accel_report.z;
+
+ float x_in_new = ((accel_report->x_raw * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
+ float y_in_new = ((accel_report->y_raw * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
+ float z_in_new = ((accel_report->z_raw * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
+
+ accel_report->x = _accel_filter_x.apply(x_in_new);
+ accel_report->y = _accel_filter_y.apply(y_in_new);
+ accel_report->z = _accel_filter_z.apply(z_in_new);
+
+ accel_report->scaling = _accel_range_scale;
+ accel_report->range_m_s2 = _accel_range_m_s2;
+
+ /* post a report to the ring - note, not locked */
+ INCREMENT(_next_accel_report, _num_accel_reports);
+
+ /* if we are running up against the oldest report, fix it */
+ if (_next_accel_report == _oldest_accel_report)
+ INCREMENT(_oldest_accel_report, _num_accel_reports);
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ /* publish for subscribers */
+ orb_publish(ORB_ID(sensor_accel), _accel_topic, accel_report);
+
+ _accel_read++;
+
+ /* stop the perf counter */
+ perf_end(_accel_sample_perf);
+}
+
+void
+LSM303D::mag_measure()
+{
+ /* status register and data as read back from the device */
+#pragma pack(push, 1)
+ struct {
+ uint8_t cmd;
+ uint8_t status;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } raw_mag_report;
+#pragma pack(pop)
+
+ mag_report *mag_report = &_mag_reports[_next_mag_report];
+
+ /* start the performance counter */
+ perf_begin(_mag_sample_perf);
+
+ /* fetch data from the sensor */
+ raw_mag_report.cmd = ADDR_STATUS_M | DIR_READ | ADDR_INCREMENT;
+ transfer((uint8_t *)&raw_mag_report, (uint8_t *)&raw_mag_report, sizeof(raw_mag_report));
+
+ /*
+ * 1) Scale raw value to SI units using scaling from datasheet.
+ * 2) Subtract static offset (in SI units)
+ * 3) Scale the statically calibrated values with a linear
+ * dynamically obtained factor
+ *
+ * Note: the static sensor offset is the number the sensor outputs
+ * at a nominally 'zero' input. Therefore the offset has to
+ * be subtracted.
+ *
+ * Example: A gyro outputs a value of 74 at zero angular rate
+ * the offset is 74 from the origin and subtracting
+ * 74 from all measurements centers them around zero.
+ */
+
+
+ mag_report->timestamp = hrt_absolute_time();
+
+ mag_report->x_raw = raw_mag_report.x;
+ mag_report->y_raw = raw_mag_report.y;
+ mag_report->z_raw = raw_mag_report.z;
+ mag_report->x = ((mag_report->x_raw * _mag_range_scale) - _mag_scale.x_offset) * _mag_scale.x_scale;
+ mag_report->y = ((mag_report->y_raw * _mag_range_scale) - _mag_scale.y_offset) * _mag_scale.y_scale;
+ mag_report->z = ((mag_report->z_raw * _mag_range_scale) - _mag_scale.z_offset) * _mag_scale.z_scale;
+ mag_report->scaling = _mag_range_scale;
+ mag_report->range_ga = (float)_mag_range_ga;
+
+ /* post a report to the ring - note, not locked */
+ INCREMENT(_next_mag_report, _num_mag_reports);
+
+ /* if we are running up against the oldest report, fix it */
+ if (_next_mag_report == _oldest_mag_report)
+ INCREMENT(_oldest_mag_report, _num_mag_reports);
+
+ /* XXX please check this poll_notify, is it the right one? */
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ /* publish for subscribers */
+ orb_publish(ORB_ID(sensor_mag), _mag_topic, mag_report);
+
+ _mag_read++;
+
+ /* stop the perf counter */
+ perf_end(_mag_sample_perf);
+}
+
+void
+LSM303D::print_info()
+{
+ printf("accel reads: %u\n", _accel_read);
+ printf("mag reads: %u\n", _mag_read);
+ perf_print_counter(_accel_sample_perf);
+ printf("report queue: %u (%u/%u @ %p)\n",
+ _num_accel_reports, _oldest_accel_report, _next_accel_report, _accel_reports);
+ perf_print_counter(_mag_sample_perf);
+ printf("report queue: %u (%u/%u @ %p)\n",
+ _num_mag_reports, _oldest_mag_report, _next_mag_report, _mag_reports);
+}
+
+LSM303D_mag::LSM303D_mag(LSM303D *parent) :
+ CDev("LSM303D_mag", MAG_DEVICE_PATH),
+ _parent(parent)
+{
+}
+
+LSM303D_mag::~LSM303D_mag()
+{
+}
+
+void
+LSM303D_mag::parent_poll_notify()
+{
+ poll_notify(POLLIN);
+}
+
+ssize_t
+LSM303D_mag::read(struct file *filp, char *buffer, size_t buflen)
+{
+ return _parent->mag_read(filp, buffer, buflen);
+}
+
+int
+LSM303D_mag::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ return _parent->mag_ioctl(filp, cmd, arg);
+}
+
+void
+LSM303D_mag::measure()
+{
+ _parent->mag_measure();
+}
+
+void
+LSM303D_mag::measure_trampoline(void *arg)
+{
+ _parent->mag_measure_trampoline(arg);
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace lsm303d
+{
+
+LSM303D *g_dev;
+
+void start();
+void test();
+void reset();
+void info();
+
+/**
+ * Start the driver.
+ */
+void
+start()
+{
+ int fd, fd_mag;
+
+ if (g_dev != nullptr)
+ errx(0, "already started");
+
+ /* create the driver */
+ g_dev = new LSM303D(1 /* XXX magic number */, ACCEL_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
+
+ 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(ACCEL_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0)
+ goto fail;
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ goto fail;
+
+ fd_mag = open(MAG_DEVICE_PATH, O_RDONLY);
+
+ /* don't fail if open cannot be opened */
+ if (0 <= fd_mag) {
+ if (ioctl(fd_mag, 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");
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ */
+void
+test()
+{
+ int fd_accel = -1;
+ struct accel_report accel_report;
+ ssize_t sz;
+ int ret;
+
+ /* get the driver */
+ fd_accel = open(ACCEL_DEVICE_PATH, O_RDONLY);
+
+ if (fd_accel < 0)
+ err(1, "%s open failed", ACCEL_DEVICE_PATH);
+
+ /* do a simple demand read */
+ sz = read(fd_accel, &accel_report, sizeof(accel_report));
+
+ if (sz != sizeof(accel_report))
+ err(1, "immediate read failed");
+
+
+ warnx("accel x: \t% 9.5f\tm/s^2", (double)accel_report.x);
+ warnx("accel y: \t% 9.5f\tm/s^2", (double)accel_report.y);
+ warnx("accel z: \t% 9.5f\tm/s^2", (double)accel_report.z);
+ warnx("accel x: \t%d\traw", (int)accel_report.x_raw);
+ warnx("accel y: \t%d\traw", (int)accel_report.y_raw);
+ warnx("accel z: \t%d\traw", (int)accel_report.z_raw);
+
+ warnx("accel range: %8.4f m/s^2", (double)accel_report.range_m_s2);
+ if (ERROR == (ret = ioctl(fd_accel, ACCELIOCGLOWPASS, 0)))
+ warnx("accel antialias filter bandwidth: fail");
+ else
+ warnx("accel antialias filter bandwidth: %d Hz", ret);
+
+ int fd_mag = -1;
+ struct mag_report m_report;
+
+ /* get the driver */
+ fd_mag = open(MAG_DEVICE_PATH, O_RDONLY);
+
+ if (fd_mag < 0)
+ err(1, "%s open failed", MAG_DEVICE_PATH);
+
+ /* check if mag is onboard or external */
+ if ((ret = ioctl(fd_mag, MAGIOCGEXTERNAL, 0)) < 0)
+ errx(1, "failed to get if mag is onboard or external");
+ warnx("mag device active: %s", ret ? "external" : "onboard");
+
+ /* do a simple demand read */
+ sz = read(fd_mag, &m_report, sizeof(m_report));
+
+ if (sz != sizeof(m_report))
+ err(1, "immediate read failed");
+
+ warnx("mag x: \t% 9.5f\tga", (double)m_report.x);
+ warnx("mag y: \t% 9.5f\tga", (double)m_report.y);
+ warnx("mag z: \t% 9.5f\tga", (double)m_report.z);
+ warnx("mag x: \t%d\traw", (int)m_report.x_raw);
+ warnx("mag y: \t%d\traw", (int)m_report.y_raw);
+ warnx("mag z: \t%d\traw", (int)m_report.z_raw);
+ warnx("mag range: %8.4f ga", (double)m_report.range_ga);
+
+ /* XXX add poll-rate tests here too */
+
+ reset();
+ errx(0, "PASS");
+}
+
+/**
+ * Reset the driver.
+ */
+void
+reset()
+{
+ int fd = open(ACCEL_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, "accel pollrate reset failed");
+
+ fd = open(MAG_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0) {
+ warnx("mag could not be opened, external mag might be used");
+ } else {
+ /* no need to reset the mag as well, the reset() is the same */
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ err(1, "mag pollrate reset failed");
+ }
+
+ exit(0);
+}
+
+/**
+ * Print a little info about the driver.
+ */
+void
+info()
+{
+ if (g_dev == nullptr)
+ errx(1, "driver not running\n");
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ exit(0);
+}
+
+
+} // namespace
+
+int
+lsm303d_main(int argc, char *argv[])
+{
+ /*
+ * Start/load the driver.
+
+ */
+ if (!strcmp(argv[1], "start"))
+ lsm303d::start();
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test"))
+ lsm303d::test();
+
+ /*
+ * Reset the driver.
+ */
+ if (!strcmp(argv[1], "reset"))
+ lsm303d::reset();
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(argv[1], "info"))
+ lsm303d::info();
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
+}
diff --git a/src/drivers/lsm303d/module.mk b/src/drivers/lsm303d/module.mk
new file mode 100644
index 000000000..e40f718c5
--- /dev/null
+++ b/src/drivers/lsm303d/module.mk
@@ -0,0 +1,8 @@
+#
+# LSM303D accel/mag driver
+#
+
+MODULE_COMMAND = lsm303d
+SRCS = lsm303d.cpp
+
+
diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp
index 397686e8b..c5f49fb36 100644
--- a/src/drivers/mb12xx/mb12xx.cpp
+++ b/src/drivers/mb12xx/mb12xx.cpp
@@ -59,8 +59,6 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
-#include <arch/board/board.h>
-
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@@ -70,6 +68,8 @@
#include <uORB/uORB.h>
#include <uORB/topics/subsystem_info.h>
+#include <board_config.h>
+
/* Configuration Constants */
#define MB12XX_BUS PX4_I2C_BUS_EXPANSION
#define MB12XX_BASEADDR 0x70 /* 7-bit address. 8-bit address is 0xE0 */
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
index 68d2c5d65..666bd30e6 100644
--- a/src/drivers/meas_airspeed/meas_airspeed.cpp
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -70,7 +70,7 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <systemlib/airspeed.h>
#include <systemlib/err.h>
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index e78d96569..1bc3e97a4 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -59,10 +59,11 @@
#include <nuttx/arch.h>
#include <nuttx/i2c.h>
+#include <board_config.h>
+
#include <drivers/device/device.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_gpio.h>
-#include <drivers/boards/px4fmu/px4fmu_internal.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_rc_input.h>
@@ -74,6 +75,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/esc_status.h>
#include <systemlib/err.h>
@@ -134,7 +136,7 @@ private:
int _current_update_rate;
int _task;
int _t_actuators;
- int _t_armed;
+ int _t_actuator_armed;
unsigned int _motor;
int _px4mode;
int _frametype;
@@ -247,7 +249,7 @@ MK::MK(int bus) :
_update_rate(50),
_task(-1),
_t_actuators(-1),
- _t_armed(-1),
+ _t_actuator_armed(-1),
_t_outputs(0),
_t_actuators_effective(0),
_t_esc_status(0),
@@ -512,8 +514,8 @@ MK::task_main()
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
+ orb_set_interval(_t_actuator_armed, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@@ -539,7 +541,7 @@ MK::task_main()
pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_armed;
fds[1].events = POLLIN;
log("starting");
@@ -653,7 +655,7 @@ MK::task_main()
actuator_armed_s aa;
/* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
+ orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &aa);
/* update PWM servo armed status if armed and not locked down */
mk_servo_arm(aa.armed && !aa.lockdown);
@@ -699,7 +701,7 @@ MK::task_main()
//::close(_t_esc_status);
::close(_t_actuators);
::close(_t_actuators_effective);
- ::close(_t_armed);
+ ::close(_t_actuator_armed);
/* make sure servos are off */
@@ -1345,44 +1347,6 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest,
gpio_bits = 0;
servo_mode = MK::MODE_NONE;
- switch (new_mode) {
- case PORT_FULL_GPIO:
- case PORT_MODE_UNSET:
- /* nothing more to do here */
- break;
-
- case PORT_FULL_SERIAL:
- /* set all multi-GPIOs to serial mode */
- gpio_bits = GPIO_MULTI_1 | GPIO_MULTI_2 | GPIO_MULTI_3 | GPIO_MULTI_4;
- break;
-
- case PORT_FULL_PWM:
- /* select 4-pin PWM mode */
- servo_mode = MK::MODE_4PWM;
- break;
-
- case PORT_GPIO_AND_SERIAL:
- /* set RX/TX multi-GPIOs to serial mode */
- gpio_bits = GPIO_MULTI_3 | GPIO_MULTI_4;
- break;
-
- case PORT_PWM_AND_SERIAL:
- /* select 2-pin PWM mode */
- servo_mode = MK::MODE_2PWM;
- /* set RX/TX multi-GPIOs to serial mode */
- gpio_bits = GPIO_MULTI_3 | GPIO_MULTI_4;
- break;
-
- case PORT_PWM_AND_GPIO:
- /* select 2-pin PWM mode */
- servo_mode = MK::MODE_2PWM;
- break;
- }
-
- /* adjust GPIO config for serial mode(s) */
- if (gpio_bits != 0)
- g_mk->ioctl(0, GPIO_SET_ALT_1, gpio_bits);
-
/* native PX4 addressing) */
g_mk->set_px4mode(px4mode);
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 4f7075600..14f8f44b8 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -63,7 +63,7 @@
#include <nuttx/arch.h>
#include <nuttx/clock.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
@@ -149,6 +149,17 @@
#define MPU6000_REV_D9 0x59
#define MPU6000_REV_D10 0x5A
+#define MPU6000_ACCEL_DEFAULT_RANGE_G 8
+#define MPU6000_ACCEL_DEFAULT_RATE 1000
+#define MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 30
+
+#define MPU6000_GYRO_DEFAULT_RANGE_G 8
+#define MPU6000_GYRO_DEFAULT_RATE 1000
+#define MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ 30
+
+#define MPU6000_DEFAULT_ONCHIP_FILTER_FREQ 42
+
+#define MPU6000_ONE_G 9.80665f
class MPU6000_gyro;
@@ -357,12 +368,12 @@ MPU6000::MPU6000(int bus, spi_dev_e device) :
_reads(0),
_sample_rate(1000),
_sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")),
- _accel_filter_x(1000, 30),
- _accel_filter_y(1000, 30),
- _accel_filter_z(1000, 30),
- _gyro_filter_x(1000, 30),
- _gyro_filter_y(1000, 30),
- _gyro_filter_z(1000, 30)
+ _accel_filter_x(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
+ _accel_filter_y(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
+ _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)
{
// disable debug() calls
_debug_enabled = false;
@@ -485,14 +496,13 @@ void MPU6000::reset()
up_udelay(1000);
// SAMPLE RATE
- //write_reg(MPUREG_SMPLRT_DIV, 0x04); // Sample rate = 200Hz Fsample= 1Khz/(4+1) = 200Hz
- _set_sample_rate(_sample_rate); // default sample rate = 200Hz
+ _set_sample_rate(_sample_rate);
usleep(1000);
// FS & DLPF FS=2000 deg/s, DLPF = 20Hz (low pass filter)
// was 90 Hz, but this ruins quality and does not improve the
// system response
- _set_dlpf_filter(42);
+ _set_dlpf_filter(MPU6000_DEFAULT_ONCHIP_FILTER_FREQ);
usleep(1000);
// Gyro scale 2000 deg/s ()
write_reg(MPUREG_GYRO_CONFIG, BITS_FS_2000DPS);
@@ -535,8 +545,8 @@ void MPU6000::reset()
// Correct accel scale factors of 4096 LSB/g
// scale to m/s^2 ( 1g = 9.81 m/s^2)
- _accel_range_scale = (9.81f / 4096.0f);
- _accel_range_m_s2 = 8.0f * 9.81f;
+ _accel_range_scale = (MPU6000_ONE_G / 4096.0f);
+ _accel_range_m_s2 = 8.0f * MPU6000_ONE_G;
usleep(1000);
@@ -777,9 +787,10 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
+ return ioctl(filp, SENSORIOCSPOLLRATE, 1000);
+
case SENSOR_POLLRATE_DEFAULT:
- /* set to same as sample rate per default */
- return ioctl(filp, SENSORIOCSPOLLRATE, _sample_rate);
+ return ioctl(filp, SENSORIOCSPOLLRATE, MPU6000_ACCEL_DEFAULT_RATE);
/* adjust to a legal polling interval in Hz */
default: {
@@ -867,9 +878,9 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
// XXX decide on relationship of both filters
// i.e. disable the on-chip filter
//_set_dlpf_filter((uint16_t)arg);
- _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);
+ _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);
return OK;
case ACCELIOCSSCALE:
@@ -897,7 +908,7 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
// _accel_range_m_s2 = 8.0f * 9.81f;
return -EINVAL;
case ACCELIOCGRANGE:
- return _accel_range_m_s2;
+ return (unsigned long)((_accel_range_m_s2)/MPU6000_ONE_G + 0.5f);
case ACCELIOCSELFTEST:
return accel_self_test();
@@ -920,28 +931,28 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
return ioctl(filp, cmd, arg);
case SENSORIOCSQUEUEDEPTH: {
- /* lower bound is mandatory, upper bound is a sanity check */
- if ((arg < 1) || (arg > 100))
- return -EINVAL;
-
- /* allocate new buffer */
- GyroReportBuffer *buf = new GyroReportBuffer(arg);
-
- if (nullptr == buf)
- return -ENOMEM;
- if (buf->size() == 0) {
- delete buf;
- return -ENOMEM;
- }
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100))
+ return -EINVAL;
+
+ /* allocate new buffer */
+ GyroReportBuffer *buf = new GyroReportBuffer(arg);
+
+ if (nullptr == buf)
+ return -ENOMEM;
+ if (buf->size() == 0) {
+ delete buf;
+ return -ENOMEM;
+ }
- /* reset the measurement state machine with the new buffer, free the old */
- stop();
- delete _gyro_reports;
- _gyro_reports = buf;
- start();
+ /* reset the measurement state machine with the new buffer, free the old */
+ stop();
+ delete _gyro_reports;
+ _gyro_reports = buf;
+ start();
- return OK;
- }
+ return OK;
+ }
case SENSORIOCGQUEUEDEPTH:
return _gyro_reports->size();
@@ -980,7 +991,7 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
// _gyro_range_rad_s = xx
return -EINVAL;
case GYROIOCGRANGE:
- return _gyro_range_rad_s;
+ return (unsigned long)(_gyro_range_rad_s * 180.0f / M_PI_F + 0.5f);
case GYROIOCSELFTEST:
return gyro_self_test();
@@ -1400,7 +1411,7 @@ test()
warnx("acc y: \t%d\traw 0x%0x", (short)a_report.y_raw, (unsigned short)a_report.y_raw);
warnx("acc z: \t%d\traw 0x%0x", (short)a_report.z_raw, (unsigned short)a_report.z_raw);
warnx("acc range: %8.4f m/s^2 (%8.4f g)", (double)a_report.range_m_s2,
- (double)(a_report.range_m_s2 / 9.81f));
+ (double)(a_report.range_m_s2 / MPU6000_ONE_G));
/* do a simple demand read */
sz = read(fd_gyro, &g_report, sizeof(g_report));
diff --git a/src/drivers/ms5611/module.mk b/src/drivers/ms5611/module.mk
index 3c4b0f093..20f8aa173 100644
--- a/src/drivers/ms5611/module.mk
+++ b/src/drivers/ms5611/module.mk
@@ -37,4 +37,4 @@
MODULE_COMMAND = ms5611
-SRCS = ms5611.cpp
+SRCS = ms5611.cpp ms5611_spi.cpp ms5611_i2c.cpp
diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index c13b65d5a..d9268c0b3 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012-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
@@ -33,13 +33,11 @@
/**
* @file ms5611.cpp
- * Driver for the MS5611 barometric pressure sensor connected via I2C.
+ * Driver for the MS5611 barometric pressure sensor connected via I2C or SPI.
*/
#include <nuttx/config.h>
-#include <drivers/device/i2c.h>
-
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
@@ -59,12 +57,14 @@
#include <arch/board/board.h>
+#include <drivers/device/device.h>
+#include <drivers/drv_baro.h>
#include <drivers/drv_hrt.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
-#include <drivers/drv_baro.h>
+#include "ms5611.h"
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -76,35 +76,25 @@ static const int ERROR = -1;
# error This requires CONFIG_SCHED_WORKQUEUE.
#endif
-/**
- * Calibration PROM as reported by the device.
- */
-#pragma pack(push,1)
-struct ms5611_prom_s {
- uint16_t factory_setup;
- uint16_t c1_pressure_sens;
- uint16_t c2_pressure_offset;
- uint16_t c3_temp_coeff_pres_sens;
- uint16_t c4_temp_coeff_pres_offset;
- uint16_t c5_reference_temp;
- uint16_t c6_temp_coeff_temp;
- uint16_t serial_and_crc;
-};
+/* helper macro for handling report buffer indices */
+#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
-/**
- * Grody hack for crc4()
+/* helper macro for arithmetic - returns the square of the argument */
+#define POW2(_x) ((_x) * (_x))
+
+/*
+ * MS5611 internal constants and data structures.
*/
-union ms5611_prom_u {
- uint16_t c[8];
- struct ms5611_prom_s s;
-};
-#pragma pack(pop)
-class MS5611 : public device::I2C
+/* internal conversion time: 9.17 ms, so should not be read at rates higher than 100 Hz */
+#define MS5611_CONVERSION_INTERVAL 10000 /* microseconds */
+#define MS5611_MEASUREMENT_RATIO 3 /* pressure measurements per temperature measurement */
+
+class MS5611 : public device::CDev
{
public:
- MS5611(int bus);
- virtual ~MS5611();
+ MS5611(device::Device *interface, ms5611::prom_u &prom_buf);
+ ~MS5611();
virtual int init();
@@ -117,10 +107,9 @@ public:
void print_info();
protected:
- virtual int probe();
+ Device *_interface;
-private:
- union ms5611_prom_u _prom;
+ ms5611::prom_s _prom;
struct work_s _work;
unsigned _measure_ticks;
@@ -149,16 +138,7 @@ private:
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.
+ * Initialize 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.
@@ -198,70 +178,23 @@ private:
*
* @return OK if the measurement command was successful.
*/
- int measure();
+ virtual int measure();
/**
* Collect the result of the most recent measurement.
*/
- int collect();
-
- /**
- * Send a reset command to the MS5611.
- *
- * This is required after any bus reset.
- */
- int cmd_reset();
-
- /**
- * Read the MS5611 PROM
- *
- * @return OK if the PROM reads successfully.
- */
- int read_prom();
-
- /**
- * PROM CRC routine ported from MS5611 application note
- *
- * @param n_prom Pointer to words read from PROM.
- * @return True if the CRC matches.
- */
- bool crc4(uint16_t *n_prom);
-
+ virtual int collect();
};
-/* helper macro for handling report buffer indices */
-#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
-
-/* helper macro for arithmetic - returns the square of the argument */
-#define POW2(_x) ((_x) * (_x))
-
-/*
- * MS5611 internal constants and data structures.
- */
-
-/* internal conversion time: 9.17 ms, so should not be read at rates higher than 100 Hz */
-#define MS5611_CONVERSION_INTERVAL 10000 /* microseconds */
-#define MS5611_MEASUREMENT_RATIO 3 /* pressure measurements per temperature measurement */
-
-#define MS5611_BUS PX4_I2C_BUS_ONBOARD
-#define MS5611_ADDRESS_1 PX4_I2C_OBDEV_MS5611 /* address select pins pulled high (PX4FMU series v1.6+) */
-#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
-
-#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
-#define ADDR_CMD_CONVERT_D1 0x48 /* write to this address to start temperature conversion */
-#define ADDR_CMD_CONVERT_D2 0x58 /* write to this address to start pressure conversion */
-#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */
-#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
-#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */
-
/*
* Driver 'main' command.
*/
extern "C" __EXPORT int ms5611_main(int argc, char *argv[]);
-
-MS5611::MS5611(int bus) :
- I2C("MS5611", BARO_DEVICE_PATH, bus, 0, 400000),
+MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf) :
+ CDev("MS5611", BARO_DEVICE_PATH),
+ _interface(interface),
+ _prom(prom_buf.s),
_measure_ticks(0),
_num_reports(0),
_next_report(0),
@@ -279,10 +212,7 @@ MS5611::MS5611(int bus) :
_comms_errors(perf_alloc(PC_COUNT, "ms5611_comms_errors")),
_buffer_overflows(perf_alloc(PC_COUNT, "ms5611_buffer_overflows"))
{
- // enable debug() calls
- _debug_enabled = true;
-
- // work_cancel in the dtor will explode if we don't do this...
+ // work_cancel in stop_cycle called from the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
}
@@ -294,23 +224,30 @@ MS5611::~MS5611()
/* free any existing reports */
if (_reports != nullptr)
delete[] _reports;
+
+ delete _interface;
}
int
MS5611::init()
{
- int ret = ERROR;
+ int ret;
- /* do I2C init (and probe) first */
- if (I2C::init() != OK)
+ ret = CDev::init();
+ if (ret != OK) {
+ debug("CDev init failed");
goto out;
+ }
/* allocate basic report buffers */
_num_reports = 2;
_reports = new struct baro_report[_num_reports];
- if (_reports == nullptr)
+ if (_reports == nullptr) {
+ debug("can't get memory for reports");
+ ret = -ENOMEM;
goto out;
+ }
_oldest_report = _next_report = 0;
@@ -318,49 +255,17 @@ MS5611::init()
memset(&_reports[0], 0, sizeof(_reports[0]));
_baro_topic = orb_advertise(ORB_ID(sensor_baro), &_reports[0]);
- if (_baro_topic < 0)
+ if (_baro_topic < 0) {
debug("failed to create sensor_baro object");
+ ret = -ENOSPC;
+ goto out;
+ }
ret = OK;
out:
return ret;
}
-int
-MS5611::probe()
-{
- _retries = 10;
-
- if ((OK == probe_address(MS5611_ADDRESS_1)) ||
- (OK == probe_address(MS5611_ADDRESS_2))) {
- /*
- * Disable retries; we may enable them selectively in some cases,
- * but the device gets confused if we retry some of the commands.
- */
- _retries = 0;
- return OK;
- }
-
- return -EIO;
-}
-
-int
-MS5611::probe_address(uint8_t address)
-{
- /* select the address we are going to try */
- set_address(address);
-
- /* send reset command */
- if (OK != cmd_reset())
- return -EIO;
-
- /* read PROM */
- if (OK != read_prom())
- return -EIO;
-
- return OK;
-}
-
ssize_t
MS5611::read(struct file *filp, char *buffer, size_t buflen)
{
@@ -546,8 +451,9 @@ MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
break;
}
- /* give it to the superclass */
- return I2C::ioctl(filp, cmd, arg);
+ /* give it to the bus-specific superclass */
+ // return bus_ioctl(filp, cmd, arg);
+ return CDev::ioctl(filp, cmd, arg);
}
void
@@ -572,7 +478,7 @@ MS5611::stop_cycle()
void
MS5611::cycle_trampoline(void *arg)
{
- MS5611 *dev = (MS5611 *)arg;
+ MS5611 *dev = reinterpret_cast<MS5611 *>(arg);
dev->cycle();
}
@@ -592,7 +498,7 @@ MS5611::cycle()
/*
* The ms5611 seems to regularly fail to respond to
* its address; this happens often enough that we'd rather not
- * spam the console with the message.
+ * spam the console with a message for this.
*/
} else {
//log("collection error %d", ret);
@@ -654,17 +560,12 @@ MS5611::measure()
/*
* In phase zero, request temperature; in other phases, request pressure.
*/
- uint8_t cmd_data = (_measure_phase == 0) ? ADDR_CMD_CONVERT_D2 : ADDR_CMD_CONVERT_D1;
+ unsigned addr = (_measure_phase == 0) ? ADDR_CMD_CONVERT_D2 : ADDR_CMD_CONVERT_D1;
/*
* Send the command to begin measuring.
- *
- * Disable retries on this command; we can't know whether failure
- * means the device did or did not see the write.
*/
- _retries = 0;
- ret = transfer(&cmd_data, 1, nullptr, 0);
-
+ ret = _interface->ioctl(IOCTL_MEASURE, addr);
if (OK != ret)
perf_count(_comms_errors);
@@ -677,47 +578,33 @@ int
MS5611::collect()
{
int ret;
- uint8_t cmd;
- uint8_t data[3];
- union {
- uint8_t b[4];
- uint32_t w;
- } cvt;
-
- /* read the most recent measurement */
- cmd = 0;
+ uint32_t raw;
perf_begin(_sample_perf);
/* this should be fairly close to the end of the conversion, so the best approximation of the time */
_reports[_next_report].timestamp = hrt_absolute_time();
- ret = transfer(&cmd, 1, &data[0], 3);
- if (ret != OK) {
+ /* read the most recent measurement - read offset/size are hardcoded in the interface */
+ ret = _interface->read(0, (void *)&raw, 0);
+ if (ret < 0) {
perf_count(_comms_errors);
perf_end(_sample_perf);
return ret;
}
- /* fetch the raw value */
- cvt.b[0] = data[2];
- cvt.b[1] = data[1];
- cvt.b[2] = data[0];
- cvt.b[3] = 0;
- uint32_t raw = cvt.w;
-
/* handle a measurement */
if (_measure_phase == 0) {
/* temperature offset (in ADC units) */
- int32_t dT = (int32_t)raw - ((int32_t)_prom.s.c5_reference_temp << 8);
+ int32_t dT = (int32_t)raw - ((int32_t)_prom.c5_reference_temp << 8);
/* absolute temperature in centidegrees - note intermediate value is outside 32-bit range */
- _TEMP = 2000 + (int32_t)(((int64_t)dT * _prom.s.c6_temp_coeff_temp) >> 23);
+ _TEMP = 2000 + (int32_t)(((int64_t)dT * _prom.c6_temp_coeff_temp) >> 23);
/* base sensor scale/offset values */
- _SENS = ((int64_t)_prom.s.c1_pressure_sens << 15) + (((int64_t)_prom.s.c3_temp_coeff_pres_sens * dT) >> 8);
- _OFF = ((int64_t)_prom.s.c2_pressure_offset << 16) + (((int64_t)_prom.s.c4_temp_coeff_pres_offset * dT) >> 7);
+ _SENS = ((int64_t)_prom.c1_pressure_sens << 15) + (((int64_t)_prom.c3_temp_coeff_pres_sens * dT) >> 8);
+ _OFF = ((int64_t)_prom.c2_pressure_offset << 16) + (((int64_t)_prom.c4_temp_coeff_pres_offset * dT) >> 7);
/* temperature compensation */
if (_TEMP < 2000) {
@@ -761,30 +648,7 @@ MS5611::collect()
* double precision: ms5611_read: 992 events, 258641us elapsed, min 202us max 305us
* single precision: ms5611_read: 963 events, 208066us elapsed, min 202us max 241us
*/
-#if 0/* USE_FLOAT */
- /* tropospheric properties (0-11km) for standard atmosphere */
- const float T1 = 15.0f + 273.15f; /* temperature at base height in Kelvin */
- const float a = -6.5f / 1000f; /* temperature gradient in degrees per metre */
- const float g = 9.80665f; /* gravity constant in m/s/s */
- const float R = 287.05f; /* ideal gas constant in J/kg/K */
-
- /* current pressure at MSL in kPa */
- float p1 = _msl_pressure / 1000.0f;
-
- /* measured pressure in kPa */
- float p = P / 1000.0f;
- /*
- * Solve:
- *
- * / -(aR / g) \
- * | (p / p1) . T1 | - T1
- * \ /
- * h = ------------------------------- + h1
- * a
- */
- _reports[_next_report].altitude = (((powf((p / p1), (-(a * R) / g))) * T1) - T1) / a;
-#else
/* tropospheric properties (0-11km) for standard atmosphere */
const double T1 = 15.0 + 273.15; /* temperature at base height in Kelvin */
const double a = -6.5 / 1000; /* temperature gradient in degrees per metre */
@@ -807,7 +671,7 @@ MS5611::collect()
* a
*/
_reports[_next_report].altitude = (((pow((p / p1), (-(a * R) / g))) * T1) - T1) / a;
-#endif
+
/* publish it */
orb_publish(ORB_ID(sensor_baro), _baro_topic, &_reports[_next_report]);
@@ -832,55 +696,49 @@ MS5611::collect()
return OK;
}
-int
-MS5611::cmd_reset()
+void
+MS5611::print_info()
{
- unsigned old_retrycount = _retries;
- uint8_t cmd = ADDR_RESET_CMD;
- int result;
-
- /* bump the retry count */
- _retries = 10;
- result = transfer(&cmd, 1, nullptr, 0);
- _retries = old_retrycount;
+ perf_print_counter(_sample_perf);
+ perf_print_counter(_comms_errors);
+ perf_print_counter(_buffer_overflows);
+ printf("poll interval: %u ticks\n", _measure_ticks);
+ printf("report queue: %u (%u/%u @ %p)\n",
+ _num_reports, _oldest_report, _next_report, _reports);
+ printf("TEMP: %d\n", _TEMP);
+ printf("SENS: %lld\n", _SENS);
+ printf("OFF: %lld\n", _OFF);
+ printf("MSL pressure: %10.4f\n", (double)(_msl_pressure / 100.f));
- return result;
+ printf("factory_setup %u\n", _prom.factory_setup);
+ printf("c1_pressure_sens %u\n", _prom.c1_pressure_sens);
+ printf("c2_pressure_offset %u\n", _prom.c2_pressure_offset);
+ printf("c3_temp_coeff_pres_sens %u\n", _prom.c3_temp_coeff_pres_sens);
+ printf("c4_temp_coeff_pres_offset %u\n", _prom.c4_temp_coeff_pres_offset);
+ printf("c5_reference_temp %u\n", _prom.c5_reference_temp);
+ printf("c6_temp_coeff_temp %u\n", _prom.c6_temp_coeff_temp);
+ printf("serial_and_crc %u\n", _prom.serial_and_crc);
}
-int
-MS5611::read_prom()
+/**
+ * Local functions in support of the shell command.
+ */
+namespace ms5611
{
- uint8_t prom_buf[2];
- union {
- uint8_t b[2];
- uint16_t w;
- } cvt;
-
- /*
- * Wait for PROM contents to be in the device (2.8 ms) in the case we are
- * called immediately after reset.
- */
- usleep(3000);
- /* read and convert PROM words */
- for (int i = 0; i < 8; i++) {
- uint8_t cmd = ADDR_PROM_SETUP + (i * 2);
-
- if (OK != transfer(&cmd, 1, &prom_buf[0], 2))
- break;
-
- /* assemble 16 bit value and convert from big endian (sensor) to little endian (MCU) */
- cvt.b[0] = prom_buf[1];
- cvt.b[1] = prom_buf[0];
- _prom.c[i] = cvt.w;
- }
+MS5611 *g_dev;
- /* calculate CRC and return success/failure accordingly */
- return crc4(&_prom.c[0]) ? OK : -EIO;
-}
+void start();
+void test();
+void reset();
+void info();
+void calibrate(unsigned altitude);
+/**
+ * MS5611 crc4 cribbed from the datasheet
+ */
bool
-MS5611::crc4(uint16_t *n_prom)
+crc4(uint16_t *n_prom)
{
int16_t cnt;
uint16_t n_rem;
@@ -922,43 +780,6 @@ MS5611::crc4(uint16_t *n_prom)
return (0x000F & crc_read) == (n_rem ^ 0x00);
}
-void
-MS5611::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);
- printf("report queue: %u (%u/%u @ %p)\n",
- _num_reports, _oldest_report, _next_report, _reports);
- printf("TEMP: %d\n", _TEMP);
- printf("SENS: %lld\n", _SENS);
- printf("OFF: %lld\n", _OFF);
- printf("MSL pressure: %10.4f\n", (double)(_msl_pressure / 100.f));
-
- printf("factory_setup %u\n", _prom.s.factory_setup);
- printf("c1_pressure_sens %u\n", _prom.s.c1_pressure_sens);
- printf("c2_pressure_offset %u\n", _prom.s.c2_pressure_offset);
- printf("c3_temp_coeff_pres_sens %u\n", _prom.s.c3_temp_coeff_pres_sens);
- printf("c4_temp_coeff_pres_offset %u\n", _prom.s.c4_temp_coeff_pres_offset);
- printf("c5_reference_temp %u\n", _prom.s.c5_reference_temp);
- printf("c6_temp_coeff_temp %u\n", _prom.s.c6_temp_coeff_temp);
- printf("serial_and_crc %u\n", _prom.s.serial_and_crc);
-}
-
-/**
- * Local functions in support of the shell command.
- */
-namespace ms5611
-{
-
-MS5611 *g_dev;
-
-void start();
-void test();
-void reset();
-void info();
-void calibrate(unsigned altitude);
/**
* Start the driver.
@@ -967,28 +788,46 @@ void
start()
{
int fd;
+ prom_u prom_buf;
if (g_dev != nullptr)
/* if already started, the still command succeeded */
errx(0, "already started");
- /* create the driver */
- g_dev = new MS5611(MS5611_BUS);
+ device::Device *interface = nullptr;
- if (g_dev == nullptr)
- goto fail;
+ /* create the driver, try SPI first, fall back to I2C if unsuccessful */
+ if (MS5611_spi_interface != nullptr)
+ interface = MS5611_spi_interface(prom_buf);
+ if (interface == nullptr && (MS5611_i2c_interface != nullptr))
+ interface = MS5611_i2c_interface(prom_buf);
- if (OK != g_dev->init())
+ if (interface == nullptr)
+ errx(1, "failed to allocate an interface");
+
+ if (interface->init() != OK) {
+ delete interface;
+ errx(1, "interface init failed");
+ }
+
+ g_dev = new MS5611(interface, prom_buf);
+ if (g_dev == nullptr) {
+ delete interface;
+ errx(1, "failed to allocate driver");
+ }
+ if (g_dev->init() != OK)
goto fail;
/* set the poll rate to default, starts automatic data collection */
fd = open(BARO_DEVICE_PATH, O_RDONLY);
-
- if (fd < 0)
+ if (fd < 0) {
+ warnx("can't open baro device");
goto fail;
-
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ }
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
+ warnx("failed setting default poll rate");
goto fail;
+ }
exit(0);
@@ -1155,11 +994,11 @@ calibrate(unsigned altitude)
const float g = 9.80665f; /* gravity constant in m/s/s */
const float R = 287.05f; /* ideal gas constant in J/kg/K */
- warnx("averaged pressure %10.4fkPa at %um", pressure, altitude);
+ warnx("averaged pressure %10.4fkPa at %um", (double)pressure, altitude);
p1 = pressure * (powf(((T1 + (a * (float)altitude)) / T1), (g / (a * R))));
- warnx("calculated MSL pressure %10.4fkPa", p1);
+ warnx("calculated MSL pressure %10.4fkPa", (double)p1);
/* save as integer Pa */
p1 *= 1000.0f;
diff --git a/src/drivers/ms5611/ms5611.h b/src/drivers/ms5611/ms5611.h
new file mode 100644
index 000000000..76fb84de8
--- /dev/null
+++ b/src/drivers/ms5611/ms5611.h
@@ -0,0 +1,85 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-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 ms5611.h
+ *
+ * Shared defines for the ms5611 driver.
+ */
+
+#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
+#define ADDR_CMD_CONVERT_D1 0x48 /* write to this address to start temperature conversion */
+#define ADDR_CMD_CONVERT_D2 0x58 /* write to this address to start pressure conversion */
+#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */
+#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
+#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */
+
+/* interface ioctls */
+#define IOCTL_RESET 2
+#define IOCTL_MEASURE 3
+
+namespace ms5611
+{
+
+/**
+ * Calibration PROM as reported by the device.
+ */
+#pragma pack(push,1)
+struct prom_s {
+ uint16_t factory_setup;
+ uint16_t c1_pressure_sens;
+ uint16_t c2_pressure_offset;
+ uint16_t c3_temp_coeff_pres_sens;
+ uint16_t c4_temp_coeff_pres_offset;
+ uint16_t c5_reference_temp;
+ uint16_t c6_temp_coeff_temp;
+ uint16_t serial_and_crc;
+};
+
+/**
+ * Grody hack for crc4()
+ */
+union prom_u {
+ uint16_t c[8];
+ prom_s s;
+};
+#pragma pack(pop)
+
+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_i2c_interface(ms5611::prom_u &prom_buf) weak_function;
+
diff --git a/src/drivers/ms5611/ms5611_i2c.cpp b/src/drivers/ms5611/ms5611_i2c.cpp
new file mode 100644
index 000000000..87d9b94a6
--- /dev/null
+++ b/src/drivers/ms5611/ms5611_i2c.cpp
@@ -0,0 +1,278 @@
+/****************************************************************************
+ *
+ * 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 ms5611_i2c.cpp
+ *
+ * I2C interface for MS5611
+ */
+
+/* XXX trim includes */
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+#include <debug.h>
+#include <errno.h>
+#include <unistd.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/device/i2c.h>
+
+#include "ms5611.h"
+
+#include "board_config.h"
+
+#ifdef PX4_I2C_OBDEV_MS5611
+
+#ifndef PX4_I2C_BUS_ONBOARD
+ #define MS5611_BUS 1
+#else
+ #define MS5611_BUS PX4_I2C_BUS_ONBOARD
+#endif
+
+#define MS5611_ADDRESS_1 0x76 /* address select pins pulled high (PX4FMU series v1.6+) */
+#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
+
+
+
+device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf);
+
+class MS5611_I2C : public device::I2C
+{
+public:
+ MS5611_I2C(int bus, ms5611::prom_u &prom_buf);
+ virtual ~MS5611_I2C();
+
+ virtual int init();
+ virtual int read(unsigned offset, void *data, unsigned count);
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
+protected:
+ virtual int probe();
+
+private:
+ ms5611::prom_u &_prom;
+
+ int _probe_address(uint8_t address);
+
+ /**
+ * Send a reset command to the MS5611.
+ *
+ * This is required after any bus reset.
+ */
+ int _reset();
+
+ /**
+ * Send a measure command to the MS5611.
+ *
+ * @param addr Which address to use for the measure operation.
+ */
+ int _measure(unsigned addr);
+
+ /**
+ * Read the MS5611 PROM
+ *
+ * @return OK if the PROM reads successfully.
+ */
+ int _read_prom();
+
+};
+
+device::Device *
+MS5611_i2c_interface(ms5611::prom_u &prom_buf)
+{
+ return new MS5611_I2C(MS5611_BUS, prom_buf);
+}
+
+MS5611_I2C::MS5611_I2C(int bus, ms5611::prom_u &prom) :
+ I2C("MS5611_I2C", nullptr, bus, 0, 400000),
+ _prom(prom)
+{
+}
+
+MS5611_I2C::~MS5611_I2C()
+{
+}
+
+int
+MS5611_I2C::init()
+{
+ /* this will call probe(), and thereby _probe_address */
+ return I2C::init();
+}
+
+int
+MS5611_I2C::read(unsigned offset, void *data, unsigned count)
+{
+ union _cvt {
+ uint8_t b[4];
+ uint32_t w;
+ } *cvt = (_cvt *)data;
+ uint8_t buf[3];
+
+ /* read the most recent measurement */
+ uint8_t cmd = 0;
+ int ret = transfer(&cmd, 1, &buf[0], 3);
+ if (ret == OK) {
+ /* fetch the raw value */
+ cvt->b[0] = buf[2];
+ cvt->b[1] = buf[1];
+ cvt->b[2] = buf[0];
+ cvt->b[3] = 0;
+ }
+
+ return ret;
+}
+
+int
+MS5611_I2C::ioctl(unsigned operation, unsigned &arg)
+{
+ int ret;
+
+ switch (operation) {
+ case IOCTL_RESET:
+ ret = _reset();
+ break;
+
+ case IOCTL_MEASURE:
+ ret = _measure(arg);
+ break;
+
+ default:
+ ret = EINVAL;
+ }
+
+ return ret;
+}
+
+int
+MS5611_I2C::probe()
+{
+ _retries = 10;
+
+ if ((OK == _probe_address(MS5611_ADDRESS_1)) ||
+ (OK == _probe_address(MS5611_ADDRESS_2))) {
+ /*
+ * Disable retries; we may enable them selectively in some cases,
+ * but the device gets confused if we retry some of the commands.
+ */
+ _retries = 0;
+ return OK;
+ }
+
+ return -EIO;
+}
+
+int
+MS5611_I2C::_probe_address(uint8_t address)
+{
+ /* select the address we are going to try */
+ set_address(address);
+
+ /* send reset command */
+ if (OK != _reset())
+ return -EIO;
+
+ /* read PROM */
+ if (OK != _read_prom())
+ return -EIO;
+
+ return OK;
+}
+
+
+int
+MS5611_I2C::_reset()
+{
+ unsigned old_retrycount = _retries;
+ uint8_t cmd = ADDR_RESET_CMD;
+ int result;
+
+ /* bump the retry count */
+ _retries = 10;
+ result = transfer(&cmd, 1, nullptr, 0);
+ _retries = old_retrycount;
+
+ return result;
+}
+
+int
+MS5611_I2C::_measure(unsigned addr)
+{
+ /*
+ * Disable retries on this command; we can't know whether failure
+ * means the device did or did not see the command.
+ */
+ _retries = 0;
+
+ uint8_t cmd = addr;
+ return transfer(&cmd, 1, nullptr, 0);
+}
+
+int
+MS5611_I2C::_read_prom()
+{
+ uint8_t prom_buf[2];
+ union {
+ uint8_t b[2];
+ uint16_t w;
+ } cvt;
+
+ /*
+ * Wait for PROM contents to be in the device (2.8 ms) in the case we are
+ * called immediately after reset.
+ */
+ usleep(3000);
+
+ /* read and convert PROM words */
+ for (int i = 0; i < 8; i++) {
+ uint8_t cmd = ADDR_PROM_SETUP + (i * 2);
+
+ if (OK != transfer(&cmd, 1, &prom_buf[0], 2))
+ break;
+
+ /* assemble 16 bit value and convert from big endian (sensor) to little endian (MCU) */
+ cvt.b[0] = prom_buf[1];
+ cvt.b[1] = prom_buf[0];
+ _prom.c[i] = cvt.w;
+ }
+
+ /* calculate CRC and return success/failure accordingly */
+ return ms5611::crc4(&_prom.c[0]) ? OK : -EIO;
+}
+
+#endif /* PX4_I2C_OBDEV_MS5611 */
diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp
new file mode 100644
index 000000000..f6c624340
--- /dev/null
+++ b/src/drivers/ms5611/ms5611_spi.cpp
@@ -0,0 +1,273 @@
+/****************************************************************************
+ *
+ * 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 ms5611_spi.cpp
+ *
+ * SPI interface for MS5611
+ */
+
+/* XXX trim includes */
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+#include <debug.h>
+#include <errno.h>
+#include <unistd.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/device/spi.h>
+
+#include "ms5611.h"
+#include "board_config.h"
+
+/* SPI protocol address bits */
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#ifdef PX4_SPIDEV_BARO
+
+device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf);
+
+class MS5611_SPI : public device::SPI
+{
+public:
+ MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf);
+ virtual ~MS5611_SPI();
+
+ virtual int init();
+ virtual int read(unsigned offset, void *data, unsigned count);
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
+private:
+ ms5611::prom_u &_prom;
+
+ /**
+ * Send a reset command to the MS5611.
+ *
+ * This is required after any bus reset.
+ */
+ int _reset();
+
+ /**
+ * Send a measure command to the MS5611.
+ *
+ * @param addr Which address to use for the measure operation.
+ */
+ int _measure(unsigned addr);
+
+ /**
+ * Read the MS5611 PROM
+ *
+ * @return OK if the PROM reads successfully.
+ */
+ int _read_prom();
+
+ /**
+ * Read a 16-bit register value.
+ *
+ * @param reg The register to read.
+ */
+ uint16_t _reg16(unsigned reg);
+
+ /**
+ * Wrapper around transfer() that prevents interrupt-context transfers
+ * from pre-empting us. The sensor may (does) share a bus with sensors
+ * that are polled from interrupt context (or we may be pre-empted)
+ * so we need to guarantee that transfers complete without interruption.
+ */
+ int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
+};
+
+device::Device *
+MS5611_spi_interface(ms5611::prom_u &prom_buf)
+{
+ return new MS5611_SPI(1 /* XXX MAGIC NUMBER */, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
+}
+
+MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) :
+ SPI("MS5611_SPI", nullptr, bus, device, SPIDEV_MODE3, 2000000),
+ _prom(prom_buf)
+{
+}
+
+MS5611_SPI::~MS5611_SPI()
+{
+}
+
+int
+MS5611_SPI::init()
+{
+ int ret;
+
+ ret = SPI::init();
+ if (ret != OK) {
+ debug("SPI init failed");
+ goto out;
+ }
+
+ /* send reset command */
+ ret = _reset();
+ if (ret != OK) {
+ debug("reset failed");
+ goto out;
+ }
+
+ /* read PROM */
+ ret = _read_prom();
+ if (ret != OK) {
+ debug("prom readout failed");
+ goto out;
+ }
+
+out:
+ return ret;
+}
+
+int
+MS5611_SPI::read(unsigned offset, void *data, unsigned count)
+{
+ union _cvt {
+ uint8_t b[4];
+ uint32_t w;
+ } *cvt = (_cvt *)data;
+ uint8_t buf[4];
+
+ /* read the most recent measurement */
+ buf[0] = 0 | DIR_WRITE;
+ int ret = _transfer(&buf[0], &buf[0], sizeof(buf));
+
+ if (ret == OK) {
+ /* fetch the raw value */
+ cvt->b[0] = buf[3];
+ cvt->b[1] = buf[2];
+ cvt->b[2] = buf[1];
+ cvt->b[3] = 0;
+
+ ret = count;
+ }
+
+ return ret;
+}
+
+int
+MS5611_SPI::ioctl(unsigned operation, unsigned &arg)
+{
+ int ret;
+
+ switch (operation) {
+ case IOCTL_RESET:
+ ret = _reset();
+ break;
+
+ case IOCTL_MEASURE:
+ ret = _measure(arg);
+ break;
+
+ default:
+ ret = EINVAL;
+ }
+
+ if (ret != OK) {
+ errno = ret;
+ return -1;
+ }
+ return 0;
+}
+
+int
+MS5611_SPI::_reset()
+{
+ uint8_t cmd = ADDR_RESET_CMD | DIR_WRITE;
+
+ return _transfer(&cmd, nullptr, 1);
+}
+
+int
+MS5611_SPI::_measure(unsigned addr)
+{
+ uint8_t cmd = addr | DIR_WRITE;
+
+ return _transfer(&cmd, nullptr, 1);
+}
+
+
+int
+MS5611_SPI::_read_prom()
+{
+ /*
+ * Wait for PROM contents to be in the device (2.8 ms) in the case we are
+ * called immediately after reset.
+ */
+ usleep(3000);
+
+ /* read and convert PROM words */
+ for (int i = 0; i < 8; i++) {
+ uint8_t cmd = (ADDR_PROM_SETUP + (i * 2));
+ _prom.c[i] = _reg16(cmd);
+ }
+
+ /* calculate CRC and return success/failure accordingly */
+ return ms5611::crc4(&_prom.c[0]) ? OK : -EIO;
+}
+
+uint16_t
+MS5611_SPI::_reg16(unsigned reg)
+{
+ uint8_t cmd[3];
+
+ cmd[0] = reg | DIR_READ;
+
+ _transfer(cmd, cmd, sizeof(cmd));
+
+ return (uint16_t)(cmd[1] << 8) | cmd[2];
+}
+
+int
+MS5611_SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
+{
+ irqstate_t flags = irqsave();
+
+ int ret = transfer(send, recv, len);
+
+ irqrestore(flags);
+
+ return ret;
+}
+
+#endif /* PX4_SPIDEV_BARO */
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index a98b527b1..6d4019f24 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -34,7 +34,7 @@
/**
* @file fmu.cpp
*
- * Driver/configurator for the PX4 FMU multi-purpose port.
+ * Driver/configurator for the PX4 FMU multi-purpose port on v1 and v2 boards.
*/
#include <nuttx/config.h>
@@ -57,9 +57,10 @@
#include <drivers/device/device.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_gpio.h>
-#include <drivers/boards/px4fmu/px4fmu_internal.h>
#include <drivers/drv_hrt.h>
+# include <board_config.h>
+
#include <systemlib/systemlib.h>
#include <systemlib/err.h>
#include <systemlib/mixer/mixer.h>
@@ -69,17 +70,21 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/actuator_armed.h>
#include <systemlib/err.h>
-#include <systemlib/ppm_decode.h>
+#ifdef HRT_PPM_CHANNEL
+# include <systemlib/ppm_decode.h>
+#endif
class PX4FMU : public device::CDev
{
public:
enum Mode {
+ MODE_NONE,
MODE_2PWM,
MODE_4PWM,
- MODE_NONE
+ MODE_6PWM,
};
PX4FMU();
virtual ~PX4FMU();
@@ -104,7 +109,7 @@ private:
unsigned _current_update_rate;
int _task;
int _t_actuators;
- int _t_armed;
+ int _t_actuator_armed;
orb_advert_t _t_outputs;
orb_advert_t _t_actuators_effective;
unsigned _num_outputs;
@@ -146,6 +151,7 @@ private:
};
const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
{GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1},
@@ -154,6 +160,22 @@ const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
{GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1},
{GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2},
{GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2},
+#endif
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
+ {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
+ {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, 0},
+ {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0},
+ {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0},
+ {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0},
+
+ {0, GPIO_VDD_5V_PERIPH_EN, 0},
+ {0, GPIO_VDD_3V3_SENSORS_EN, 0},
+ {GPIO_VDD_BRICK_VALID, 0, 0},
+ {GPIO_VDD_SERVO_VALID, 0, 0},
+ {GPIO_VDD_5V_HIPOWER_OC, 0, 0},
+ {GPIO_VDD_5V_PERIPH_OC, 0, 0},
+#endif
};
const unsigned PX4FMU::_ngpio = sizeof(PX4FMU::_gpio_tab) / sizeof(PX4FMU::_gpio_tab[0]);
@@ -174,7 +196,7 @@ PX4FMU::PX4FMU() :
_current_update_rate(0),
_task(-1),
_t_actuators(-1),
- _t_armed(-1),
+ _t_actuator_armed(-1),
_t_outputs(0),
_t_actuators_effective(0),
_num_outputs(0),
@@ -271,9 +293,36 @@ PX4FMU::set_mode(Mode mode)
* are presented on the output pins.
*/
switch (mode) {
- case MODE_2PWM: // multi-port with flow control lines as PWM
- case MODE_4PWM: // multi-port as 4 PWM outs
- debug("MODE_%dPWM", (mode == MODE_2PWM) ? 2 : 4);
+ case MODE_2PWM: // v1 multi-port with flow control lines as PWM
+ debug("MODE_2PWM");
+
+ /* default output rates */
+ _pwm_default_rate = 50;
+ _pwm_alt_rate = 50;
+ _pwm_alt_rate_channels = 0;
+
+ /* XXX magic numbers */
+ up_pwm_servo_init(0x3);
+ set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
+
+ break;
+
+ case MODE_4PWM: // v1 multi-port as 4 PWM outs
+ debug("MODE_4PWM");
+
+ /* default output rates */
+ _pwm_default_rate = 50;
+ _pwm_alt_rate = 50;
+ _pwm_alt_rate_channels = 0;
+
+ /* XXX magic numbers */
+ up_pwm_servo_init(0xf);
+ set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
+
+ break;
+
+ case MODE_6PWM: // v2 PWMs as 6 PWM outs
+ debug("MODE_6PWM");
/* default output rates */
_pwm_default_rate = 50;
@@ -281,7 +330,7 @@ PX4FMU::set_mode(Mode mode)
_pwm_alt_rate_channels = 0;
/* XXX magic numbers */
- up_pwm_servo_init((mode == MODE_2PWM) ? 0x3 : 0xf);
+ up_pwm_servo_init(0x3f);
set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
break;
@@ -376,8 +425,8 @@ PX4FMU::task_main()
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
+ orb_set_interval(_t_actuator_armed, 200); /* 5Hz update rate */
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
@@ -396,17 +445,17 @@ PX4FMU::task_main()
pollfd fds[2];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_armed;
fds[1].events = POLLIN;
- unsigned num_outputs = (_mode == MODE_2PWM) ? 2 : 4;
-
+#ifdef HRT_PPM_CHANNEL
// rc input, published to ORB
struct rc_input_values rc_in;
orb_advert_t to_input_rc = 0;
memset(&rc_in, 0, sizeof(rc_in));
rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM;
+#endif
log("starting");
@@ -460,6 +509,23 @@ PX4FMU::task_main()
/* can we mix? */
if (_mixers != nullptr) {
+ unsigned num_outputs;
+
+ switch (_mode) {
+ case MODE_2PWM:
+ num_outputs = 2;
+ break;
+ case MODE_4PWM:
+ num_outputs = 4;
+ break;
+ case MODE_6PWM:
+ num_outputs = 6;
+ break;
+ default:
+ num_outputs = 0;
+ break;
+ }
+
/* do mixing */
outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
outputs.timestamp = hrt_absolute_time();
@@ -502,7 +568,7 @@ PX4FMU::task_main()
actuator_armed_s aa;
/* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_armed, &aa);
+ orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &aa);
/* update PWM servo armed status if armed and not locked down */
bool set_armed = aa.armed && !aa.lockdown;
@@ -512,6 +578,7 @@ PX4FMU::task_main()
}
}
+#ifdef HRT_PPM_CHANNEL
// see if we have new PPM input data
if (ppm_last_valid_decode != rc_in.timestamp) {
// we have a new PPM frame. Publish it.
@@ -531,11 +598,13 @@ PX4FMU::task_main()
orb_publish(ORB_ID(input_rc), to_input_rc, &rc_in);
}
}
+#endif
+
}
::close(_t_actuators);
::close(_t_actuators_effective);
- ::close(_t_armed);
+ ::close(_t_actuator_armed);
/* make sure servos are off */
up_pwm_servo_deinit();
@@ -579,6 +648,7 @@ PX4FMU::ioctl(file *filp, int cmd, unsigned long arg)
switch (_mode) {
case MODE_2PWM:
case MODE_4PWM:
+ case MODE_6PWM:
ret = pwm_ioctl(filp, cmd, arg);
break;
@@ -623,16 +693,24 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
ret = set_pwm_rate(arg, _pwm_default_rate, _pwm_alt_rate);
break;
- case PWM_SERVO_SET(2):
+ case PWM_SERVO_SET(5):
+ case PWM_SERVO_SET(4):
+ if (_mode < MODE_6PWM) {
+ ret = -EINVAL;
+ break;
+ }
+
+ /* FALLTHROUGH */
case PWM_SERVO_SET(3):
- if (_mode != MODE_4PWM) {
+ case PWM_SERVO_SET(2):
+ if (_mode < MODE_4PWM) {
ret = -EINVAL;
break;
}
/* FALLTHROUGH */
- case PWM_SERVO_SET(0):
case PWM_SERVO_SET(1):
+ case PWM_SERVO_SET(0):
if (arg < 2100) {
up_pwm_servo_set(cmd - PWM_SERVO_SET(0), arg);
} else {
@@ -641,16 +719,24 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
- case PWM_SERVO_GET(2):
+ case PWM_SERVO_GET(5):
+ case PWM_SERVO_GET(4):
+ if (_mode < MODE_6PWM) {
+ ret = -EINVAL;
+ break;
+ }
+
+ /* FALLTHROUGH */
case PWM_SERVO_GET(3):
- if (_mode != MODE_4PWM) {
+ case PWM_SERVO_GET(2):
+ if (_mode < MODE_4PWM) {
ret = -EINVAL;
break;
}
/* FALLTHROUGH */
- case PWM_SERVO_GET(0):
case PWM_SERVO_GET(1):
+ case PWM_SERVO_GET(0):
*(servo_position_t *)arg = up_pwm_servo_get(cmd - PWM_SERVO_GET(0));
break;
@@ -658,16 +744,26 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_GET_RATEGROUP(1):
case PWM_SERVO_GET_RATEGROUP(2):
case PWM_SERVO_GET_RATEGROUP(3):
+ case PWM_SERVO_GET_RATEGROUP(4):
+ case PWM_SERVO_GET_RATEGROUP(5):
*(uint32_t *)arg = up_pwm_servo_get_rate_group(cmd - PWM_SERVO_GET_RATEGROUP(0));
break;
case PWM_SERVO_GET_COUNT:
case MIXERIOCGETOUTPUTCOUNT:
- if (_mode == MODE_4PWM) {
+ switch (_mode) {
+ case MODE_6PWM:
+ *(unsigned *)arg = 6;
+ break;
+ case MODE_4PWM:
*(unsigned *)arg = 4;
-
- } else {
+ break;
+ case MODE_2PWM:
*(unsigned *)arg = 2;
+ break;
+ default:
+ ret = -EINVAL;
+ break;
}
break;
@@ -743,17 +839,17 @@ ssize_t
PX4FMU::write(file *filp, const char *buffer, size_t len)
{
unsigned count = len / 2;
- uint16_t values[4];
+ uint16_t values[6];
- if (count > 4) {
- // we only have 4 PWM outputs on the FMU
- count = 4;
+ if (count > 6) {
+ // we have at most 6 outputs
+ count = 6;
}
// allow for misaligned values
- memcpy(values, buffer, count*2);
+ memcpy(values, buffer, count * 2);
- for (uint8_t i=0; i<count; i++) {
+ for (uint8_t i = 0; i < count; i++) {
up_pwm_servo_set(i, values[i]);
}
return count * 2;
@@ -763,19 +859,28 @@ void
PX4FMU::gpio_reset(void)
{
/*
- * Setup default GPIO config - all pins as GPIOs, GPIO driver chip
- * to input mode.
+ * Setup default GPIO config - all pins as GPIOs, input if
+ * possible otherwise output if possible.
*/
- for (unsigned i = 0; i < _ngpio; i++)
- stm32_configgpio(_gpio_tab[i].input);
+ for (unsigned i = 0; i < _ngpio; i++) {
+ if (_gpio_tab[i].input != 0) {
+ stm32_configgpio(_gpio_tab[i].input);
+ } else if (_gpio_tab[i].output != 0) {
+ stm32_configgpio(_gpio_tab[i].output);
+ }
+ }
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+ /* if we have a GPIO direction control, set it to zero (input) */
stm32_gpiowrite(GPIO_GPIO_DIR, 0);
stm32_configgpio(GPIO_GPIO_DIR);
+#endif
}
void
PX4FMU::gpio_set_function(uint32_t gpios, int function)
{
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
/*
* GPIOs 0 and 1 must have the same direction as they are buffered
* by a shared 2-port driver. Any attempt to set either sets both.
@@ -787,6 +892,7 @@ PX4FMU::gpio_set_function(uint32_t gpios, int function)
if (GPIO_SET_OUTPUT == function)
stm32_gpiowrite(GPIO_GPIO_DIR, 1);
}
+#endif
/* configure selected GPIOs as required */
for (unsigned i = 0; i < _ngpio; i++) {
@@ -809,9 +915,11 @@ PX4FMU::gpio_set_function(uint32_t gpios, int function)
}
}
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
/* flip buffer to input mode if required */
if ((GPIO_SET_INPUT == function) && (gpios & 3))
stm32_gpiowrite(GPIO_GPIO_DIR, 0);
+#endif
}
void
@@ -912,14 +1020,21 @@ fmu_new_mode(PortMode new_mode)
/* nothing more to do here */
break;
- case PORT_FULL_SERIAL:
- /* set all multi-GPIOs to serial mode */
- gpio_bits = GPIO_MULTI_1 | GPIO_MULTI_2 | GPIO_MULTI_3 | GPIO_MULTI_4;
- break;
-
case PORT_FULL_PWM:
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
/* select 4-pin PWM mode */
servo_mode = PX4FMU::MODE_4PWM;
+#endif
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ servo_mode = PX4FMU::MODE_6PWM;
+#endif
+ break;
+
+ /* mixed modes supported on v1 board only */
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+ case PORT_FULL_SERIAL:
+ /* set all multi-GPIOs to serial mode */
+ gpio_bits = GPIO_MULTI_1 | GPIO_MULTI_2 | GPIO_MULTI_3 | GPIO_MULTI_4;
break;
case PORT_GPIO_AND_SERIAL:
@@ -938,6 +1053,9 @@ fmu_new_mode(PortMode new_mode)
/* select 2-pin PWM mode */
servo_mode = PX4FMU::MODE_2PWM;
break;
+#endif
+ default:
+ return -1;
}
/* adjust GPIO config for serial mode(s) */
@@ -979,22 +1097,84 @@ void
test(void)
{
int fd;
-
- fd = open(PWM_OUTPUT_DEVICE_PATH, 0);
+ unsigned servo_count = 0;
+ unsigned pwm_value = 1000;
+ int direction = 1;
+
+ fd = open(PX4FMU_DEVICE_PATH, O_RDWR);
if (fd < 0)
errx(1, "open fail");
if (ioctl(fd, PWM_SERVO_ARM, 0) < 0) err(1, "servo arm failed");
- if (ioctl(fd, PWM_SERVO_SET(0), 1000) < 0) err(1, "servo 1 set failed");
+ if (ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count) != 0) {
+ err(1, "Unable to get servo count\n");
+ }
+
+ warnx("Testing %u servos", (unsigned)servo_count);
+
+ int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
+ if (!console)
+ err(1, "failed opening console");
+
+ warnx("Press CTRL-C or 'c' to abort.");
+
+ for (;;) {
+ /* sweep all servos between 1000..2000 */
+ servo_position_t servos[servo_count];
+ for (unsigned i = 0; i < servo_count; i++)
+ servos[i] = pwm_value;
+
+ if (direction == 1) {
+ // use ioctl interface for one direction
+ for (unsigned i=0; i < servo_count; i++) {
+ if (ioctl(fd, PWM_SERVO_SET(i), servos[i]) < 0) {
+ err(1, "servo %u set failed", i);
+ }
+ }
+ } else {
+ // and use write interface for the other direction
+ int ret = write(fd, servos, sizeof(servos));
+ if (ret != (int)sizeof(servos))
+ err(1, "error writing PWM servo data, wrote %u got %d", sizeof(servos), ret);
+ }
+
+ if (direction > 0) {
+ if (pwm_value < 2000) {
+ pwm_value++;
+ } else {
+ direction = -1;
+ }
+ } else {
+ if (pwm_value > 1000) {
+ pwm_value--;
+ } else {
+ direction = 1;
+ }
+ }
- if (ioctl(fd, PWM_SERVO_SET(1), 1200) < 0) err(1, "servo 2 set failed");
+ /* readback servo values */
+ for (unsigned i = 0; i < servo_count; i++) {
+ servo_position_t value;
- if (ioctl(fd, PWM_SERVO_SET(2), 1400) < 0) err(1, "servo 3 set failed");
+ if (ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&value))
+ err(1, "error reading PWM servo %d", i);
+ if (value != servos[i])
+ errx(1, "servo %d readback error, got %u expected %u", i, value, servos[i]);
+ }
- if (ioctl(fd, PWM_SERVO_SET(3), 1600) < 0) err(1, "servo 4 set failed");
+ /* Check if user wants to quit */
+ char c;
+ if (read(console, &c, 1) == 1) {
+ if (c == 0x03 || c == 0x63) {
+ warnx("User abort\n");
+ break;
+ }
+ }
+ }
+ close(console);
close(fd);
exit(0);
@@ -1053,12 +1233,13 @@ fmu_main(int argc, char *argv[])
if (!strcmp(verb, "mode_gpio")) {
new_mode = PORT_FULL_GPIO;
- } else if (!strcmp(verb, "mode_serial")) {
- new_mode = PORT_FULL_SERIAL;
-
} else if (!strcmp(verb, "mode_pwm")) {
new_mode = PORT_FULL_PWM;
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+ } else if (!strcmp(verb, "mode_serial")) {
+ new_mode = PORT_FULL_SERIAL;
+
} else if (!strcmp(verb, "mode_gpio_serial")) {
new_mode = PORT_GPIO_AND_SERIAL;
@@ -1067,6 +1248,7 @@ fmu_main(int argc, char *argv[])
} else if (!strcmp(verb, "mode_pwm_gpio")) {
new_mode = PORT_PWM_AND_GPIO;
+#endif
}
/* was a new mode set? */
@@ -1088,6 +1270,10 @@ fmu_main(int argc, char *argv[])
fake(argc - 1, argv + 1);
fprintf(stderr, "FMU: unrecognised command, try:\n");
- fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio\n");
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
+ fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n");
+#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ fprintf(stderr, " mode_gpio, mode_pwm, test\n");
+#endif
exit(1);
}
diff --git a/src/drivers/px4io/module.mk b/src/drivers/px4io/module.mk
index 328e5a684..2054faa12 100644
--- a/src/drivers/px4io/module.mk
+++ b/src/drivers/px4io/module.mk
@@ -38,4 +38,9 @@
MODULE_COMMAND = px4io
SRCS = px4io.cpp \
- uploader.cpp
+ px4io_uploader.cpp \
+ px4io_serial.cpp \
+ px4io_i2c.cpp
+
+# XXX prune to just get UART registers
+INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index fed83ea1a..15873f79b 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -58,7 +58,6 @@
#include <arch/board/board.h>
#include <drivers/device/device.h>
-#include <drivers/device/i2c.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_gpio.h>
@@ -75,7 +74,9 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
-#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/safety.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/battery_status.h>
@@ -83,9 +84,13 @@
#include <debug.h>
#include <mavlink/mavlink_log.h>
-#include "uploader.h"
#include <modules/px4iofirmware/protocol.h>
+#include "uploader.h"
+
+extern device::Device *PX4IO_i2c_interface() weak_function;
+extern device::Device *PX4IO_serial_interface() weak_function;
+
#define PX4IO_SET_DEBUG _IOC(0xff00, 0)
#define PX4IO_INAIR_RESTART_ENABLE _IOC(0xff00, 1)
@@ -94,7 +99,7 @@
*
* Encapsulates PX4FMU to PX4IO communications modeled as file operations.
*/
-class PX4IO : public device::I2C
+class PX4IO : public device::CDev
{
public:
/**
@@ -102,7 +107,8 @@ public:
*
* Initialize all class variables.
*/
- PX4IO();
+ PX4IO(device::Device *interface);
+
/**
* Destructor.
*
@@ -143,8 +149,8 @@ public:
/**
* Set the update rate for actuator outputs from FMU to IO.
*
- * @param[in] rate The rate in Hz actuator output are sent to IO.
- * Min 10 Hz, max 400 Hz
+ * @param[in] rate The rate in Hz actuator outpus are sent to IO.
+ * Min 10 Hz, max 400 Hz
*/
int set_update_rate(int rate);
@@ -159,12 +165,27 @@ public:
/**
* Push failsafe values to IO.
*
- * @param[in] vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full)
- * @param[in] len Number of channels, could up to 8
+ * @param[in] vals Failsafe control inputs: in us PPM (900 for zero, 1500 for centered, 2100 for full)
+ * @param[in] len Number of channels, could up to 8
*/
int set_failsafe_values(const uint16_t *vals, unsigned len);
/**
+ * Set the minimum PWM signals when armed
+ */
+ int set_min_values(const uint16_t *vals, unsigned len);
+
+ /**
+ * Set the maximum PWM signal when armed
+ */
+ int set_max_values(const uint16_t *vals, unsigned len);
+
+ /**
+ * Set an idle PWM signal that is active right after startup, even when SAFETY_SAFE
+ */
+ int set_idle_values(const uint16_t *vals, unsigned len);
+
+ /**
* Print IO status.
*
* Print all relevant IO status information
@@ -172,6 +193,11 @@ public:
void print_status();
/**
+ * Disable RC input handling
+ */
+ int disable_rc_handling();
+
+ /**
* Set the DSM VCC is controlled by relay one flag
*
* @param[in] enable true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled
@@ -192,14 +218,18 @@ public:
};
private:
+ device::Device *_interface;
+
// XXX
+ unsigned _hardware; ///< Hardware revision
unsigned _max_actuators; ///<Maximum # of actuators supported by PX4IO
unsigned _max_controls; ///<Maximum # of controls supported by PX4IO
unsigned _max_rc_input; ///<Maximum receiver channels supported by PX4IO
unsigned _max_relays; ///<Maximum relays supported by PX4IO
unsigned _max_transfer; ///<Maximum number of I2C transfers supported by PX4IO
- unsigned _update_interval; ///<Subscription interval limiting send rate
+ unsigned _update_interval; ///< Subscription interval limiting send rate
+ bool _rc_handling_disabled; ///< If set, IO does not evaluate, but only forward the RC values
volatile int _task; ///<worker task id
volatile bool _task_should_exit; ///<worker terminate flag
@@ -213,16 +243,17 @@ private:
uint16_t _alarms; ///<Various IO alarms
/* subscribed topics */
- int _t_actuators; ///<actuator controls topic
- int _t_armed; ///<system armed control topic
- int _t_vstatus; ///<system / vehicle status
- int _t_param; ///<parameter update topic
+ int _t_actuators; ///< actuator controls topic
+ int _t_actuator_armed; ///< system armed control topic
+ int _t_vehicle_control_mode;///< vehicle control mode topic
+ int _t_param; ///< parameter update topic
/* advertised topics */
- orb_advert_t _to_input_rc; ///<rc inputs from IO topic
- orb_advert_t _to_actuators_effective; ///<effective actuator controls topic
- orb_advert_t _to_outputs; ///<mixed servo outputs topic
- orb_advert_t _to_battery; ///<battery status / voltage topic
+ orb_advert_t _to_input_rc; ///< rc inputs from io
+ orb_advert_t _to_actuators_effective; ///< effective actuator controls topic
+ orb_advert_t _to_outputs; ///< mixed servo outputs topic
+ orb_advert_t _to_battery; ///< battery status / voltage
+ orb_advert_t _to_safety; ///< status of safety
actuator_outputs_s _outputs; ///<mixed outputs
actuator_controls_effective_s _controls_effective; ///<effective controls
@@ -269,6 +300,11 @@ private:
int io_get_status();
/**
+ * Disable RC input handling
+ */
+ int io_disable_rc_handling();
+
+ /**
* Fetch RC inputs from IO.
*
* @param input_rc Input structure to populate.
@@ -298,7 +334,7 @@ private:
* @param offset Register offset to start writing at.
* @param values Pointer to array of values to write.
* @param num_values The number of values to write.
- * @return Zero if all values were successfully written.
+ * @return OK if all values were successfully written.
*/
int io_reg_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values);
@@ -308,7 +344,7 @@ private:
* @param page Register page to write to.
* @param offset Register offset to write to.
* @param value Value to write.
- * @return Zero if the value was written successfully.
+ * @return OK if the value was written successfully.
*/
int io_reg_set(uint8_t page, uint8_t offset, const uint16_t value);
@@ -319,7 +355,7 @@ private:
* @param offset Register offset to start reading from.
* @param values Pointer to array where values should be stored.
* @param num_values The number of values to read.
- * @return Zero if all values were successfully read.
+ * @return OK if all values were successfully read.
*/
int io_reg_get(uint8_t page, uint8_t offset, uint16_t *values, unsigned num_values);
@@ -376,14 +412,17 @@ PX4IO *g_dev;
}
-PX4IO::PX4IO() :
- I2C("px4io", PX4IO_DEVICE_PATH, PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_PX4IO, 320000),
+PX4IO::PX4IO(device::Device *interface) :
+ CDev("px4io", PX4IO_DEVICE_PATH),
+ _interface(interface),
+ _hardware(0),
_max_actuators(0),
_max_controls(0),
_max_rc_input(0),
_max_relays(0),
_max_transfer(16), /* sensible default */
_update_interval(0),
+ _rc_handling_disabled(false),
_task(-1),
_task_should_exit(false),
_mavlink_fd(-1),
@@ -391,13 +430,14 @@ PX4IO::PX4IO() :
_status(0),
_alarms(0),
_t_actuators(-1),
- _t_armed(-1),
- _t_vstatus(-1),
+ _t_actuator_armed(-1),
+ _t_vehicle_control_mode(-1),
_t_param(-1),
_to_input_rc(0),
_to_actuators_effective(0),
_to_outputs(0),
_to_battery(0),
+ _to_safety(0),
_primary_pwm_device(false),
_battery_amp_per_volt(90.0f/5.0f), // this matches the 3DR current sensor
_battery_amp_bias(0),
@@ -429,6 +469,9 @@ PX4IO::~PX4IO()
if (_task != -1)
task_delete(_task);
+ if (_interface != nullptr)
+ delete _interface;
+
g_dev = nullptr;
}
@@ -440,31 +483,30 @@ PX4IO::init()
ASSERT(_task == -1);
/* do regular cdev init */
- ret = I2C::init();
+ ret = CDev::init();
if (ret != OK)
return ret;
- /*
- * Enable a couple of retries for operations to IO.
- *
- * Register read/write operations are intentionally idempotent
- * so this is safe as designed.
- */
- _retries = 2;
-
/* get some parameters */
+ unsigned protocol = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION);
+ if (protocol != PX4IO_PROTOCOL_VERSION) {
+ log("protocol/firmware mismatch");
+ mavlink_log_emergency(_mavlink_fd, "[IO] protocol/firmware mismatch, abort.");
+ return -1;
+ }
+ _hardware = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_HARDWARE_VERSION);
_max_actuators = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ACTUATOR_COUNT);
- _max_controls = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_CONTROL_COUNT);
+ _max_controls = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_CONTROL_COUNT);
_max_relays = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RELAY_COUNT);
_max_transfer = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_MAX_TRANSFER) - 2;
_max_rc_input = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RC_INPUT_COUNT);
if ((_max_actuators < 1) || (_max_actuators > 255) ||
- (_max_relays < 1) || (_max_relays > 255) ||
- (_max_transfer < 16) || (_max_transfer > 255) ||
+ (_max_relays > 32) ||
+ (_max_transfer < 16) || (_max_transfer > 255) ||
(_max_rc_input < 1) || (_max_rc_input > 255)) {
- log("failed getting parameters from PX4IO");
- mavlink_log_emergency(_mavlink_fd, "[IO] param read fail, abort.");
+ log("config read error");
+ mavlink_log_emergency(_mavlink_fd, "[IO] config read fail, abort.");
return -1;
}
if (_max_rc_input > RC_INPUT_MAX_CHANNELS)
@@ -492,26 +534,27 @@ PX4IO::init()
(reg & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
mavlink_log_emergency(_mavlink_fd, "[IO] RECOVERING FROM FMU IN-AIR RESTART");
+ log("INAIR RESTART RECOVERY (needs commander app running)");
/* WARNING: COMMANDER app/vehicle status must be initialized.
* If this fails (or the app is not started), worst-case IO
* remains untouched (so manual override is still available).
*/
- int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int safety_sub = orb_subscribe(ORB_ID(actuator_armed));
/* fill with initial values, clear updated flag */
- vehicle_status_s status;
+ struct actuator_armed_s safety;
uint64_t try_start_time = hrt_absolute_time();
bool updated = false;
- /* keep checking for an update, ensure we got a recent state,
+ /* keep checking for an update, ensure we got a arming information,
not something that was published a long time ago. */
do {
- orb_check(vstatus_sub, &updated);
+ orb_check(safety_sub, &updated);
if (updated) {
/* got data, copy and exit loop */
- orb_copy(ORB_ID(vehicle_status), vstatus_sub, &status);
+ orb_copy(ORB_ID(actuator_armed), safety_sub, &safety);
break;
}
@@ -519,7 +562,7 @@ PX4IO::init()
usleep(10000);
/* abort after 5s */
- if ((hrt_absolute_time() - try_start_time)/1000 > 50000) {
+ if ((hrt_absolute_time() - try_start_time)/1000 > 3000) {
log("failed to recover from in-air restart (1), aborting IO driver init.");
return 1;
}
@@ -537,35 +580,41 @@ PX4IO::init()
cmd.param6 = 0;
cmd.param7 = 0;
cmd.command = VEHICLE_CMD_COMPONENT_ARM_DISARM;
- cmd.target_system = status.system_id;
- cmd.target_component = status.component_id;
- cmd.source_system = status.system_id;
- cmd.source_component = status.component_id;
+ // cmd.target_system = status.system_id;
+ // cmd.target_component = status.component_id;
+ // cmd.source_system = status.system_id;
+ // cmd.source_component = status.component_id;
/* ask to confirm command */
cmd.confirmation = 1;
/* send command once */
- (void)orb_advertise(ORB_ID(vehicle_command), &cmd);
+ orb_advert_t pub = orb_advertise(ORB_ID(vehicle_command), &cmd);
/* spin here until IO's state has propagated into the system */
do {
- orb_check(vstatus_sub, &updated);
+ orb_check(safety_sub, &updated);
if (updated) {
- orb_copy(ORB_ID(vehicle_status), vstatus_sub, &status);
+ orb_copy(ORB_ID(actuator_armed), safety_sub, &safety);
}
- /* wait 10 ms */
- usleep(10000);
+ /* wait 50 ms */
+ usleep(50000);
/* abort after 5s */
- if ((hrt_absolute_time() - try_start_time)/1000 > 50000) {
+ if ((hrt_absolute_time() - try_start_time)/1000 > 2000) {
log("failed to recover from in-air restart (2), aborting IO driver init.");
return 1;
}
- /* keep waiting for state change for 10 s */
- } while (!status.flag_system_armed);
+ /* re-send if necessary */
+ if (!safety.armed) {
+ orb_publish(ORB_ID(vehicle_command), pub, &cmd);
+ log("re-sending arm cmd");
+ }
+
+ /* keep waiting for state change for 2 s */
+ } while (!safety.armed);
/* regular boot, no in-air restart, init IO */
} else {
@@ -575,14 +624,19 @@ PX4IO::init()
io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING,
PX4IO_P_SETUP_ARMING_FMU_ARMED |
PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK |
- PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK, 0);
+ PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK |
+ PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE, 0);
- /* publish RC config to IO */
- ret = io_set_rc_config();
- if (ret != OK) {
- log("failed to update RC input config");
- mavlink_log_info(_mavlink_fd, "[IO] RC config upload fail");
- return ret;
+ if (_rc_handling_disabled) {
+ ret = io_disable_rc_handling();
+ } else {
+ /* publish RC config to IO */
+ ret = io_set_rc_config();
+ if (ret != OK) {
+ log("failed to update RC input config");
+ mavlink_log_info(_mavlink_fd, "[IO] RC config upload fail");
+ return ret;
+ }
}
}
@@ -596,7 +650,7 @@ PX4IO::init()
}
/* start the IO interface task */
- _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 4096, (main_t)&PX4IO::task_main_trampoline, nullptr);
+ _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 2048, (main_t)&PX4IO::task_main_trampoline, nullptr);
if (_task < 0) {
debug("task start failed: %d", errno);
@@ -631,22 +685,30 @@ PX4IO::task_main()
ORB_ID(actuator_controls_1));
orb_set_interval(_t_actuators, 20); /* default to 50Hz */
- _t_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_armed, 200); /* 5Hz update rate */
+ _t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
+ orb_set_interval(_t_actuator_armed, 200); /* 5Hz update rate */
- _t_vstatus = orb_subscribe(ORB_ID(vehicle_status));
- orb_set_interval(_t_vstatus, 200); /* 5Hz update rate max. */
+ _t_vehicle_control_mode = orb_subscribe(ORB_ID(vehicle_control_mode));
+ orb_set_interval(_t_vehicle_control_mode, 200); /* 5Hz update rate max. */
_t_param = orb_subscribe(ORB_ID(parameter_update));
orb_set_interval(_t_param, 500); /* 2Hz update rate max. */
+ if ((_t_actuators < 0) ||
+ (_t_actuator_armed < 0) ||
+ (_t_vehicle_control_mode < 0) ||
+ (_t_param < 0)) {
+ log("subscription(s) failed");
+ goto out;
+ }
+
/* poll descriptor */
pollfd fds[4];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_armed;
+ fds[1].fd = _t_actuator_armed;
fds[1].events = POLLIN;
- fds[2].fd = _t_vstatus;
+ fds[2].fd = _t_vehicle_control_mode;
fds[2].events = POLLIN;
fds[3].fd = _t_param;
fds[3].events = POLLIN;
@@ -728,7 +790,7 @@ PX4IO::task_main()
// See if bind parameter has been set, and reset it to 0
param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val);
if (dsm_bind_val) {
- if (!(_status & PX4IO_P_STATUS_FLAGS_ARMED)) {
+ if (!(_status & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
if ((dsm_bind_val == 1) || (dsm_bind_val == 2)) {
mavlink_log_info(mavlink_fd, "[IO] binding dsm%c rx", dsm_bind_val == 1 ? '2' : 'x');
ioctl(nullptr, DSM_BIND_START, dsm_bind_val == 1 ? 3 : 7);
@@ -755,6 +817,7 @@ PX4IO::task_main()
unlock();
+out:
debug("exiting");
/* clean up the alternate device node */
@@ -795,13 +858,55 @@ PX4IO::set_failsafe_values(const uint16_t *vals, unsigned len)
}
int
+PX4IO::set_min_values(const uint16_t *vals, unsigned len)
+{
+ uint16_t regs[_max_actuators];
+
+ if (len > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ /* copy values to registers in IO */
+ return io_reg_set(PX4IO_PAGE_CONTROL_MIN_PWM, 0, vals, len);
+}
+
+int
+PX4IO::set_max_values(const uint16_t *vals, unsigned len)
+{
+ uint16_t regs[_max_actuators];
+
+ if (len > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ /* copy values to registers in IO */
+ return io_reg_set(PX4IO_PAGE_CONTROL_MAX_PWM, 0, vals, len);
+}
+
+int
+PX4IO::set_idle_values(const uint16_t *vals, unsigned len)
+{
+ uint16_t regs[_max_actuators];
+
+ if (len > _max_actuators)
+ /* fail with error */
+ return E2BIG;
+
+ printf("Sending IDLE values\n");
+
+ /* copy values to registers in IO */
+ return io_reg_set(PX4IO_PAGE_IDLE_PWM, 0, vals, len);
+}
+
+
+int
PX4IO::io_set_arming_state()
{
actuator_armed_s armed; ///< system armed state
- vehicle_status_s vstatus; ///< overall system state
+ vehicle_control_mode_s control_mode; ///< vehicle_control_mode
- orb_copy(ORB_ID(actuator_armed), _t_armed, &armed);
- orb_copy(ORB_ID(vehicle_status), _t_vstatus, &vstatus);
+ orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &armed);
+ orb_copy(ORB_ID(vehicle_control_mode), _t_vehicle_control_mode, &control_mode);
uint16_t set = 0;
uint16_t clear = 0;
@@ -811,14 +916,13 @@ PX4IO::io_set_arming_state()
} else {
clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
}
-
if (armed.ready_to_arm) {
set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
} else {
clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
}
- if (vstatus.flag_external_manual_override_ok) {
+ if (control_mode.flag_external_manual_override_ok) {
set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
} else {
clear |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
@@ -828,6 +932,21 @@ PX4IO::io_set_arming_state()
}
int
+PX4IO::disable_rc_handling()
+{
+ return io_disable_rc_handling();
+}
+
+int
+PX4IO::io_disable_rc_handling()
+{
+ uint16_t set = PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED;
+ uint16_t clear = 0;
+
+ return io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, clear, set);
+}
+
+int
PX4IO::io_set_rc_config()
{
unsigned offset = 0;
@@ -945,14 +1064,14 @@ PX4IO::io_handle_status(uint16_t status)
*/
/* check for IO reset - force it back to armed if necessary */
- if (_status & PX4IO_P_STATUS_FLAGS_ARMED && !(status & PX4IO_P_STATUS_FLAGS_ARMED)
+ if (_status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF && !(status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
&& !(status & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
/* set the arming flag */
- ret = io_reg_modify(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, 0, PX4IO_P_STATUS_FLAGS_ARMED | PX4IO_P_STATUS_FLAGS_ARM_SYNC);
+ ret = io_reg_modify(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, 0, PX4IO_P_STATUS_FLAGS_SAFETY_OFF | PX4IO_P_STATUS_FLAGS_ARM_SYNC);
/* set new status */
_status = status;
- _status &= PX4IO_P_STATUS_FLAGS_ARMED;
+ _status &= PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
} else if (!(_status & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
/* set the sync flag */
@@ -967,6 +1086,27 @@ PX4IO::io_handle_status(uint16_t status)
_status = status;
}
+ /**
+ * Get and handle the safety status
+ */
+ struct safety_s safety;
+ safety.timestamp = hrt_absolute_time();
+
+ if (status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
+ safety.safety_off = true;
+ safety.safety_switch_available = true;
+ } else {
+ safety.safety_off = false;
+ safety.safety_switch_available = true;
+ }
+
+ /* lazily publish the safety status */
+ if (_to_safety > 0) {
+ orb_publish(ORB_ID(safety), _to_safety, &safety);
+ } else {
+ _to_safety = orb_advertise(ORB_ID(safety), &safety);
+ }
+
return ret;
}
@@ -996,7 +1136,7 @@ PX4IO::io_get_status()
io_handle_status(regs[0]);
io_handle_alarms(regs[1]);
-
+
/* only publish if battery has a valid minimum voltage */
if (regs[2] > 3300) {
battery_status_s battery_status;
@@ -1030,6 +1170,7 @@ PX4IO::io_get_status()
_to_battery = orb_advertise(ORB_ID(battery_status), &battery_status);
}
}
+
return ret;
}
@@ -1037,38 +1178,38 @@ int
PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
{
uint32_t channel_count;
- int ret = OK;
+ int ret;
/* we don't have the status bits, so input_source has to be set elsewhere */
input_rc.input_source = RC_INPUT_SOURCE_UNKNOWN;
+ static const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
+ uint16_t regs[RC_INPUT_MAX_CHANNELS + prolog];
+
/*
- * XXX Because the channel count and channel data are fetched
- * separately, there is a risk of a race between the two
- * that could leave us with channel data and a count that
- * are out of sync.
- * Fixing this would require a guarantee of atomicity from
- * IO, and a single fetch for both count and channels.
+ * Read the channel count and the first 9 channels.
*
- * XXX Since IO has the input calibration info, we ought to be
- * able to get the pre-fixed-up controls directly.
- *
- * XXX can we do this more cheaply? If we knew we had DMA, it would
- * almost certainly be better to just get all the inputs...
+ * This should be the common case (9 channel R/C control being a reasonable upper bound).
*/
- channel_count = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT);
- if (channel_count == _io_reg_get_error)
- return -EIO;
- if (channel_count > RC_INPUT_MAX_CHANNELS)
- channel_count = RC_INPUT_MAX_CHANNELS;
- input_rc.channel_count = channel_count;
+ input_rc.timestamp = hrt_absolute_time();
+ ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT, &regs[0], prolog + 9);
+ if (ret != OK)
+ return ret;
- if (channel_count > 0) {
- ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE, input_rc.values, channel_count);
- if (ret == OK)
- input_rc.timestamp = hrt_absolute_time();
+ /*
+ * Get the channel count any any extra channels. This is no more expensive than reading the
+ * channel count once.
+ */
+ channel_count = regs[0];
+ if (channel_count > 9) {
+ ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + 9, &regs[prolog + 9], channel_count - 9);
+ if (ret != OK)
+ return ret;
}
+ input_rc.channel_count = channel_count;
+ memcpy(input_rc.values, &regs[prolog], channel_count * 2);
+
return ret;
}
@@ -1198,25 +1339,12 @@ PX4IO::io_reg_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned
return -EINVAL;
}
- /* set up the transfer */
- uint8_t addr[2] = {
- page,
- offset
- };
- i2c_msg_s msgv[2];
-
- msgv[0].flags = 0;
- msgv[0].buffer = addr;
- msgv[0].length = 2;
- msgv[1].flags = I2C_M_NORESTART;
- msgv[1].buffer = (uint8_t *)values;
- msgv[1].length = num_values * sizeof(*values);
-
- /* perform the transfer */
- int ret = transfer(msgv, 2);
- if (ret != OK)
- debug("io_reg_set: error %d", ret);
- return ret;
+ int ret = _interface->write((page << 8) | offset, (void *)values, num_values);
+ if (ret != num_values) {
+ debug("io_reg_set(%u,%u,%u): error %d", page, offset, num_values, ret);
+ return -1;
+ }
+ return OK;
}
int
@@ -1228,25 +1356,18 @@ PX4IO::io_reg_set(uint8_t page, uint8_t offset, uint16_t value)
int
PX4IO::io_reg_get(uint8_t page, uint8_t offset, uint16_t *values, unsigned num_values)
{
- /* set up the transfer */
- uint8_t addr[2] = {
- page,
- offset
- };
- i2c_msg_s msgv[2];
-
- msgv[0].flags = 0;
- msgv[0].buffer = addr;
- msgv[0].length = 2;
- msgv[1].flags = I2C_M_READ;
- msgv[1].buffer = (uint8_t *)values;
- msgv[1].length = num_values * sizeof(*values);
+ /* range check the transfer */
+ if (num_values > ((_max_transfer) / sizeof(*values))) {
+ debug("io_reg_get: too many registers (%u, max %u)", num_values, _max_transfer / 2);
+ return -EINVAL;
+ }
- /* perform the transfer */
- int ret = transfer(msgv, 2);
- if (ret != OK)
- debug("io_reg_get: data error %d", ret);
- return ret;
+ int ret = _interface->read((page << 8) | offset, reinterpret_cast<void *>(values), num_values);
+ if (ret != num_values) {
+ debug("io_reg_get(%u,%u,%u): data error %d", page, offset, num_values, ret);
+ return -1;
+ }
+ return OK;
}
uint32_t
@@ -1254,7 +1375,7 @@ PX4IO::io_reg_get(uint8_t page, uint8_t offset)
{
uint16_t value;
- if (io_reg_get(page, offset, &value, 1))
+ if (io_reg_get(page, offset, &value, 1) != OK)
return _io_reg_get_error;
return value;
@@ -1267,7 +1388,7 @@ PX4IO::io_reg_modify(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t
uint16_t value;
ret = io_reg_get(page, offset, &value, 1);
- if (ret)
+ if (ret != OK)
return ret;
value &= ~clearbits;
value |= setbits;
@@ -1339,9 +1460,9 @@ void
PX4IO::print_status()
{
/* basic configuration */
- printf("protocol %u software %u bootloader %u buffer %uB\n",
+ printf("protocol %u hardware %u bootloader %u buffer %uB\n",
io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_SOFTWARE_VERSION),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_HARDWARE_VERSION),
io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_BOOTLOADER_VERSION),
io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_MAX_TRANSFER));
printf("%u controls %u actuators %u R/C inputs %u analog inputs %u relays\n",
@@ -1357,7 +1478,8 @@ PX4IO::print_status()
uint16_t flags = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS);
printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s%s\n",
flags,
- ((flags & PX4IO_P_STATUS_FLAGS_ARMED) ? " ARMED" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED) ? " OUTPUTS_ARMED" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ? " SAFETY_OFF" : " SAFETY_SAFE"),
((flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ? " OVERRIDE" : ""),
((flags & PX4IO_P_STATUS_FLAGS_RC_OK) ? " RC_OK" : " RC_FAIL"),
((flags & PX4IO_P_STATUS_FLAGS_RC_PPM) ? " PPM" : ""),
@@ -1365,13 +1487,13 @@ PX4IO::print_status()
(((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) && (flags & PX4IO_P_STATUS_FLAGS_RC_DSM11)) ? " DSM11" : ""),
((flags & PX4IO_P_STATUS_FLAGS_RC_SBUS) ? " SBUS" : ""),
((flags & PX4IO_P_STATUS_FLAGS_FMU_OK) ? " FMU_OK" : " FMU_FAIL"),
- ((flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ? " RAW_PPM" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ? " RAW_PWM_PASSTHROUGH" : ""),
((flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) ? " MIXER_OK" : " MIXER_FAIL"),
((flags & PX4IO_P_STATUS_FLAGS_ARM_SYNC) ? " ARM_SYNC" : " ARM_NO_SYNC"),
((flags & PX4IO_P_STATUS_FLAGS_INIT_OK) ? " INIT_OK" : " INIT_FAIL"),
((flags & PX4IO_P_STATUS_FLAGS_FAILSAFE) ? " FAILSAFE" : ""));
uint16_t alarms = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS);
- printf("alarms 0x%04x%s%s%s%s%s%s%s\n",
+ printf("alarms 0x%04x%s%s%s%s%s%s%s%s\n",
alarms,
((alarms & PX4IO_P_STATUS_ALARMS_VBATT_LOW) ? " VBATT_LOW" : ""),
((alarms & PX4IO_P_STATUS_ALARMS_TEMPERATURE) ? " TEMPERATURE" : ""),
@@ -1379,18 +1501,26 @@ PX4IO::print_status()
((alarms & PX4IO_P_STATUS_ALARMS_ACC_CURRENT) ? " ACC_CURRENT" : ""),
((alarms & PX4IO_P_STATUS_ALARMS_FMU_LOST) ? " FMU_LOST" : ""),
((alarms & PX4IO_P_STATUS_ALARMS_RC_LOST) ? " RC_LOST" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) ? " PWM_ERROR" : ""));
+ ((alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) ? " PWM_ERROR" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_VSERVO_FAULT) ? " VSERVO_FAULT" : ""));
/* now clear alarms */
io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, 0xFFFF);
- printf("vbatt %u ibatt %u vbatt scale %u\n",
- io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VBATT),
- io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT),
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE));
- printf("amp_per_volt %.3f amp_offset %.3f mAh discharged %.3f\n",
- (double)_battery_amp_per_volt,
- (double)_battery_amp_bias,
- (double)_battery_mamphour_total);
+ if (_hardware == 1) {
+ printf("vbatt mV %u ibatt mV %u vbatt scale %u\n",
+ io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VBATT),
+ io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE));
+ printf("amp_per_volt %.3f amp_offset %.3f mAh discharged %.3f\n",
+ (double)_battery_amp_per_volt,
+ (double)_battery_amp_bias,
+ (double)_battery_mamphour_total);
+ } else if (_hardware == 2) {
+ printf("vservo %u mV vservo scale %u\n",
+ io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VSERVO),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VSERVO_SCALE));
+ printf("vrssi %u\n", io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VRSSI));
+ }
printf("actuators");
for (unsigned i = 0; i < _max_actuators; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_ACTUATORS, i));
@@ -1420,12 +1550,14 @@ PX4IO::print_status()
/* setup and state */
printf("features 0x%04x\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES));
uint16_t arming = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING);
- printf("arming 0x%04x%s%s%s%s\n",
+ printf("arming 0x%04x%s%s%s%s%s%s\n",
arming,
- ((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : " FMU_DISARMED"),
+ ((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : " IO_ARM_DENIED"),
((arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ? " MANUAL_OVERRIDE_OK" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""));
+ ((arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ? " FAILSAFE_CUSTOM" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE) ? " ALWAYS_PWM_ENABLE" : ""));
printf("rates 0x%04x default %u alt %u relays 0x%04x\n",
io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES),
io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE),
@@ -1452,7 +1584,10 @@ PX4IO::print_status()
}
printf("failsafe");
for (unsigned i = 0; i < _max_actuators; i++)
- printf(" %u", io_reg_get(PX4IO_PAGE_FAILSAFE_PWM, i));
+ printf(" %u\n", io_reg_get(PX4IO_PAGE_FAILSAFE_PWM, i));
+ printf("\nidle values");
+ for (unsigned i = 0; i < _max_actuators; i++)
+ printf(" %u", io_reg_get(PX4IO_PAGE_IDLE_PWM, i));
printf("\n");
}
@@ -1561,9 +1696,9 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
unsigned channel = cmd - PWM_SERVO_GET_RATEGROUP(0);
- uint32_t value = io_reg_get(PX4IO_PAGE_PWM_INFO, PX4IO_RATE_MAP_BASE + channel);
-
- *(uint32_t *)arg = value;
+ *(uint32_t *)arg = io_reg_get(PX4IO_PAGE_PWM_INFO, PX4IO_RATE_MAP_BASE + channel);
+ if (*(uint32_t *)arg == _io_reg_get_error)
+ ret = -EIO;
break;
}
@@ -1571,7 +1706,7 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
uint32_t bits = (1 << _max_relays) - 1;
/* don't touch relay1 if it's controlling RX vcc */
if (_dsm_vcc_ctl)
- bits &= ~PX4IO_RELAY1;
+ bits &= ~PX4IO_P_SETUP_RELAYS_POWER1;
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, bits, 0);
break;
}
@@ -1579,7 +1714,7 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
case GPIO_SET:
arg &= ((1 << _max_relays) - 1);
/* don't touch relay1 if it's controlling RX vcc */
- if (_dsm_vcc_ctl & (arg & PX4IO_RELAY1))
+ if (_dsm_vcc_ctl & (arg & PX4IO_P_SETUP_RELAYS_POWER1))
ret = -EINVAL;
else
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, 0, arg);
@@ -1588,7 +1723,7 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
case GPIO_CLEAR:
arg &= ((1 << _max_relays) - 1);
/* don't touch relay1 if it's controlling RX vcc */
- if (_dsm_vcc_ctl & (arg & PX4IO_RELAY1))
+ if (_dsm_vcc_ctl & (arg & PX4IO_P_SETUP_RELAYS_POWER1))
ret = -EINVAL;
else
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, arg, 0);
@@ -1686,8 +1821,8 @@ int
PX4IO::set_update_rate(int rate)
{
int interval_ms = 1000 / rate;
- if (interval_ms < 5) {
- interval_ms = 5;
+ if (interval_ms < 3) {
+ interval_ms = 3;
warnx("update rate too high, limiting interval to %d ms (%d Hz).", interval_ms, 1000 / interval_ms);
}
@@ -1712,14 +1847,47 @@ extern "C" __EXPORT int px4io_main(int argc, char *argv[]);
namespace
{
+device::Device *
+get_interface()
+{
+ device::Device *interface = nullptr;
+
+#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
+ /* try for a serial interface */
+ if (PX4IO_serial_interface != nullptr)
+ interface = PX4IO_serial_interface();
+ if (interface != nullptr)
+ goto got;
+#endif
+
+ /* try for an I2C interface if we haven't got a serial one */
+ if (PX4IO_i2c_interface != nullptr)
+ interface = PX4IO_i2c_interface();
+ if (interface != nullptr)
+ goto got;
+
+ errx(1, "cannot alloc interface");
+
+got:
+ if (interface->init() != OK) {
+ delete interface;
+ errx(1, "interface init failed");
+ }
+
+ return interface;
+}
+
void
start(int argc, char *argv[])
{
if (g_dev != nullptr)
errx(1, "already loaded");
+ /* allocate the interface */
+ device::Device *interface = get_interface();
+
/* create the driver - it will set g_dev */
- (void)new PX4IO();
+ (void)new PX4IO(interface);
if (g_dev == nullptr)
errx(1, "driver alloc failed");
@@ -1729,6 +1897,18 @@ start(int argc, char *argv[])
errx(1, "driver init failed");
}
+ /* disable RC handling on request */
+ if (argc > 1) {
+ if (!strcmp(argv[1], "norc")) {
+
+ if(g_dev->disable_rc_handling())
+ warnx("Failed disabling RC handling");
+
+ } else {
+ warnx("unknown argument: %s", argv[1]);
+ }
+ }
+
int dsm_vcc_ctl;
if (param_get(param_find("RC_RL1_DSM_VCC"), &dsm_vcc_ctl) == OK) {
@@ -1786,6 +1966,11 @@ test(void)
if (ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count))
err(1, "failed to get servo count");
+ /* tell IO that its ok to disable its safety with the switch */
+ ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET_ARM_OK");
+
if (ioctl(fd, PWM_SERVO_ARM, 0))
err(1, "failed to arm servos");
@@ -1834,7 +2019,7 @@ test(void)
/* Check if user wants to quit */
char c;
if (read(console, &c, 1) == 1) {
- if (c == 0x03 || c == 0x63) {
+ if (c == 0x03 || c == 0x63 || c == 'q') {
warnx("User abort\n");
close(console);
exit(0);
@@ -1871,8 +2056,19 @@ monitor(void)
}
}
+void
+if_test(unsigned mode)
+{
+ device::Device *interface = get_interface();
+
+ int result = interface->ioctl(1, mode); /* XXX magic numbers */
+ delete interface;
+
+ errx(0, "test returned %d", result);
}
+} /* namespace */
+
int
px4io_main(int argc, char *argv[])
{
@@ -1883,28 +2079,87 @@ px4io_main(int argc, char *argv[])
if (!strcmp(argv[1], "start"))
start(argc - 1, argv + 1);
- if (!strcmp(argv[1], "limit")) {
+ if (!strcmp(argv[1], "update")) {
if (g_dev != nullptr) {
+ printf("[px4io] loaded, detaching first\n");
+ /* stop the driver */
+ delete g_dev;
+ }
- if ((argc > 2)) {
- g_dev->set_update_rate(atoi(argv[2]));
- } else {
- errx(1, "missing argument (50 - 200 Hz)");
- return 1;
- }
+ PX4IO_Uploader *up;
+ const char *fn[5];
+
+ /* work out what we're uploading... */
+ if (argc > 2) {
+ fn[0] = argv[2];
+ fn[1] = nullptr;
+
+ } else {
+ fn[0] = "/fs/microsd/px4io.bin";
+ fn[1] = "/etc/px4io.bin";
+ fn[2] = "/fs/microsd/px4io2.bin";
+ fn[3] = "/etc/px4io2.bin";
+ fn[4] = nullptr;
+ }
+
+ up = new PX4IO_Uploader;
+ int ret = up->upload(&fn[0]);
+ delete up;
+
+ switch (ret) {
+ case OK:
+ break;
+
+ case -ENOENT:
+ errx(1, "PX4IO firmware file not found");
+
+ case -EEXIST:
+ case -EIO:
+ errx(1, "error updating PX4IO - check that bootloader mode is enabled");
+
+ case -EINVAL:
+ errx(1, "verify failed - retry the update");
+
+ case -ETIMEDOUT:
+ errx(1, "timed out waiting for bootloader - power-cycle and try again");
+
+ default:
+ errx(1, "unexpected error %d", ret);
+ }
+
+ return ret;
+ }
+
+ if (!strcmp(argv[1], "iftest")) {
+ if (g_dev != nullptr)
+ errx(1, "can't iftest when started");
+
+ if_test((argc > 2) ? strtol(argv[2], NULL, 0) : 0);
+ }
+
+ /* commands below here require a started driver */
+
+ if (g_dev == nullptr)
+ errx(1, "not started");
+
+ if (!strcmp(argv[1], "limit")) {
+
+ if ((argc > 2)) {
+ g_dev->set_update_rate(atoi(argv[2]));
+ } else {
+ errx(1, "missing argument (50 - 400 Hz)");
+ return 1;
}
exit(0);
}
if (!strcmp(argv[1], "current")) {
- if (g_dev != nullptr) {
- if ((argc > 3)) {
- g_dev->set_battery_current_scaling(atof(argv[2]), atof(argv[3]));
- } else {
- errx(1, "missing argument (apm_per_volt, amp_offset)");
- return 1;
- }
+ if ((argc > 3)) {
+ g_dev->set_battery_current_scaling(atof(argv[2]), atof(argv[3]));
+ } else {
+ errx(1, "missing argument (apm_per_volt, amp_offset)");
+ return 1;
}
exit(0);
}
@@ -1915,70 +2170,158 @@ px4io_main(int argc, char *argv[])
errx(1, "failsafe command needs at least one channel value (ppm)");
}
+ /* set values for first 8 channels, fill unassigned channels with 1500. */
+ uint16_t failsafe[8];
+
+ for (int i = 0; i < sizeof(failsafe) / sizeof(failsafe[0]); i++) {
+
+ /* set channel to commandline argument or to 900 for non-provided channels */
+ if (argc > i + 2) {
+ failsafe[i] = atoi(argv[i+2]);
+ if (failsafe[i] < 800 || failsafe[i] > 2200) {
+ errx(1, "value out of range of 800 < value < 2200. Aborting.");
+ }
+ } else {
+ /* a zero value will result in stopping to output any pulse */
+ failsafe[i] = 0;
+ }
+ }
+
+ int ret = g_dev->set_failsafe_values(failsafe, sizeof(failsafe) / sizeof(failsafe[0]));
+
+ if (ret != OK)
+ errx(ret, "failed setting failsafe values");
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "min")) {
+
+ if (argc < 3) {
+ errx(1, "min command needs at least one channel value (PWM)");
+ }
+
if (g_dev != nullptr) {
- /* set values for first 8 channels, fill unassigned channels with 1500. */
- uint16_t failsafe[8];
+ /* set values for first 8 channels, fill unassigned channels with 900. */
+ uint16_t min[8];
- for (int i = 0; i < sizeof(failsafe) / sizeof(failsafe[0]); i++)
+ for (int i = 0; i < sizeof(min) / sizeof(min[0]); i++)
{
/* set channel to commanline argument or to 900 for non-provided channels */
if (argc > i + 2) {
- failsafe[i] = atoi(argv[i+2]);
- if (failsafe[i] < 800 || failsafe[i] > 2200) {
- errx(1, "value out of range of 800 < value < 2200. Aborting.");
+ min[i] = atoi(argv[i+2]);
+ if (min[i] < 900 || min[i] > 1200) {
+ errx(1, "value out of range of 900 < value < 1200. Aborting.");
}
} else {
- /* a zero value will result in stopping to output any pulse */
- failsafe[i] = 0;
+ /* a zero value will the default */
+ min[i] = 0;
}
}
- int ret = g_dev->set_failsafe_values(failsafe, sizeof(failsafe) / sizeof(failsafe[0]));
+ int ret = g_dev->set_min_values(min, sizeof(min) / sizeof(min[0]));
if (ret != OK)
- errx(ret, "failed setting failsafe values");
+ errx(ret, "failed setting min values");
} else {
errx(1, "not loaded");
}
exit(0);
}
- if (!strcmp(argv[1], "recovery")) {
+ if (!strcmp(argv[1], "max")) {
+
+ if (argc < 3) {
+ errx(1, "max command needs at least one channel value (PWM)");
+ }
if (g_dev != nullptr) {
- /*
- * Enable in-air restart support.
- * We can cheat and call the driver directly, as it
- * doesn't reference filp in ioctl()
- */
- g_dev->ioctl(nullptr, PX4IO_INAIR_RESTART_ENABLE, 1);
+
+ /* set values for first 8 channels, fill unassigned channels with 2100. */
+ uint16_t max[8];
+
+ for (int i = 0; i < sizeof(max) / sizeof(max[0]); i++)
+ {
+ /* set channel to commanline argument or to 2100 for non-provided channels */
+ if (argc > i + 2) {
+ max[i] = atoi(argv[i+2]);
+ if (max[i] < 1800 || max[i] > 2100) {
+ errx(1, "value out of range of 1800 < value < 2100. Aborting.");
+ }
+ } else {
+ /* a zero value will the default */
+ max[i] = 0;
+ }
+ }
+
+ int ret = g_dev->set_max_values(max, sizeof(max) / sizeof(max[0]));
+
+ if (ret != OK)
+ errx(ret, "failed setting max values");
} else {
errx(1, "not loaded");
}
exit(0);
}
- if (!strcmp(argv[1], "stop")) {
+ if (!strcmp(argv[1], "idle")) {
+
+ if (argc < 3) {
+ errx(1, "max command needs at least one channel value (PWM)");
+ }
if (g_dev != nullptr) {
- /* stop the driver */
- delete g_dev;
+
+ /* set values for first 8 channels, fill unassigned channels with 0. */
+ uint16_t idle[8];
+
+ for (int i = 0; i < sizeof(idle) / sizeof(idle[0]); i++)
+ {
+ /* set channel to commanline argument or to 0 for non-provided channels */
+ if (argc > i + 2) {
+ idle[i] = atoi(argv[i+2]);
+ if (idle[i] < 900 || idle[i] > 2100) {
+ errx(1, "value out of range of 900 < value < 2100. Aborting.");
+ }
+ } else {
+ /* a zero value will the default */
+ idle[i] = 0;
+ }
+ }
+
+ int ret = g_dev->set_idle_values(idle, sizeof(idle) / sizeof(idle[0]));
+
+ if (ret != OK)
+ errx(ret, "failed setting idle values");
} else {
errx(1, "not loaded");
}
exit(0);
}
+ if (!strcmp(argv[1], "recovery")) {
+
+ /*
+ * Enable in-air restart support.
+ * We can cheat and call the driver directly, as it
+ * doesn't reference filp in ioctl()
+ */
+ g_dev->ioctl(NULL, PX4IO_INAIR_RESTART_ENABLE, 1);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+
+ /* stop the driver */
+ delete g_dev;
+ exit(0);
+ }
+
if (!strcmp(argv[1], "status")) {
- if (g_dev != nullptr) {
- printf("[px4io] loaded\n");
- g_dev->print_status();
- } else {
- printf("[px4io] not loaded\n");
- }
+ printf("[px4io] loaded\n");
+ g_dev->print_status();
exit(0);
}
@@ -2005,58 +2348,6 @@ px4io_main(int argc, char *argv[])
exit(0);
}
- /* note, stop not currently implemented */
-
- if (!strcmp(argv[1], "update")) {
-
- if (g_dev != nullptr) {
- printf("[px4io] loaded, detaching first\n");
- /* stop the driver */
- delete g_dev;
- }
-
- PX4IO_Uploader *up;
- const char *fn[3];
-
- /* work out what we're uploading... */
- if (argc > 2) {
- fn[0] = argv[2];
- fn[1] = nullptr;
-
- } else {
- fn[0] = "/fs/microsd/px4io.bin";
- fn[1] = "/etc/px4io.bin";
- fn[2] = nullptr;
- }
-
- up = new PX4IO_Uploader;
- int ret = up->upload(&fn[0]);
- delete up;
-
- switch (ret) {
- case OK:
- break;
-
- case -ENOENT:
- errx(1, "PX4IO firmware file not found");
-
- case -EEXIST:
- case -EIO:
- errx(1, "error updating PX4IO - check that bootloader mode is enabled");
-
- case -EINVAL:
- errx(1, "verify failed - retry the update");
-
- case -ETIMEDOUT:
- errx(1, "timed out waiting for bootloader - power-cycle and try again");
-
- default:
- errx(1, "unexpected error %d", ret);
- }
-
- return ret;
- }
-
if (!strcmp(argv[1], "rx_dsm") ||
!strcmp(argv[1], "rx_dsm_10bit") ||
!strcmp(argv[1], "rx_dsm_11bit") ||
@@ -2074,5 +2365,5 @@ px4io_main(int argc, char *argv[])
bind(argc, argv);
out:
- errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current', 'failsafe', 'bind', or 'update'");
+ errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug',\n 'recovery', 'limit', 'current', 'failsafe', 'min, 'max',\n 'idle', 'bind' or 'update'");
}
diff --git a/src/drivers/px4io/px4io_i2c.cpp b/src/drivers/px4io/px4io_i2c.cpp
new file mode 100644
index 000000000..19776c40a
--- /dev/null
+++ b/src/drivers/px4io/px4io_i2c.cpp
@@ -0,0 +1,169 @@
+/****************************************************************************
+ *
+ * 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 px4io_i2c.cpp
+ *
+ * I2C interface for PX4IO
+ */
+
+/* XXX trim includes */
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+#include <debug.h>
+#include <errno.h>
+#include <unistd.h>
+
+#include <arch/board/board.h>
+#include <board_config.h>
+
+#include <drivers/device/i2c.h>
+
+#ifdef PX4_I2C_OBDEV_PX4IO
+
+device::Device *PX4IO_i2c_interface();
+
+class PX4IO_I2C : public device::I2C
+{
+public:
+ PX4IO_I2C(int bus, uint8_t address);
+ virtual ~PX4IO_I2C();
+
+ virtual int init();
+ virtual int read(unsigned offset, void *data, unsigned count = 1);
+ virtual int write(unsigned address, void *data, unsigned count = 1);
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
+private:
+
+};
+
+device::Device
+*PX4IO_i2c_interface()
+{
+ return new PX4IO_I2C(PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_PX4IO);
+}
+
+PX4IO_I2C::PX4IO_I2C(int bus, uint8_t address) :
+ I2C("PX4IO_i2c", nullptr, bus, address, 320000)
+{
+ _retries = 3;
+}
+
+PX4IO_I2C::~PX4IO_I2C()
+{
+}
+
+int
+PX4IO_I2C::init()
+{
+ int ret;
+
+ ret = I2C::init();
+ if (ret != OK)
+ goto out;
+
+ /* XXX really should do something more here */
+
+out:
+ return 0;
+}
+
+int
+PX4IO_I2C::ioctl(unsigned operation, unsigned &arg)
+{
+ return 0;
+}
+
+int
+PX4IO_I2C::write(unsigned address, void *data, unsigned count)
+{
+ uint8_t page = address >> 8;
+ uint8_t offset = address & 0xff;
+ const uint16_t *values = reinterpret_cast<const uint16_t *>(data);
+
+ /* set up the transfer */
+ uint8_t addr[2] = {
+ page,
+ offset
+ };
+
+ i2c_msg_s msgv[2];
+
+ msgv[0].flags = 0;
+ msgv[0].buffer = addr;
+ msgv[0].length = 2;
+
+ msgv[1].flags = I2C_M_NORESTART;
+ msgv[1].buffer = (uint8_t *)values;
+ msgv[1].length = 2 * count;
+
+ int ret = transfer(msgv, 2);
+ if (ret == OK)
+ ret = count;
+ return ret;
+}
+
+int
+PX4IO_I2C::read(unsigned address, void *data, unsigned count)
+{
+ uint8_t page = address >> 8;
+ uint8_t offset = address & 0xff;
+ const uint16_t *values = reinterpret_cast<const uint16_t *>(data);
+
+ /* set up the transfer */
+ uint8_t addr[2] = {
+ page,
+ offset
+ };
+ i2c_msg_s msgv[2];
+
+ msgv[0].flags = 0;
+ msgv[0].buffer = addr;
+ msgv[0].length = 2;
+
+ msgv[1].flags = I2C_M_READ;
+ msgv[1].buffer = (uint8_t *)values;
+ msgv[1].length = 2 * count;
+
+ int ret = transfer(msgv, 2);
+ if (ret == OK)
+ ret = count;
+ return ret;
+}
+
+#endif /* PX4_I2C_OBDEV_PX4IO */
diff --git a/src/drivers/px4io/px4io_serial.cpp b/src/drivers/px4io/px4io_serial.cpp
new file mode 100644
index 000000000..236cb918d
--- /dev/null
+++ b/src/drivers/px4io/px4io_serial.cpp
@@ -0,0 +1,673 @@
+/****************************************************************************
+ *
+ * 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 px4io_serial.cpp
+ *
+ * Serial interface for PX4IO
+ */
+
+/* XXX trim includes */
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+#include <debug.h>
+#include <time.h>
+#include <errno.h>
+#include <string.h>
+
+#include <arch/board/board.h>
+
+/* XXX might be able to prune these */
+#include <nuttx/arch.h>
+#include <chip.h>
+#include <up_internal.h>
+#include <up_arch.h>
+
+#include <debug.h>
+
+#include <drivers/device/device.h>
+#include <drivers/drv_hrt.h>
+#include <board_config.h>
+
+#include <systemlib/perf_counter.h>
+
+#include <modules/px4iofirmware/protocol.h>
+
+#ifdef PX4IO_SERIAL_BASE
+
+device::Device *PX4IO_serial_interface();
+
+/* serial register accessors */
+#define REG(_x) (*(volatile uint32_t *)(PX4IO_SERIAL_BASE + _x))
+#define rSR REG(STM32_USART_SR_OFFSET)
+#define rDR REG(STM32_USART_DR_OFFSET)
+#define rBRR REG(STM32_USART_BRR_OFFSET)
+#define rCR1 REG(STM32_USART_CR1_OFFSET)
+#define rCR2 REG(STM32_USART_CR2_OFFSET)
+#define rCR3 REG(STM32_USART_CR3_OFFSET)
+#define rGTPR REG(STM32_USART_GTPR_OFFSET)
+
+class PX4IO_serial : public device::Device
+{
+public:
+ PX4IO_serial();
+ virtual ~PX4IO_serial();
+
+ virtual int init();
+ virtual int read(unsigned offset, void *data, unsigned count = 1);
+ virtual int write(unsigned address, void *data, unsigned count = 1);
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
+private:
+ /*
+ * XXX tune this value
+ *
+ * At 1.5Mbps each register takes 13.3µs, and we always transfer a full packet.
+ * Packet overhead is 26µs for the four-byte header.
+ *
+ * 32 registers = 451µs
+ *
+ * Maybe we can just send smaller packets (e.g. 8 regs) and loop for larger (less common)
+ * transfers? Could cause issues with any regs expecting to be written atomically...
+ */
+ static IOPacket _dma_buffer; // XXX static to ensure DMA-able memory
+
+ DMA_HANDLE _tx_dma;
+ DMA_HANDLE _rx_dma;
+
+ /** saved DMA status */
+ static const unsigned _dma_status_inactive = 0x80000000; // low bits overlap DMA_STATUS_* values
+ static const unsigned _dma_status_waiting = 0x00000000;
+ volatile unsigned _rx_dma_status;
+
+ /** bus-ownership lock */
+ sem_t _bus_semaphore;
+
+ /** client-waiting lock/signal */
+ sem_t _completion_semaphore;
+
+ /**
+ * Start the transaction with IO and wait for it to complete.
+ */
+ int _wait_complete();
+
+ /**
+ * DMA completion handler.
+ */
+ static void _dma_callback(DMA_HANDLE handle, uint8_t status, void *arg);
+ void _do_rx_dma_callback(unsigned status);
+
+ /**
+ * Serial interrupt handler.
+ */
+ static int _interrupt(int vector, void *context);
+ void _do_interrupt();
+
+ /**
+ * Cancel any DMA in progress with an error.
+ */
+ void _abort_dma();
+
+ /**
+ * Performance counters.
+ */
+ perf_counter_t _pc_txns;
+ perf_counter_t _pc_dmasetup;
+ perf_counter_t _pc_retries;
+ perf_counter_t _pc_timeouts;
+ perf_counter_t _pc_crcerrs;
+ perf_counter_t _pc_dmaerrs;
+ perf_counter_t _pc_protoerrs;
+ perf_counter_t _pc_uerrs;
+ perf_counter_t _pc_idle;
+ perf_counter_t _pc_badidle;
+
+};
+
+IOPacket PX4IO_serial::_dma_buffer;
+static PX4IO_serial *g_interface;
+
+device::Device
+*PX4IO_serial_interface()
+{
+ return new PX4IO_serial();
+}
+
+PX4IO_serial::PX4IO_serial() :
+ Device("PX4IO_serial"),
+ _tx_dma(nullptr),
+ _rx_dma(nullptr),
+ _rx_dma_status(_dma_status_inactive),
+ _pc_txns(perf_alloc(PC_ELAPSED, "io_txns ")),
+ _pc_dmasetup(perf_alloc(PC_ELAPSED, "io_dmasetup ")),
+ _pc_retries(perf_alloc(PC_COUNT, "io_retries ")),
+ _pc_timeouts(perf_alloc(PC_COUNT, "io_timeouts ")),
+ _pc_crcerrs(perf_alloc(PC_COUNT, "io_crcerrs ")),
+ _pc_dmaerrs(perf_alloc(PC_COUNT, "io_dmaerrs ")),
+ _pc_protoerrs(perf_alloc(PC_COUNT, "io_protoerrs")),
+ _pc_uerrs(perf_alloc(PC_COUNT, "io_uarterrs ")),
+ _pc_idle(perf_alloc(PC_COUNT, "io_idle ")),
+ _pc_badidle(perf_alloc(PC_COUNT, "io_badidle "))
+{
+ g_interface = this;
+}
+
+PX4IO_serial::~PX4IO_serial()
+{
+ if (_tx_dma != nullptr) {
+ stm32_dmastop(_tx_dma);
+ stm32_dmafree(_tx_dma);
+ }
+ if (_rx_dma != nullptr) {
+ stm32_dmastop(_rx_dma);
+ stm32_dmafree(_rx_dma);
+ }
+
+ /* reset the UART */
+ rCR1 = 0;
+ rCR2 = 0;
+ rCR3 = 0;
+
+ /* detach our interrupt handler */
+ up_disable_irq(PX4IO_SERIAL_VECTOR);
+ irq_detach(PX4IO_SERIAL_VECTOR);
+
+ /* restore the GPIOs */
+ stm32_unconfiggpio(PX4IO_SERIAL_TX_GPIO);
+ stm32_unconfiggpio(PX4IO_SERIAL_RX_GPIO);
+
+ /* and kill our semaphores */
+ sem_destroy(&_completion_semaphore);
+ sem_destroy(&_bus_semaphore);
+
+ perf_free(_pc_txns);
+ perf_free(_pc_dmasetup);
+ perf_free(_pc_retries);
+ perf_free(_pc_timeouts);
+ perf_free(_pc_crcerrs);
+ perf_free(_pc_dmaerrs);
+ perf_free(_pc_protoerrs);
+ perf_free(_pc_uerrs);
+ perf_free(_pc_idle);
+ perf_free(_pc_badidle);
+
+ if (g_interface == this)
+ g_interface = nullptr;
+}
+
+int
+PX4IO_serial::init()
+{
+ /* allocate DMA */
+ _tx_dma = stm32_dmachannel(PX4IO_SERIAL_TX_DMAMAP);
+ _rx_dma = stm32_dmachannel(PX4IO_SERIAL_RX_DMAMAP);
+ if ((_tx_dma == nullptr) || (_rx_dma == nullptr))
+ return -1;
+
+ /* configure pins for serial use */
+ stm32_configgpio(PX4IO_SERIAL_TX_GPIO);
+ stm32_configgpio(PX4IO_SERIAL_RX_GPIO);
+
+ /* reset & configure the UART */
+ rCR1 = 0;
+ rCR2 = 0;
+ rCR3 = 0;
+
+ /* eat any existing interrupt status */
+ (void)rSR;
+ (void)rDR;
+
+ /* configure line speed */
+ uint32_t usartdiv32 = PX4IO_SERIAL_CLOCK / (PX4IO_SERIAL_BITRATE / 2);
+ uint32_t mantissa = usartdiv32 >> 5;
+ uint32_t fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
+ rBRR = (mantissa << USART_BRR_MANT_SHIFT) | (fraction << USART_BRR_FRAC_SHIFT);
+
+ /* attach serial interrupt handler */
+ irq_attach(PX4IO_SERIAL_VECTOR, _interrupt);
+ up_enable_irq(PX4IO_SERIAL_VECTOR);
+
+ /* enable UART in DMA mode, enable error and line idle interrupts */
+ /* rCR3 = USART_CR3_EIE;*/
+ rCR1 = USART_CR1_RE | USART_CR1_TE | USART_CR1_UE | USART_CR1_IDLEIE;
+
+ /* create semaphores */
+ sem_init(&_completion_semaphore, 0, 0);
+ sem_init(&_bus_semaphore, 0, 1);
+
+
+ /* XXX this could try talking to IO */
+
+ return 0;
+}
+
+int
+PX4IO_serial::ioctl(unsigned operation, unsigned &arg)
+{
+
+ switch (operation) {
+
+ case 1: /* XXX magic number - test operation */
+ switch (arg) {
+ case 0:
+ lowsyslog("test 0\n");
+
+ /* kill DMA, this is a PIO test */
+ stm32_dmastop(_tx_dma);
+ stm32_dmastop(_rx_dma);
+ rCR3 &= ~(USART_CR3_DMAR | USART_CR3_DMAT);
+
+ for (;;) {
+ while (!(rSR & USART_SR_TXE))
+ ;
+ rDR = 0x55;
+ }
+ return 0;
+
+ case 1:
+ {
+ unsigned fails = 0;
+ for (unsigned count = 0;; count++) {
+ uint16_t value = count & 0xffff;
+
+ if (write((PX4IO_PAGE_TEST << 8) | PX4IO_P_TEST_LED, &value, 1) != 0)
+ fails++;
+
+ if (count >= 5000) {
+ lowsyslog("==== test 1 : %u failures ====\n", fails);
+ perf_print_counter(_pc_txns);
+ perf_print_counter(_pc_dmasetup);
+ perf_print_counter(_pc_retries);
+ perf_print_counter(_pc_timeouts);
+ perf_print_counter(_pc_crcerrs);
+ perf_print_counter(_pc_dmaerrs);
+ perf_print_counter(_pc_protoerrs);
+ perf_print_counter(_pc_uerrs);
+ perf_print_counter(_pc_idle);
+ perf_print_counter(_pc_badidle);
+ count = 0;
+ }
+ }
+ return 0;
+ }
+ case 2:
+ lowsyslog("test 2\n");
+ return 0;
+ }
+ default:
+ break;
+ }
+
+ return -1;
+}
+
+int
+PX4IO_serial::write(unsigned address, void *data, unsigned count)
+{
+ uint8_t page = address >> 8;
+ uint8_t offset = address & 0xff;
+ const uint16_t *values = reinterpret_cast<const uint16_t *>(data);
+
+ if (count > PKT_MAX_REGS)
+ return -EINVAL;
+
+ sem_wait(&_bus_semaphore);
+
+ int result;
+ for (unsigned retries = 0; retries < 3; retries++) {
+
+ _dma_buffer.count_code = count | PKT_CODE_WRITE;
+ _dma_buffer.page = page;
+ _dma_buffer.offset = offset;
+ memcpy((void *)&_dma_buffer.regs[0], (void *)values, (2 * count));
+ for (unsigned i = count; i < PKT_MAX_REGS; i++)
+ _dma_buffer.regs[i] = 0x55aa;
+
+ /* XXX implement check byte */
+
+ /* start the transaction and wait for it to complete */
+ result = _wait_complete();
+
+ /* successful transaction? */
+ if (result == OK) {
+
+ /* check result in packet */
+ if (PKT_CODE(_dma_buffer) == PKT_CODE_ERROR) {
+
+ /* IO didn't like it - no point retrying */
+ result = -EINVAL;
+ perf_count(_pc_protoerrs);
+ }
+
+ break;
+ }
+ perf_count(_pc_retries);
+ }
+
+ sem_post(&_bus_semaphore);
+
+ if (result == OK)
+ result = count;
+ return result;
+}
+
+int
+PX4IO_serial::read(unsigned address, void *data, unsigned count)
+{
+ uint8_t page = address >> 8;
+ uint8_t offset = address & 0xff;
+ uint16_t *values = reinterpret_cast<uint16_t *>(data);
+
+ if (count > PKT_MAX_REGS)
+ return -EINVAL;
+
+ sem_wait(&_bus_semaphore);
+
+ int result;
+ for (unsigned retries = 0; retries < 3; retries++) {
+
+ _dma_buffer.count_code = count | PKT_CODE_READ;
+ _dma_buffer.page = page;
+ _dma_buffer.offset = offset;
+
+ /* start the transaction and wait for it to complete */
+ result = _wait_complete();
+
+ /* successful transaction? */
+ if (result == OK) {
+
+ /* check result in packet */
+ if (PKT_CODE(_dma_buffer) == PKT_CODE_ERROR) {
+
+ /* IO didn't like it - no point retrying */
+ result = -EINVAL;
+ perf_count(_pc_protoerrs);
+
+ /* compare the received count with the expected count */
+ } else if (PKT_COUNT(_dma_buffer) != count) {
+
+ /* IO returned the wrong number of registers - no point retrying */
+ result = -EIO;
+ perf_count(_pc_protoerrs);
+
+ /* successful read */
+ } else {
+
+ /* copy back the result */
+ memcpy(values, &_dma_buffer.regs[0], (2 * count));
+ }
+
+ break;
+ }
+ perf_count(_pc_retries);
+ }
+
+ sem_post(&_bus_semaphore);
+
+ if (result == OK)
+ result = count;
+ return result;
+}
+
+int
+PX4IO_serial::_wait_complete()
+{
+ /* clear any lingering error status */
+ (void)rSR;
+ (void)rDR;
+
+ /* start RX DMA */
+ perf_begin(_pc_txns);
+ perf_begin(_pc_dmasetup);
+
+ /* DMA setup time ~3µs */
+ _rx_dma_status = _dma_status_waiting;
+
+ /*
+ * Note that we enable circular buffer mode as a workaround for
+ * there being no API to disable the DMA FIFO. We need direct mode
+ * because otherwise when the line idle interrupt fires there
+ * will be packet bytes still in the DMA FIFO, and we will assume
+ * that the idle was spurious.
+ *
+ * XXX this should be fixed with a NuttX change.
+ */
+ stm32_dmasetup(
+ _rx_dma,
+ PX4IO_SERIAL_BASE + STM32_USART_DR_OFFSET,
+ reinterpret_cast<uint32_t>(&_dma_buffer),
+ sizeof(_dma_buffer),
+ DMA_SCR_CIRC | /* XXX see note above */
+ DMA_SCR_DIR_P2M |
+ DMA_SCR_MINC |
+ DMA_SCR_PSIZE_8BITS |
+ DMA_SCR_MSIZE_8BITS |
+ DMA_SCR_PBURST_SINGLE |
+ DMA_SCR_MBURST_SINGLE);
+ stm32_dmastart(_rx_dma, _dma_callback, this, false);
+ rCR3 |= USART_CR3_DMAR;
+
+ /* start TX DMA - no callback if we also expect a reply */
+ /* DMA setup time ~3µs */
+ _dma_buffer.crc = 0;
+ _dma_buffer.crc = crc_packet(&_dma_buffer);
+ stm32_dmasetup(
+ _tx_dma,
+ PX4IO_SERIAL_BASE + STM32_USART_DR_OFFSET,
+ reinterpret_cast<uint32_t>(&_dma_buffer),
+ PKT_SIZE(_dma_buffer),
+ DMA_SCR_DIR_M2P |
+ DMA_SCR_MINC |
+ DMA_SCR_PSIZE_8BITS |
+ DMA_SCR_MSIZE_8BITS |
+ DMA_SCR_PBURST_SINGLE |
+ DMA_SCR_MBURST_SINGLE);
+ stm32_dmastart(_tx_dma, nullptr, nullptr, false);
+ rCR3 |= USART_CR3_DMAT;
+
+ perf_end(_pc_dmasetup);
+
+ /* compute the deadline for a 5ms timeout */
+ struct timespec abstime;
+ clock_gettime(CLOCK_REALTIME, &abstime);
+#if 0
+ abstime.tv_sec++; /* long timeout for testing */
+#else
+ abstime.tv_nsec += 10000000; /* 0ms timeout */
+ if (abstime.tv_nsec > 1000000000) {
+ abstime.tv_sec++;
+ abstime.tv_nsec -= 1000000000;
+ }
+#endif
+
+ /* wait for the transaction to complete - 64 bytes @ 1.5Mbps ~426µs */
+ int ret;
+ for (;;) {
+ ret = sem_timedwait(&_completion_semaphore, &abstime);
+
+ if (ret == OK) {
+ /* check for DMA errors */
+ if (_rx_dma_status & DMA_STATUS_TEIF) {
+ perf_count(_pc_dmaerrs);
+ ret = -EIO;
+ break;
+ }
+
+ /* check packet CRC - corrupt packet errors mean IO receive CRC error */
+ uint8_t crc = _dma_buffer.crc;
+ _dma_buffer.crc = 0;
+ if ((crc != crc_packet(&_dma_buffer)) | (PKT_CODE(_dma_buffer) == PKT_CODE_CORRUPT)) {
+ perf_count(_pc_crcerrs);
+ ret = -EIO;
+ break;
+ }
+
+ /* successful txn (may still be reporting an error) */
+ break;
+ }
+
+ if (errno == ETIMEDOUT) {
+ /* something has broken - clear out any partial DMA state and reconfigure */
+ _abort_dma();
+ perf_count(_pc_timeouts);
+ perf_cancel(_pc_txns); /* don't count this as a transaction */
+ break;
+ }
+
+ /* we might? see this for EINTR */
+ lowsyslog("unexpected ret %d/%d\n", ret, errno);
+ }
+
+ /* reset DMA status */
+ _rx_dma_status = _dma_status_inactive;
+
+ /* update counters */
+ perf_end(_pc_txns);
+
+ return ret;
+}
+
+void
+PX4IO_serial::_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg)
+{
+ if (arg != nullptr) {
+ PX4IO_serial *ps = reinterpret_cast<PX4IO_serial *>(arg);
+
+ ps->_do_rx_dma_callback(status);
+ }
+}
+
+void
+PX4IO_serial::_do_rx_dma_callback(unsigned status)
+{
+ /* on completion of a reply, wake the waiter */
+ if (_rx_dma_status == _dma_status_waiting) {
+
+ /* check for packet overrun - this will occur after DMA completes */
+ uint32_t sr = rSR;
+ if (sr & (USART_SR_ORE | USART_SR_RXNE)) {
+ (void)rDR;
+ status = DMA_STATUS_TEIF;
+ }
+
+ /* save RX status */
+ _rx_dma_status = status;
+
+ /* disable UART DMA */
+ rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
+
+ /* complete now */
+ sem_post(&_completion_semaphore);
+ }
+}
+
+int
+PX4IO_serial::_interrupt(int irq, void *context)
+{
+ if (g_interface != nullptr)
+ g_interface->_do_interrupt();
+ return 0;
+}
+
+void
+PX4IO_serial::_do_interrupt()
+{
+ uint32_t sr = rSR; /* get UART status register */
+ (void)rDR; /* read DR to clear status */
+
+ if (sr & (USART_SR_ORE | /* overrun error - packet was too big for DMA or DMA was too slow */
+ USART_SR_NE | /* noise error - we have lost a byte due to noise */
+ USART_SR_FE)) { /* framing error - start/stop bit lost or line break */
+
+ /*
+ * If we are in the process of listening for something, these are all fatal;
+ * abort the DMA with an error.
+ */
+ if (_rx_dma_status == _dma_status_waiting) {
+ _abort_dma();
+ perf_count(_pc_uerrs);
+
+ /* complete DMA as though in error */
+ _do_rx_dma_callback(DMA_STATUS_TEIF);
+
+ return;
+ }
+
+ /* XXX we might want to use FE / line break as an out-of-band handshake ... handle it here */
+
+ /* don't attempt to handle IDLE if it's set - things went bad */
+ return;
+ }
+
+ if (sr & USART_SR_IDLE) {
+
+ /* if there is DMA reception going on, this is a short packet */
+ if (_rx_dma_status == _dma_status_waiting) {
+
+ /* verify that the received packet is complete */
+ unsigned length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
+ if ((length < 1) || (length < PKT_SIZE(_dma_buffer))) {
+ perf_count(_pc_badidle);
+ return;
+ }
+
+ perf_count(_pc_idle);
+
+ /* stop the receive DMA */
+ stm32_dmastop(_rx_dma);
+
+ /* complete the short reception */
+ _do_rx_dma_callback(DMA_STATUS_TCIF);
+ }
+ }
+}
+
+void
+PX4IO_serial::_abort_dma()
+{
+ /* disable UART DMA */
+ rCR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR);
+ (void)rSR;
+ (void)rDR;
+ (void)rDR;
+
+ /* stop DMA */
+ stm32_dmastop(_tx_dma);
+ stm32_dmastop(_rx_dma);
+}
+
+#endif /* PX4IO_SERIAL_BASE */ \ No newline at end of file
diff --git a/src/drivers/px4io/uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp
index 9e3f041e3..c7ce60b5e 100644
--- a/src/drivers/px4io/uploader.cpp
+++ b/src/drivers/px4io/px4io_uploader.cpp
@@ -52,51 +52,14 @@
#include <termios.h>
#include <sys/stat.h>
+#include <crc32.h>
+
#include "uploader.h"
-static const uint32_t crctab[] =
-{
- 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
- 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
- 0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
- 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
- 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
- 0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
- 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
- 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
- 0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
- 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
- 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
- 0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
- 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
- 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
- 0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
- 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
- 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
- 0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
- 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
- 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
- 0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
- 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
- 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
- 0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
- 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
- 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
- 0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
- 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
- 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
- 0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
- 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
- 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
-};
-
-static uint32_t
-crc32(const uint8_t *src, unsigned len, unsigned state)
-{
- for (unsigned i = 0; i < len; i++)
- state = crctab[(state ^ src[i]) & 0xff] ^ (state >> 8);
- return state;
-}
+#include <board_config.h>
+
+// define for comms logging
+//#define UDEBUG
PX4IO_Uploader::PX4IO_Uploader() :
_io_fd(-1),
@@ -115,7 +78,11 @@ PX4IO_Uploader::upload(const char *filenames[])
const char *filename = NULL;
size_t fw_size;
- _io_fd = open("/dev/ttyS2", O_RDWR);
+#ifndef PX4IO_SERIAL_DEVICE
+#error Must define PX4IO_SERIAL_DEVICE in board configuration to support firmware upload
+#endif
+
+ _io_fd = open(PX4IO_SERIAL_DEVICE, O_RDWR);
if (_io_fd < 0) {
log("could not open interface");
@@ -258,12 +225,16 @@ PX4IO_Uploader::recv(uint8_t &c, unsigned timeout)
int ret = ::poll(&fds[0], 1, timeout);
if (ret < 1) {
- //log("poll timeout %d", ret);
+#ifdef UDEBUG
+ log("poll timeout %d", ret);
+#endif
return -ETIMEDOUT;
}
read(_io_fd, &c, 1);
- //log("recv 0x%02x", c);
+#ifdef UDEBUG
+ log("recv 0x%02x", c);
+#endif
return OK;
}
@@ -289,16 +260,20 @@ PX4IO_Uploader::drain()
do {
ret = recv(c, 1000);
+#ifdef UDEBUG
if (ret == OK) {
- //log("discard 0x%02x", c);
+ log("discard 0x%02x", c);
}
+#endif
} while (ret == OK);
}
int
PX4IO_Uploader::send(uint8_t c)
{
- //log("send 0x%02x", c);
+#ifdef UDEBUG
+ log("send 0x%02x", c);
+#endif
if (write(_io_fd, &c, 1) != 1)
return -errno;
@@ -572,14 +547,14 @@ PX4IO_Uploader::verify_rev3(size_t fw_size_local)
return -errno;
/* calculate crc32 sum */
- sum = crc32((uint8_t *)&file_buf, sizeof(file_buf), sum);
+ sum = crc32part((uint8_t *)&file_buf, sizeof(file_buf), sum);
bytes_read += count;
}
/* fill the rest with 0xff */
while (bytes_read < fw_size_remote) {
- sum = crc32(&fill_blank, sizeof(fill_blank), sum);
+ sum = crc32part(&fill_blank, sizeof(fill_blank), sum);
bytes_read += sizeof(fill_blank);
}
diff --git a/src/drivers/rgbled/module.mk b/src/drivers/rgbled/module.mk
new file mode 100644
index 000000000..39b53ec9e
--- /dev/null
+++ b/src/drivers/rgbled/module.mk
@@ -0,0 +1,6 @@
+#
+# TCA62724FMG driver for RGB LED
+#
+
+MODULE_COMMAND = rgbled
+SRCS = rgbled.cpp
diff --git a/src/drivers/rgbled/rgbled.cpp b/src/drivers/rgbled/rgbled.cpp
new file mode 100644
index 000000000..05f079ede
--- /dev/null
+++ b/src/drivers/rgbled/rgbled.cpp
@@ -0,0 +1,566 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 rgbled.cpp
+ *
+ * Driver for the onboard RGB LED controller (TCA62724FMG) connected via I2C.
+ *
+ *
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <ctype.h>
+
+#include <nuttx/wqueue.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+
+#include <board_config.h>
+
+#include <drivers/drv_rgbled.h>
+
+#define RGBLED_ONTIME 120
+#define RGBLED_OFFTIME 120
+
+#define ADDR PX4_I2C_OBDEV_LED /**< I2C adress of TCA62724FMG */
+#define SUB_ADDR_START 0x01 /**< write everything (with auto-increment) */
+#define SUB_ADDR_PWM0 0x81 /**< blue (without auto-increment) */
+#define SUB_ADDR_PWM1 0x82 /**< green (without auto-increment) */
+#define SUB_ADDR_PWM2 0x83 /**< red (without auto-increment) */
+#define SUB_ADDR_SETTINGS 0x84 /**< settings (without auto-increment)*/
+
+#define SETTING_NOT_POWERSAVE 0x01 /**< power-save mode not off */
+#define SETTING_ENABLE 0x02 /**< on */
+
+
+class RGBLED : public device::I2C
+{
+public:
+ RGBLED(int bus, int rgbled);
+ virtual ~RGBLED();
+
+
+ virtual int init();
+ virtual int probe();
+ virtual int info();
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+private:
+ work_s _work;
+
+ rgbled_color_t _color;
+ rgbled_mode_t _mode;
+ rgbled_pattern_t _pattern;
+
+ bool _should_run;
+ bool _running;
+ int _led_interval;
+ int _counter;
+
+ void set_color(rgbled_color_t ledcolor);
+ void set_mode(rgbled_mode_t mode);
+ void set_pattern(rgbled_pattern_t *pattern);
+
+ static void led_trampoline(void *arg);
+ void led();
+
+ int set(bool on, uint8_t r, uint8_t g, uint8_t b);
+ int set_on(bool on);
+ int set_rgb(uint8_t r, uint8_t g, uint8_t b);
+ int get(bool &on, bool &not_powersave, uint8_t &r, uint8_t &g, uint8_t &b);
+};
+
+/* for now, we only support one RGBLED */
+namespace
+{
+ RGBLED *g_rgbled;
+}
+
+
+extern "C" __EXPORT int rgbled_main(int argc, char *argv[]);
+
+RGBLED::RGBLED(int bus, int rgbled) :
+ I2C("rgbled", RGBLED_DEVICE_PATH, bus, rgbled, 100000),
+ _color(RGBLED_COLOR_OFF),
+ _mode(RGBLED_MODE_OFF),
+ _running(false),
+ _led_interval(0),
+ _counter(0)
+{
+ memset(&_work, 0, sizeof(_work));
+ memset(&_pattern, 0, sizeof(_pattern));
+}
+
+RGBLED::~RGBLED()
+{
+}
+
+int
+RGBLED::init()
+{
+ int ret;
+ ret = I2C::init();
+
+ if (ret != OK) {
+ return ret;
+ }
+
+ /* start off */
+ set(false, 0, 0, 0);
+
+ return OK;
+}
+
+int
+RGBLED::probe()
+{
+ int ret;
+ bool on, not_powersave;
+ uint8_t r, g, b;
+
+ ret = get(on, not_powersave, r, g, b);
+
+ return ret;
+}
+
+int
+RGBLED::info()
+{
+ int ret;
+ bool on, not_powersave;
+ uint8_t r, g, b;
+
+ ret = get(on, not_powersave, r, g, b);
+
+ if (ret == OK) {
+ /* we don't care about power-save mode */
+ log("state: %s", on ? "ON" : "OFF");
+ log("red: %u, green: %u, blue: %u", (unsigned)r, (unsigned)g, (unsigned)b);
+ } else {
+ warnx("failed to read led");
+ }
+
+ return ret;
+}
+
+int
+RGBLED::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int ret = ENOTTY;
+
+ switch (cmd) {
+ case RGBLED_SET_RGB:
+ /* set the specified RGB values */
+ rgbled_rgbset_t rgbset;
+ memcpy(&rgbset, (rgbled_rgbset_t*)arg, sizeof(rgbset));
+ set_rgb(rgbset.red, rgbset.green, rgbset.blue);
+ set_mode(RGBLED_MODE_ON);
+ return OK;
+
+ case RGBLED_SET_COLOR:
+ /* set the specified color name */
+ set_color((rgbled_color_t)arg);
+ return OK;
+
+ case RGBLED_SET_MODE:
+ /* set the specified blink speed */
+ set_mode((rgbled_mode_t)arg);
+ return OK;
+
+ case RGBLED_SET_PATTERN:
+ /* set a special pattern */
+ set_pattern((rgbled_pattern_t*)arg);
+ return OK;
+
+ default:
+ break;
+ }
+
+ return ret;
+}
+
+
+void
+RGBLED::led_trampoline(void *arg)
+{
+ RGBLED *rgbl = reinterpret_cast<RGBLED *>(arg);
+
+ rgbl->led();
+}
+
+
+
+void
+RGBLED::led()
+{
+ switch (_mode) {
+ case RGBLED_MODE_BLINK_SLOW:
+ case RGBLED_MODE_BLINK_NORMAL:
+ case RGBLED_MODE_BLINK_FAST:
+ if(_counter % 2 == 0)
+ set_on(true);
+ else
+ set_on(false);
+ break;
+ case RGBLED_MODE_PATTERN:
+ /* don't run out of the pattern array and stop if the next frame is 0 */
+ if (_counter >= RGBLED_PATTERN_LENGTH || _pattern.duration[_counter] <= 0)
+ _counter = 0;
+
+ set_color(_pattern.color[_counter]);
+ _led_interval = _pattern.duration[_counter];
+ break;
+ default:
+ break;
+ }
+
+ _counter++;
+
+ /* re-queue ourselves to run again later */
+ work_queue(LPWORK, &_work, (worker_t)&RGBLED::led_trampoline, this, _led_interval);
+}
+
+void
+RGBLED::set_color(rgbled_color_t color) {
+
+ _color = color;
+
+ switch (color) {
+ case RGBLED_COLOR_OFF: // off
+ set_rgb(0,0,0);
+ break;
+ case RGBLED_COLOR_RED: // red
+ set_rgb(255,0,0);
+ break;
+ case RGBLED_COLOR_YELLOW: // yellow
+ set_rgb(255,70,0);
+ break;
+ case RGBLED_COLOR_PURPLE: // purple
+ set_rgb(255,0,255);
+ break;
+ case RGBLED_COLOR_GREEN: // green
+ set_rgb(0,255,0);
+ break;
+ case RGBLED_COLOR_BLUE: // blue
+ set_rgb(0,0,255);
+ break;
+ case RGBLED_COLOR_WHITE: // white
+ set_rgb(255,255,255);
+ break;
+ case RGBLED_COLOR_AMBER: // amber
+ set_rgb(255,20,0);
+ break;
+ case RGBLED_COLOR_DIM_RED: // red
+ set_rgb(90,0,0);
+ break;
+ case RGBLED_COLOR_DIM_YELLOW: // yellow
+ set_rgb(80,30,0);
+ break;
+ case RGBLED_COLOR_DIM_PURPLE: // purple
+ set_rgb(45,0,45);
+ break;
+ case RGBLED_COLOR_DIM_GREEN: // green
+ set_rgb(0,90,0);
+ break;
+ case RGBLED_COLOR_DIM_BLUE: // blue
+ set_rgb(0,0,90);
+ break;
+ case RGBLED_COLOR_DIM_WHITE: // white
+ set_rgb(30,30,30);
+ break;
+ case RGBLED_COLOR_DIM_AMBER: // amber
+ set_rgb(80,20,0);
+ break;
+ default:
+ warnx("color unknown");
+ break;
+ }
+}
+
+void
+RGBLED::set_mode(rgbled_mode_t mode)
+{
+ _mode = mode;
+
+ switch (mode) {
+ case RGBLED_MODE_OFF:
+ _should_run = false;
+ set_on(false);
+ break;
+ case RGBLED_MODE_ON:
+ _should_run = false;
+ set_on(true);
+ break;
+ case RGBLED_MODE_BLINK_SLOW:
+ _should_run = true;
+ _led_interval = 2000;
+ break;
+ case RGBLED_MODE_BLINK_NORMAL:
+ _should_run = true;
+ _led_interval = 500;
+ break;
+ case RGBLED_MODE_BLINK_FAST:
+ _should_run = true;
+ _led_interval = 100;
+ break;
+ case RGBLED_MODE_PATTERN:
+ _should_run = true;
+ set_on(true);
+ _counter = 0;
+ break;
+ default:
+ warnx("mode unknown");
+ break;
+ }
+
+ /* if it should run now, start the workq */
+ if (_should_run && !_running) {
+ _running = true;
+ work_queue(LPWORK, &_work, (worker_t)&RGBLED::led_trampoline, this, 1);
+ }
+ /* if it should stop, then cancel the workq */
+ if (!_should_run && _running) {
+ _running = false;
+ work_cancel(LPWORK, &_work);
+ }
+}
+
+void
+RGBLED::set_pattern(rgbled_pattern_t *pattern)
+{
+ memcpy(&_pattern, pattern, sizeof(rgbled_pattern_t));
+
+ set_mode(RGBLED_MODE_PATTERN);
+}
+
+int
+RGBLED::set(bool on, uint8_t r, uint8_t g, uint8_t b)
+{
+ uint8_t settings_byte = 0;
+
+ if (on)
+ settings_byte |= SETTING_ENABLE;
+/* powersave not used */
+// if (not_powersave)
+ settings_byte |= SETTING_NOT_POWERSAVE;
+
+ const uint8_t msg[5] = { SUB_ADDR_START, (uint8_t)(b*15/255), (uint8_t)(g*15/255), (uint8_t)(r*15/255), settings_byte};
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+RGBLED::set_on(bool on)
+{
+ uint8_t settings_byte = 0;
+
+ if (on)
+ settings_byte |= SETTING_ENABLE;
+
+/* powersave not used */
+// if (not_powersave)
+ settings_byte |= SETTING_NOT_POWERSAVE;
+
+ const uint8_t msg[2] = { SUB_ADDR_SETTINGS, settings_byte};
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+int
+RGBLED::set_rgb(uint8_t r, uint8_t g, uint8_t b)
+{
+ const uint8_t msg[6] = { SUB_ADDR_PWM0, (uint8_t)(b*15/255), SUB_ADDR_PWM1, (uint8_t)(g*15/255), SUB_ADDR_PWM2, (uint8_t)(r*15/255)};
+
+ return transfer(msg, sizeof(msg), nullptr, 0);
+}
+
+
+int
+RGBLED::get(bool &on, bool &not_powersave, uint8_t &r, uint8_t &g, uint8_t &b)
+{
+ uint8_t result[2];
+ int ret;
+
+ ret = transfer(nullptr, 0, &result[0], 2);
+
+ if (ret == OK) {
+ on = result[0] & SETTING_ENABLE;
+ not_powersave = result[0] & SETTING_NOT_POWERSAVE;
+ /* XXX check, looks wrong */
+ r = (result[0] & 0x0f)*255/15;
+ g = (result[1] & 0xf0)*255/15;
+ b = (result[1] & 0x0f)*255/15;
+ }
+
+ return ret;
+}
+
+void rgbled_usage();
+
+
+void rgbled_usage() {
+ warnx("missing command: try 'start', 'test', 'info', 'stop'/'off', 'rgb 30 40 50'");
+ warnx("options:");
+ warnx(" -b i2cbus (%d)", PX4_I2C_BUS_LED);
+ errx(0, " -a addr (0x%x)", ADDR);
+}
+
+int
+rgbled_main(int argc, char *argv[])
+{
+ int i2cdevice = -1;
+ int rgbledadr = ADDR; /* 7bit */
+
+ int ch;
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc-1, &argv[1], "a:b:")) != EOF) {
+ switch (ch) {
+ case 'a':
+ rgbledadr = strtol(optarg, NULL, 0);
+ break;
+ case 'b':
+ i2cdevice = strtol(optarg, NULL, 0);
+ break;
+ default:
+ rgbled_usage();
+ }
+ }
+
+ const char *verb = argv[1];
+
+ int fd;
+ int ret;
+
+ if (!strcmp(verb, "start")) {
+ if (g_rgbled != nullptr)
+ errx(1, "already started");
+
+ if (i2cdevice == -1) {
+ // try the external bus first
+ i2cdevice = PX4_I2C_BUS_EXPANSION;
+ g_rgbled = new RGBLED(PX4_I2C_BUS_EXPANSION, rgbledadr);
+ if (g_rgbled != nullptr && OK != g_rgbled->init()) {
+ delete g_rgbled;
+ g_rgbled = nullptr;
+ }
+ if (g_rgbled == nullptr) {
+ // fall back to default bus
+ i2cdevice = PX4_I2C_BUS_LED;
+ }
+ }
+ if (g_rgbled == nullptr) {
+ g_rgbled = new RGBLED(i2cdevice, rgbledadr);
+ if (g_rgbled == nullptr)
+ errx(1, "new failed");
+
+ if (OK != g_rgbled->init()) {
+ delete g_rgbled;
+ g_rgbled = nullptr;
+ errx(1, "init failed");
+ }
+ }
+
+ exit(0);
+ }
+
+ /* need the driver past this point */
+ if (g_rgbled == nullptr) {
+ warnx("not started");
+ rgbled_usage();
+ exit(0);
+ }
+
+ if (!strcmp(verb, "test")) {
+ fd = open(RGBLED_DEVICE_PATH, 0);
+ if (fd == -1) {
+ errx(1, "Unable to open " RGBLED_DEVICE_PATH);
+ }
+
+ rgbled_pattern_t pattern = { {RGBLED_COLOR_RED, RGBLED_COLOR_GREEN, RGBLED_COLOR_BLUE, RGBLED_COLOR_OFF},
+ {200, 200, 200, 400 } };
+
+ ret = ioctl(fd, RGBLED_SET_PATTERN, (unsigned long)&pattern);
+
+ close(fd);
+ exit(ret);
+ }
+
+ if (!strcmp(verb, "info")) {
+ g_rgbled->info();
+ exit(0);
+ }
+
+ if (!strcmp(verb, "stop") || !strcmp(verb, "off")) {
+ /* although technically it doesn't stop, this is the excepted syntax */
+ fd = open(RGBLED_DEVICE_PATH, 0);
+ if (fd == -1) {
+ errx(1, "Unable to open " RGBLED_DEVICE_PATH);
+ }
+ ret = ioctl(fd, RGBLED_SET_MODE, (unsigned long)RGBLED_MODE_OFF);
+ close(fd);
+ exit(ret);
+ }
+
+ if (!strcmp(verb, "rgb")) {
+ fd = open(RGBLED_DEVICE_PATH, 0);
+ if (fd == -1) {
+ errx(1, "Unable to open " RGBLED_DEVICE_PATH);
+ }
+ if (argc < 5) {
+ errx(1, "Usage: rgbled rgb <red> <green> <blue>");
+ }
+ rgbled_rgbset_t v;
+ v.red = strtol(argv[1], NULL, 0);
+ v.green = strtol(argv[2], NULL, 0);
+ v.blue = strtol(argv[3], NULL, 0);
+ ret = ioctl(fd, RGBLED_SET_RGB, (unsigned long)&v);
+ close(fd);
+ exit(ret);
+ }
+
+ rgbled_usage();
+}
diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp
index 1020eb946..00e46d6b8 100644
--- a/src/drivers/stm32/adc/adc.cpp
+++ b/src/drivers/stm32/adc/adc.cpp
@@ -227,7 +227,6 @@ ADC::init()
if ((hrt_absolute_time() - now) > 500) {
log("sample timeout");
return -1;
- return 0xffff;
}
}
@@ -282,7 +281,7 @@ ADC::close_last(struct file *filp)
void
ADC::_tick_trampoline(void *arg)
{
- ((ADC *)arg)->_tick();
+ (reinterpret_cast<ADC *>(arg))->_tick();
}
void
@@ -342,7 +341,7 @@ test(void)
err(1, "can't open ADC device");
for (unsigned i = 0; i < 50; i++) {
- adc_msg_s data[8];
+ adc_msg_s data[10];
ssize_t count = read(fd, data, sizeof(data));
if (count < 0)
@@ -366,8 +365,15 @@ int
adc_main(int argc, char *argv[])
{
if (g_adc == nullptr) {
- /* XXX this hardcodes the default channel set for PX4FMU - should be configurable */
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ /* XXX this hardcodes the default channel set for PX4FMUv1 - should be configurable */
g_adc = new ADC((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
+#endif
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ /* XXX this hardcodes the default channel set for PX4FMUv2 - should be configurable */
+ g_adc = new ADC((1 << 2) | (1 << 3) | (1 << 4) |
+ (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15));
+#endif
if (g_adc == nullptr)
errx(1, "couldn't allocate the ADC driver");
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index 83a1a1abb..e79d7e10a 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -59,7 +59,7 @@
#include <errno.h>
#include <string.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <drivers/drv_hrt.h>
#include "chip.h"
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index 2284be84d..ad21f7143 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -104,7 +104,7 @@
#include <math.h>
#include <ctype.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include <drivers/drv_hrt.h>
#include <arch/stm32/chip.h>
@@ -237,6 +237,8 @@ private:
static const unsigned _default_ntunes;
static const uint8_t _note_tab[];
+ unsigned _default_tune_number; // number of currently playing default tune (0 for none)
+
const char *_user_tune;
const char *_tune; // current tune string
@@ -452,6 +454,9 @@ const char * const ToneAlarm::_default_tunes[] = {
"O1B8O2G+8E8B8G+8O3E8O2B8O3E8O2B8O3G+8E8B8"
"O3G+8O4E4P8E16E16E8E8E8E8E4P8E16E4P8O2E16"
"O2E2P64",
+ "MNT75L1O2G", //arming warning
+ "MBNT100a8", //battery warning slow
+ "MBNT255a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8a8" //battery warning fast // XXX why is there a break before a repetition
};
const unsigned ToneAlarm::_default_ntunes = sizeof(_default_tunes) / sizeof(_default_tunes[0]);
@@ -467,6 +472,7 @@ extern "C" __EXPORT int tone_alarm_main(int argc, char *argv[]);
ToneAlarm::ToneAlarm() :
CDev("tone_alarm", "/dev/tone_alarm"),
+ _default_tune_number(0),
_user_tune(nullptr),
_tune(nullptr),
_next(nullptr)
@@ -799,8 +805,12 @@ tune_error:
// stop (and potentially restart) the tune
tune_end:
stop_note();
- if (_repeat)
+ if (_repeat) {
start_tune(_tune);
+ } else {
+ _tune = nullptr;
+ _default_tune_number = 0;
+ }
return;
}
@@ -869,8 +879,12 @@ ToneAlarm::ioctl(file *filp, int cmd, unsigned long arg)
_tune = nullptr;
_next = nullptr;
} else {
- // play the selected tune
- start_tune(_default_tunes[arg - 1]);
+ /* always interrupt alarms, unless they are repeating and already playing */
+ if (!(_repeat && _default_tune_number == arg)) {
+ /* play the selected tune */
+ _default_tune_number = arg;
+ start_tune(_default_tunes[arg - 1]);
+ }
}
} else {
result = -EINVAL;