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/airspeed/airspeed.h4
-rw-r--r--src/drivers/airspeed/module.mk2
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c36
-rw-r--r--src/drivers/ardrone_interface/ardrone_motor_control.c4
-rw-r--r--src/drivers/ardrone_interface/module.mk2
-rw-r--r--src/drivers/blinkm/blinkm.cpp15
-rw-r--r--src/drivers/blinkm/module.mk2
-rw-r--r--src/drivers/bma180/module.mk2
-rw-r--r--src/drivers/boards/aerocore/aerocore_init.c13
-rw-r--r--src/drivers/boards/aerocore/board_config.h19
-rw-r--r--src/drivers/boards/aerocore/module.mk2
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h22
-rw-r--r--src/drivers/boards/px4fmu-v1/module.mk2
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_init.c2
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_led.c4
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h34
-rw-r--r--src/drivers/boards/px4fmu-v2/module.mk2
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_init.c13
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_led.c2
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_spi.c24
-rw-r--r--src/drivers/boards/px4io-v1/module.mk2
-rw-r--r--src/drivers/boards/px4io-v2/board_config.h1
-rw-r--r--src/drivers/boards/px4io-v2/module.mk2
-rw-r--r--src/drivers/boards/px4io-v2/px4iov2_init.c1
-rw-r--r--src/drivers/device/cdev.cpp7
-rw-r--r--src/drivers/device/device.cpp13
-rw-r--r--src/drivers/device/device.h40
-rw-r--r--src/drivers/device/i2c.cpp8
-rw-r--r--src/drivers/device/i2c.h3
-rw-r--r--src/drivers/device/ringbuffer.h4
-rw-r--r--src/drivers/device/spi.cpp72
-rw-r--r--src/drivers/device/spi.h11
-rw-r--r--src/drivers/drv_accel.h4
-rw-r--r--src/drivers/drv_baro.h3
-rw-r--r--src/drivers/drv_device.h7
-rw-r--r--src/drivers/drv_gps.h3
-rw-r--r--src/drivers/drv_gyro.h4
-rw-r--r--src/drivers/drv_mag.h10
-rw-r--r--src/drivers/drv_pwm_output.h47
-rw-r--r--src/drivers/drv_px4flow.h19
-rw-r--r--src/drivers/drv_range_finder.h9
-rw-r--r--src/drivers/drv_rc_input.h12
-rw-r--r--src/drivers/drv_tone_alarm.h2
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp25
-rw-r--r--src/drivers/ets_airspeed/module.mk5
-rw-r--r--src/drivers/frsky_telemetry/frsky_telemetry.c9
-rw-r--r--src/drivers/frsky_telemetry/module.mk2
-rw-r--r--src/drivers/gps/ashtech.cpp641
-rw-r--r--src/drivers/gps/ashtech.h96
-rw-r--r--src/drivers/gps/gps.cpp166
-rw-r--r--src/drivers/gps/gps_helper.h4
-rw-r--r--src/drivers/gps/module.mk3
-rw-r--r--src/drivers/gps/mtk.cpp10
-rw-r--r--src/drivers/gps/ubx.cpp1131
-rw-r--r--src/drivers/gps/ubx.h729
-rw-r--r--src/drivers/hil/hil.cpp7
-rw-r--r--src/drivers/hil/module.mk2
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp417
-rw-r--r--src/drivers/hmc5883/module.mk9
-rw-r--r--src/drivers/hott/comms.cpp8
-rw-r--r--src/drivers/hott/hott_sensors/hott_sensors.cpp6
-rw-r--r--src/drivers/hott/hott_sensors/module.mk2
-rw-r--r--src/drivers/hott/hott_telemetry/hott_telemetry.cpp6
-rw-r--r--src/drivers/hott/hott_telemetry/module.mk2
-rw-r--r--src/drivers/hott/messages.cpp16
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp123
-rw-r--r--src/drivers/l3gd20/module.mk6
-rw-r--r--src/drivers/led/module.mk2
-rw-r--r--src/drivers/ll40ls/ll40ls.cpp1010
-rw-r--r--src/drivers/ll40ls/module.mk42
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp174
-rw-r--r--src/drivers/lsm303d/module.mk4
-rw-r--r--src/drivers/mb12xx/mb12xx.cpp45
-rw-r--r--src/drivers/mb12xx/module.mk2
-rw-r--r--src/drivers/md25/module.mk2
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp58
-rw-r--r--src/drivers/meas_airspeed/module.mk7
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp33
-rw-r--r--src/drivers/mkblctrl/module.mk4
-rw-r--r--src/drivers/mpu6000/module.mk9
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp254
-rw-r--r--src/drivers/ms5611/module.mk2
-rw-r--r--src/drivers/ms5611/ms5611.cpp78
-rw-r--r--src/drivers/ms5611/ms5611.h2
-rw-r--r--src/drivers/ms5611/ms5611_spi.cpp14
-rw-r--r--src/drivers/pca8574/module.mk2
-rw-r--r--src/drivers/pca9685/arduino_Adafruit_PWM_Servo_Driver_Library_license.txt29
-rw-r--r--src/drivers/pca9685/module.mk42
-rw-r--r--src/drivers/pca9685/pca9685.cpp651
-rw-r--r--src/drivers/px4flow/module.mk2
-rw-r--r--src/drivers/px4flow/px4flow.cpp253
-rw-r--r--src/drivers/px4fmu/fmu.cpp28
-rw-r--r--src/drivers/px4fmu/module.mk4
-rw-r--r--src/drivers/px4io/module.mk4
-rw-r--r--src/drivers/px4io/px4io.cpp228
-rwxr-xr-x[-rw-r--r--]src/drivers/px4io/px4io_i2c.cpp2
-rw-r--r--src/drivers/px4io/px4io_serial.cpp10
-rw-r--r--src/drivers/px4io/px4io_uploader.cpp86
-rw-r--r--src/drivers/px4io/uploader.h9
-rw-r--r--src/drivers/rgbled/module.mk2
-rw-r--r--src/drivers/roboclaw/RoboClaw.cpp10
-rw-r--r--src/drivers/roboclaw/module.mk2
-rw-r--r--src/drivers/sf0x/module.mk5
-rw-r--r--src/drivers/sf0x/sf0x.cpp105
-rw-r--r--src/drivers/sf0x/sf0x_parser.cpp155
-rw-r--r--src/drivers/sf0x/sf0x_parser.h51
-rw-r--r--src/drivers/stm32/adc/module.mk2
-rw-r--r--src/drivers/stm32/module.mk2
-rw-r--r--src/drivers/stm32/tone_alarm/module.mk2
-rw-r--r--src/drivers/stm32/tone_alarm/tone_alarm.cpp4
111 files changed, 5777 insertions, 1579 deletions
diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp
index 41942aacd..3a1e1b7b5 100644
--- a/src/drivers/airspeed/airspeed.cpp
+++ b/src/drivers/airspeed/airspeed.cpp
@@ -147,7 +147,7 @@ Airspeed::init()
_airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &arp);
if (_airspeed_pub < 0)
- warnx("failed to create airspeed sensor object. uORB started?");
+ warnx("uORB started?");
}
ret = OK;
@@ -165,7 +165,7 @@ Airspeed::probe()
*/
_retries = 4;
int ret = measure();
- _retries = 2;
+ _retries = 0;
return ret;
}
@@ -381,7 +381,10 @@ Airspeed::cycle_trampoline(void *arg)
Airspeed *dev = (Airspeed *)arg;
dev->cycle();
- dev->update_status();
+ // XXX we do not know if this is
+ // really helping - do not update the
+ // subsys state right now
+ //dev->update_status();
}
void
diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h
index 0b8e949c9..d6a88714b 100644
--- a/src/drivers/airspeed/airspeed.h
+++ b/src/drivers/airspeed/airspeed.h
@@ -107,6 +107,10 @@ private:
RingBuffer *_reports;
perf_counter_t _buffer_overflows;
+ /* this class has pointer data members and should not be copied */
+ Airspeed(const Airspeed&);
+ Airspeed& operator=(const Airspeed&);
+
protected:
virtual int probe();
diff --git a/src/drivers/airspeed/module.mk b/src/drivers/airspeed/module.mk
index 4eef06161..5fbc75309 100644
--- a/src/drivers/airspeed/module.mk
+++ b/src/drivers/airspeed/module.mk
@@ -36,3 +36,5 @@
#
SRCS = airspeed.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index e5bb772b3..9d2c1441d 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -89,8 +89,8 @@ static void
usage(const char *reason)
{
if (reason)
- fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: ardrone_interface {start|stop|status} [-d <UART>]\n\n");
+ warnx("%s\n", reason);
+ warnx("usage: {start|stop|status} [-d <UART>]\n\n");
exit(1);
}
@@ -110,7 +110,7 @@ int ardrone_interface_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- printf("ardrone_interface already running\n");
+ warnx("already running\n");
/* this is not an error */
exit(0);
}
@@ -132,9 +132,9 @@ int ardrone_interface_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tardrone_interface is running\n");
+ warnx("running");
} else {
- printf("\tardrone_interface not started\n");
+ warnx("not started");
}
exit(0);
}
@@ -158,7 +158,7 @@ static int ardrone_open_uart(char *uart_name, struct termios *uart_config_origin
/* Back up the original uart configuration to restore it after exit */
if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
- fprintf(stderr, "[ardrone_interface] ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state);
+ warnx("ERR: TCGETATTR %s: %d", uart_name, termios_state);
close(uart);
return -1;
}
@@ -171,14 +171,14 @@ static int ardrone_open_uart(char *uart_name, struct termios *uart_config_origin
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
- fprintf(stderr, "[ardrone_interface] ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
+ warnx("ERR: cfsetispeed %s: %d", uart_name, termios_state);
close(uart);
return -1;
}
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
- fprintf(stderr, "[ardrone_interface] ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
+ warnx("ERR: tcsetattr: %s", uart_name);
close(uart);
return -1;
}
@@ -192,9 +192,6 @@ int ardrone_interface_thread_main(int argc, char *argv[])
char *device = "/dev/ttyS1";
- /* welcome user */
- printf("[ardrone_interface] Control started, taking over motors\n");
-
/* File descriptors */
int gpios;
@@ -237,7 +234,7 @@ int ardrone_interface_thread_main(int argc, char *argv[])
struct termios uart_config_original;
if (motor_test_mode) {
- printf("[ardrone_interface] Motor test mode enabled, setting 10 %% thrust.\n");
+ warnx("setting 10 %% thrust.\n");
}
/* Led animation */
@@ -255,9 +252,6 @@ int ardrone_interface_thread_main(int argc, char *argv[])
int actuator_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
- printf("[ardrone_interface] Motors initialized - ready.\n");
- fflush(stdout);
-
/* enable UART, writes potentially an empty buffer, but multiplexing is disabled */
ardrone_write = ardrone_open_uart(device, &uart_config_original);
@@ -265,7 +259,7 @@ int ardrone_interface_thread_main(int argc, char *argv[])
gpios = ar_multiplexing_init();
if (ardrone_write < 0) {
- fprintf(stderr, "[ardrone_interface] Failed opening AR.Drone UART, exiting.\n");
+ warnx("No UART, exiting.");
thread_running = false;
exit(ERROR);
}
@@ -273,7 +267,7 @@ int ardrone_interface_thread_main(int argc, char *argv[])
/* initialize motors */
if (OK != ar_init_motors(ardrone_write, gpios)) {
close(ardrone_write);
- fprintf(stderr, "[ardrone_interface] Failed initializing AR.Drone motors, exiting.\n");
+ warnx("motor init fail");
thread_running = false;
exit(ERROR);
}
@@ -294,7 +288,7 @@ int ardrone_interface_thread_main(int argc, char *argv[])
gpios = ar_multiplexing_init();
if (ardrone_write < 0) {
- fprintf(stderr, "[ardrone_interface] Failed opening AR.Drone UART, exiting.\n");
+ warnx("write fail");
thread_running = false;
exit(ERROR);
}
@@ -302,7 +296,7 @@ int ardrone_interface_thread_main(int argc, char *argv[])
/* initialize motors */
if (OK != ar_init_motors(ardrone_write, gpios)) {
close(ardrone_write);
- fprintf(stderr, "[ardrone_interface] Failed initializing AR.Drone motors, exiting.\n");
+ warnx("motor init fail");
thread_running = false;
exit(ERROR);
}
@@ -378,11 +372,9 @@ int ardrone_interface_thread_main(int argc, char *argv[])
int termios_state;
if ((termios_state = tcsetattr(ardrone_write, TCSANOW, &uart_config_original)) < 0) {
- fprintf(stderr, "[ardrone_interface] ERROR setting baudrate / termios config for (tcsetattr)\n");
+ warnx("ERR: tcsetattr");
}
- printf("[ardrone_interface] Restored original UART config, exiting..\n");
-
/* close uarts */
close(ardrone_write);
ar_multiplexing_deinit(gpios);
diff --git a/src/drivers/ardrone_interface/ardrone_motor_control.c b/src/drivers/ardrone_interface/ardrone_motor_control.c
index 81f634992..4fa24275f 100644
--- a/src/drivers/ardrone_interface/ardrone_motor_control.c
+++ b/src/drivers/ardrone_interface/ardrone_motor_control.c
@@ -301,7 +301,7 @@ int ar_init_motors(int ardrone_uart, int gpios)
ardrone_write_motor_commands(ardrone_uart, 0, 0, 0, 0);
if (errcounter != 0) {
- fprintf(stderr, "[ardrone_interface] init sequence incomplete, failed %d times", -errcounter);
+ warnx("Failed %d times", -errcounter);
fflush(stdout);
}
return errcounter;
@@ -382,8 +382,6 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
float output_band = 0.0f;
const float startpoint_full_control = 0.25f; /**< start full control at 25% thrust */
- static bool initialized = false;
-
/* linearly scale the control inputs from 0 to startpoint_full_control */
if (motor_thrust < startpoint_full_control) {
output_band = motor_thrust/startpoint_full_control; // linear from 0 to 1
diff --git a/src/drivers/ardrone_interface/module.mk b/src/drivers/ardrone_interface/module.mk
index d8e6c76c6..285db1351 100644
--- a/src/drivers/ardrone_interface/module.mk
+++ b/src/drivers/ardrone_interface/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = ardrone_interface
SRCS = ardrone_interface.c \
ardrone_motor_control.c
MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 5c502f682..6b14f5945 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -293,7 +293,7 @@ BlinkM::BlinkM(int bus, int blinkm) :
safety_sub_fd(-1),
num_of_cells(0),
detected_cells_runcount(0),
- t_led_color({0}),
+ t_led_color{0},
t_led_blink(0),
led_thread_runcount(0),
led_interval(1000),
@@ -559,13 +559,7 @@ BlinkM::led()
}
/* get number of used satellites in navigation */
- num_of_used_sats = 0;
-
- for(unsigned satloop=0; satloop<sizeof(vehicle_gps_position_raw.satellite_used); satloop++) {
- if(vehicle_gps_position_raw.satellite_used[satloop] == 1) {
- num_of_used_sats++;
- }
- }
+ num_of_used_sats = vehicle_gps_position_raw.satellites_used;
if (new_data_vehicle_status || no_data_vehicle_status < 3) {
if (num_of_cells == 0) {
@@ -655,13 +649,14 @@ BlinkM::led()
/* indicate main control state */
if (vehicle_status_raw.main_state == MAIN_STATE_POSCTL)
led_color_4 = LED_GREEN;
- else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO)
+ /* TODO: add other Auto modes */
+ else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO_MISSION)
led_color_4 = LED_BLUE;
else if (vehicle_status_raw.main_state == MAIN_STATE_ALTCTL)
led_color_4 = LED_YELLOW;
else if (vehicle_status_raw.main_state == MAIN_STATE_MANUAL)
led_color_4 = LED_WHITE;
- else
+ else
led_color_4 = LED_OFF;
led_color_5 = led_color_4;
}
diff --git a/src/drivers/blinkm/module.mk b/src/drivers/blinkm/module.mk
index b48b90f3f..c90673317 100644
--- a/src/drivers/blinkm/module.mk
+++ b/src/drivers/blinkm/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = blinkm
SRCS = blinkm.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/bma180/module.mk b/src/drivers/bma180/module.mk
index 4c60ee082..33433307a 100644
--- a/src/drivers/bma180/module.mk
+++ b/src/drivers/bma180/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = bma180
SRCS = bma180.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/boards/aerocore/aerocore_init.c b/src/drivers/boards/aerocore/aerocore_init.c
index 4e3ba2d7e..1ce235da8 100644
--- a/src/drivers/boards/aerocore/aerocore_init.c
+++ b/src/drivers/boards/aerocore/aerocore_init.c
@@ -93,6 +93,19 @@
# endif
#endif
+/*
+ * 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(void);
+extern void led_on(int led);
+extern void led_off(int led);
+__END_DECLS
+
/****************************************************************************
* Protected Functions
****************************************************************************/
diff --git a/src/drivers/boards/aerocore/board_config.h b/src/drivers/boards/aerocore/board_config.h
index 70142a314..776a2071e 100644
--- a/src/drivers/boards/aerocore/board_config.h
+++ b/src/drivers/boards/aerocore/board_config.h
@@ -171,6 +171,25 @@ __BEGIN_DECLS
extern void stm32_spiinitialize(void);
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization for NSH.
+ *
+ * CONFIG_NSH_ARCHINIT=y :
+ * Called from the NSH library
+ *
+ * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
+ * CONFIG_NSH_ARCHINIT=n :
+ * Called from board_initialize().
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_LIBRARY
+int nsh_archinitialize(void);
+#endif
+
#endif /* __ASSEMBLY__ */
__END_DECLS
diff --git a/src/drivers/boards/aerocore/module.mk b/src/drivers/boards/aerocore/module.mk
index b53fe0a29..0a2d91009 100644
--- a/src/drivers/boards/aerocore/module.mk
+++ b/src/drivers/boards/aerocore/module.mk
@@ -6,3 +6,5 @@ SRCS = aerocore_init.c \
aerocore_pwm_servo.c \
aerocore_spi.c \
aerocore_led.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
index c944007a5..188885be2 100644
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -86,7 +86,6 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
#define PX4_SPI_BUS_SENSORS 1
-#define PX4_SPI_BUS_EXT 2
/*
* Use these in place of the spi_dev_e enumeration to
@@ -210,6 +209,27 @@ __BEGIN_DECLS
extern void stm32_spiinitialize(void);
+extern void stm32_usbinitialize(void);
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization for NSH.
+ *
+ * CONFIG_NSH_ARCHINIT=y :
+ * Called from the NSH library
+ *
+ * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
+ * CONFIG_NSH_ARCHINIT=n :
+ * Called from board_initialize().
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_LIBRARY
+int nsh_archinitialize(void);
+#endif
+
#endif /* __ASSEMBLY__ */
__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v1/module.mk b/src/drivers/boards/px4fmu-v1/module.mk
index 66b776917..5e1a27d5a 100644
--- a/src/drivers/boards/px4fmu-v1/module.mk
+++ b/src/drivers/boards/px4fmu-v1/module.mk
@@ -8,3 +8,5 @@ SRCS = px4fmu_can.c \
px4fmu_spi.c \
px4fmu_usb.c \
px4fmu_led.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_init.c b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
index 4b12b75f9..293021f8b 100644
--- a/src/drivers/boards/px4fmu-v1/px4fmu_init.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_init.c
@@ -99,7 +99,7 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
-extern void led_init();
+extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_led.c b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
index ea91f34ad..ee53fc43d 100644
--- a/src/drivers/boards/px4fmu-v1/px4fmu_led.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_led.c
@@ -54,13 +54,13 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
-extern void led_init();
+extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
__END_DECLS
-__EXPORT void led_init()
+__EXPORT void led_init(void)
{
/* Configure LED1-2 GPIOs for output */
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index 36eb7bec4..ee365e47c 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -108,6 +108,8 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
#define GPIO_SPI_CS_EXT0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
#define GPIO_SPI_CS_EXT1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
+#define GPIO_SPI_CS_EXT2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
+#define GPIO_SPI_CS_EXT3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_EXT 4
@@ -121,10 +123,19 @@ __BEGIN_DECLS
/* External bus */
#define PX4_SPIDEV_EXT0 1
#define PX4_SPIDEV_EXT1 2
+#define PX4_SPIDEV_EXT2 3
+#define PX4_SPIDEV_EXT3 4
+
+/* FMUv3 SPI on external bus */
+#define PX4_SPIDEV_EXT_MPU PX4_SPIDEV_EXT0
+#define PX4_SPIDEV_EXT_BARO PX4_SPIDEV_EXT1
+#define PX4_SPIDEV_EXT_ACCEL_MAG PX4_SPIDEV_EXT2
+#define PX4_SPIDEV_EXT_GYRO PX4_SPIDEV_EXT3
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
-#define PX4_I2C_BUS_LED 2
+#define PX4_I2C_BUS_ONBOARD 2
+#define PX4_I2C_BUS_LED PX4_I2C_BUS_ONBOARD
/* Devices on the onboard bus.
*
@@ -218,6 +229,27 @@ __BEGIN_DECLS
extern void stm32_spiinitialize(void);
+extern void stm32_usbinitialize(void);
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization for NSH.
+ *
+ * CONFIG_NSH_ARCHINIT=y :
+ * Called from the NSH library
+ *
+ * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
+ * CONFIG_NSH_ARCHINIT=n :
+ * Called from board_initialize().
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_LIBRARY
+int nsh_archinitialize(void);
+#endif
+
#endif /* __ASSEMBLY__ */
__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v2/module.mk b/src/drivers/boards/px4fmu-v2/module.mk
index 99d37eeca..103232b0c 100644
--- a/src/drivers/boards/px4fmu-v2/module.mk
+++ b/src/drivers/boards/px4fmu-v2/module.mk
@@ -8,3 +8,5 @@ SRCS = px4fmu_can.c \
px4fmu_spi.c \
px4fmu_usb.c \
px4fmu2_led.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
index bf41bb1fe..9b25c574a 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
@@ -94,6 +94,19 @@
# endif
#endif
+/*
+ * 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(void);
+extern void led_on(int led);
+extern void led_off(int led);
+__END_DECLS
+
/****************************************************************************
* Protected Functions
****************************************************************************/
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_led.c b/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
index a856ccb02..3c05bfa46 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_led.c
@@ -54,7 +54,7 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
-extern void led_init();
+extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
index 01dbd6e77..8c37d31a7 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
@@ -98,8 +98,12 @@ __EXPORT void weak_function stm32_spiinitialize(void)
#ifdef CONFIG_STM32_SPI4
stm32_configgpio(GPIO_SPI_CS_EXT0);
stm32_configgpio(GPIO_SPI_CS_EXT1);
+ stm32_configgpio(GPIO_SPI_CS_EXT2);
+ stm32_configgpio(GPIO_SPI_CS_EXT3);
stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1);
#endif
}
@@ -174,12 +178,32 @@ __EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
/* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_EXT0, !selected);
stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1);
break;
case PX4_SPIDEV_EXT1:
/* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
stm32_gpiowrite(GPIO_SPI_CS_EXT1, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1);
+ break;
+
+ case PX4_SPIDEV_EXT2:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT2, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1);
+ break;
+
+ case PX4_SPIDEV_EXT3:
+ /* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT3, !selected);
break;
default:
diff --git a/src/drivers/boards/px4io-v1/module.mk b/src/drivers/boards/px4io-v1/module.mk
index 2601a1c15..a7a14dd07 100644
--- a/src/drivers/boards/px4io-v1/module.mk
+++ b/src/drivers/boards/px4io-v1/module.mk
@@ -4,3 +4,5 @@
SRCS = px4io_init.c \
px4io_pwm_servo.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/boards/px4io-v2/board_config.h b/src/drivers/boards/px4io-v2/board_config.h
index ef9bb5cad..10a93be0b 100644
--- a/src/drivers/boards/px4io-v2/board_config.h
+++ b/src/drivers/boards/px4io-v2/board_config.h
@@ -77,6 +77,7 @@
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14)
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_LED4 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN11)
/* Safety switch button *******************************************************/
diff --git a/src/drivers/boards/px4io-v2/module.mk b/src/drivers/boards/px4io-v2/module.mk
index 85f94e8be..3f0e9a0b3 100644
--- a/src/drivers/boards/px4io-v2/module.mk
+++ b/src/drivers/boards/px4io-v2/module.mk
@@ -4,3 +4,5 @@
SRCS = px4iov2_init.c \
px4iov2_pwm_servo.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/boards/px4io-v2/px4iov2_init.c b/src/drivers/boards/px4io-v2/px4iov2_init.c
index 9f8c0eeb2..5c3343ccc 100644
--- a/src/drivers/boards/px4io-v2/px4iov2_init.c
+++ b/src/drivers/boards/px4io-v2/px4iov2_init.c
@@ -108,6 +108,7 @@ __EXPORT void stm32_boardinitialize(void)
stm32_configgpio(GPIO_LED1);
stm32_configgpio(GPIO_LED2);
stm32_configgpio(GPIO_LED3);
+ stm32_configgpio(GPIO_LED4);
stm32_configgpio(GPIO_BTN_SAFETY);
diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp
index 6e2ebb1f7..39fb89501 100644
--- a/src/drivers/device/cdev.cpp
+++ b/src/drivers/device/cdev.cpp
@@ -268,6 +268,13 @@ CDev::ioctl(struct file *filp, int cmd, unsigned long arg)
break;
}
+ /* try the superclass. The different ioctl() function form
+ * means we need to copy arg */
+ unsigned arg2 = arg;
+ int ret = Device::ioctl(cmd, arg2);
+ if (ret != -ENODEV)
+ return ret;
+
return -ENOTTY;
}
diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp
index 683455149..d46901683 100644
--- a/src/drivers/device/device.cpp
+++ b/src/drivers/device/device.cpp
@@ -42,6 +42,7 @@
#include <nuttx/arch.h>
#include <stdio.h>
#include <unistd.h>
+#include <drivers/drv_device.h>
namespace device
{
@@ -93,6 +94,14 @@ Device::Device(const char *name,
_irq_attached(false)
{
sem_init(&_lock, 0, 1);
+
+ /* setup a default device ID. When bus_type is UNKNOWN the
+ other fields are invalid */
+ _device_id.devid = 0;
+ _device_id.devid_s.bus_type = DeviceBusType_UNKNOWN;
+ _device_id.devid_s.bus = 0;
+ _device_id.devid_s.address = 0;
+ _device_id.devid_s.devtype = 0;
}
Device::~Device()
@@ -238,6 +247,10 @@ Device::write(unsigned offset, void *data, unsigned count)
int
Device::ioctl(unsigned operation, unsigned &arg)
{
+ switch (operation) {
+ case DEVIOCGDEVICEID:
+ return (int)_device_id.devid;
+ }
return -ENODEV;
}
diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h
index d99f22922..67aaa0aff 100644
--- a/src/drivers/device/device.h
+++ b/src/drivers/device/device.h
@@ -124,9 +124,38 @@ public:
*/
virtual int ioctl(unsigned operation, unsigned &arg);
+ /*
+ device bus types for DEVID
+ */
+ enum DeviceBusType {
+ DeviceBusType_UNKNOWN = 0,
+ DeviceBusType_I2C = 1,
+ DeviceBusType_SPI = 2,
+ DeviceBusType_UAVCAN = 3,
+ };
+
+ /*
+ broken out device elements. The bitfields are used to keep
+ the overall value small enough to fit in a float accurately,
+ which makes it possible to transport over the MAVLink
+ parameter protocol without loss of information.
+ */
+ struct DeviceStructure {
+ enum DeviceBusType bus_type:3;
+ uint8_t bus:5; // which instance of the bus type
+ uint8_t address; // address on the bus (eg. I2C address)
+ uint8_t devtype; // device class specific device type
+ };
+
+ union DeviceId {
+ struct DeviceStructure devid_s;
+ uint32_t devid;
+ };
+
protected:
const char *_name; /**< driver name */
bool _debug_enabled; /**< if true, debug messages are printed */
+ union DeviceId _device_id; /**< device identifier information */
/**
* Constructor
@@ -212,6 +241,7 @@ private:
* @param context Pointer to the interrupted context.
*/
static void dev_interrupt(int irq, void *context);
+
};
/**
@@ -441,6 +471,10 @@ private:
* @return OK, or -errno on error.
*/
int remove_poll_waiter(struct pollfd *fds);
+
+ /* do not allow copying this class */
+ CDev(const CDev&);
+ CDev operator=(const CDev&);
};
/**
@@ -510,6 +544,10 @@ private:
} // namespace device
// class instance for primary driver of each class
-#define CLASS_DEVICE_PRIMARY 0
+enum CLASS_DEVICE {
+ CLASS_DEVICE_PRIMARY=0,
+ CLASS_DEVICE_SECONDARY=1,
+ CLASS_DEVICE_TERTIARY=2
+};
#endif /* _DEVICE_DEVICE_H */
diff --git a/src/drivers/device/i2c.cpp b/src/drivers/device/i2c.cpp
index a416801eb..286778c01 100644
--- a/src/drivers/device/i2c.cpp
+++ b/src/drivers/device/i2c.cpp
@@ -62,6 +62,12 @@ I2C::I2C(const char *name,
_frequency(frequency),
_dev(nullptr)
{
+ // fill in _device_id fields for a I2C device
+ _device_id.devid_s.bus_type = DeviceBusType_I2C;
+ _device_id.devid_s.bus = bus;
+ _device_id.devid_s.address = address;
+ // devtype needs to be filled in by the driver
+ _device_id.devid_s.devtype = 0;
}
I2C::~I2C()
@@ -201,4 +207,4 @@ I2C::transfer(i2c_msg_s *msgv, unsigned msgs)
return ret;
}
-} // namespace device \ No newline at end of file
+} // namespace device
diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h
index 549879352..705b398b0 100644
--- a/src/drivers/device/i2c.h
+++ b/src/drivers/device/i2c.h
@@ -138,6 +138,9 @@ private:
uint16_t _address;
uint32_t _frequency;
struct i2c_dev_s *_dev;
+
+ I2C(const device::I2C&);
+ I2C operator=(const device::I2C&);
};
} // namespace device
diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h
index a9e22eaa6..b26e2e7c8 100644
--- a/src/drivers/device/ringbuffer.h
+++ b/src/drivers/device/ringbuffer.h
@@ -162,6 +162,10 @@ private:
volatile unsigned _tail; /**< removal point in _item_size units */
unsigned _next(unsigned index);
+
+ /* we don't want this class to be copied */
+ RingBuffer(const RingBuffer&);
+ RingBuffer operator=(const RingBuffer&);
};
RingBuffer::RingBuffer(unsigned num_items, size_t item_size) :
diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp
index fed6c312c..200acac05 100644
--- a/src/drivers/device/spi.cpp
+++ b/src/drivers/device/spi.cpp
@@ -69,12 +69,18 @@ SPI::SPI(const char *name,
// protected
locking_mode(LOCK_PREEMPTION),
// private
- _bus(bus),
_device(device),
_mode(mode),
_frequency(frequency),
- _dev(nullptr)
+ _dev(nullptr),
+ _bus(bus)
{
+ // fill in _device_id fields for a SPI device
+ _device_id.devid_s.bus_type = DeviceBusType_SPI;
+ _device_id.devid_s.bus = bus;
+ _device_id.devid_s.address = (uint8_t)device;
+ // devtype needs to be filled in by the driver
+ _device_id.devid_s.devtype = 0;
}
SPI::~SPI()
@@ -133,26 +139,44 @@ SPI::probe()
int
SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
{
- irqstate_t state;
+ int result;
if ((send == nullptr) && (recv == nullptr))
return -EINVAL;
+ LockMode mode = up_interrupt_context() ? LOCK_NONE : locking_mode;
+
/* lock the bus as required */
- if (!up_interrupt_context()) {
- switch (locking_mode) {
- default:
- case LOCK_PREEMPTION:
- state = irqsave();
- break;
- case LOCK_THREADS:
- SPI_LOCK(_dev, true);
- break;
- case LOCK_NONE:
- break;
+ switch (mode) {
+ default:
+ case LOCK_PREEMPTION:
+ {
+ irqstate_t state = irqsave();
+ result = _transfer(send, recv, len);
+ irqrestore(state);
}
+ break;
+ case LOCK_THREADS:
+ SPI_LOCK(_dev, true);
+ result = _transfer(send, recv, len);
+ SPI_LOCK(_dev, false);
+ break;
+ case LOCK_NONE:
+ result = _transfer(send, recv, len);
+ break;
}
+ return result;
+}
+void
+SPI::set_frequency(uint32_t frequency)
+{
+ _frequency = frequency;
+}
+
+int
+SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
+{
SPI_SETFREQUENCY(_dev, _frequency);
SPI_SETMODE(_dev, _mode);
SPI_SETBITS(_dev, 8);
@@ -164,27 +188,7 @@ SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
/* and clean up */
SPI_SELECT(_dev, _device, false);
- if (!up_interrupt_context()) {
- switch (locking_mode) {
- default:
- case LOCK_PREEMPTION:
- irqrestore(state);
- break;
- case LOCK_THREADS:
- SPI_LOCK(_dev, false);
- break;
- case LOCK_NONE:
- break;
- }
- }
-
return OK;
}
-void
-SPI::set_frequency(uint32_t frequency)
-{
- _frequency = frequency;
-}
-
} // namespace device
diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h
index 299575dc5..1d9837689 100644
--- a/src/drivers/device/spi.h
+++ b/src/drivers/device/spi.h
@@ -124,11 +124,20 @@ protected:
LockMode locking_mode; /**< selected locking mode */
private:
- int _bus;
enum spi_dev_e _device;
enum spi_mode_e _mode;
uint32_t _frequency;
struct spi_dev_s *_dev;
+
+ /* this class does not allow copying */
+ SPI(const SPI&);
+ SPI operator=(const SPI&);
+
+protected:
+ int _bus;
+
+ int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
+
};
} // namespace device
diff --git a/src/drivers/drv_accel.h b/src/drivers/drv_accel.h
index 7d93ed938..1f98d966b 100644
--- a/src/drivers/drv_accel.h
+++ b/src/drivers/drv_accel.h
@@ -81,7 +81,9 @@ struct accel_scale {
/*
* ObjDev tag for raw accelerometer data.
*/
-ORB_DECLARE(sensor_accel);
+ORB_DECLARE(sensor_accel0);
+ORB_DECLARE(sensor_accel1);
+ORB_DECLARE(sensor_accel2);
/*
* ioctl() definitions
diff --git a/src/drivers/drv_baro.h b/src/drivers/drv_baro.h
index e2f0137ae..248b9a73d 100644
--- a/src/drivers/drv_baro.h
+++ b/src/drivers/drv_baro.h
@@ -63,7 +63,8 @@ struct baro_report {
/*
* ObjDev tag for raw barometer data.
*/
-ORB_DECLARE(sensor_baro);
+ORB_DECLARE(sensor_baro0);
+ORB_DECLARE(sensor_baro1);
/*
* ioctl() definitions
diff --git a/src/drivers/drv_device.h b/src/drivers/drv_device.h
index b310beb74..19d55cef3 100644
--- a/src/drivers/drv_device.h
+++ b/src/drivers/drv_device.h
@@ -59,4 +59,11 @@
/** check publication block status */
#define DEVIOCGPUBBLOCK _DEVICEIOC(1)
+/**
+ * Return device ID, to enable matching of configuration parameters
+ * (such as compass offsets) to specific sensors
+ */
+#define DEVIOCGDEVICEID _DEVICEIOC(2)
+
+
#endif /* _DRV_DEVICE_H */
diff --git a/src/drivers/drv_gps.h b/src/drivers/drv_gps.h
index e14f4e00d..76a211000 100644
--- a/src/drivers/drv_gps.h
+++ b/src/drivers/drv_gps.h
@@ -57,7 +57,8 @@
typedef enum {
GPS_DRIVER_MODE_NONE = 0,
GPS_DRIVER_MODE_UBX,
- GPS_DRIVER_MODE_MTK
+ GPS_DRIVER_MODE_MTK,
+ GPS_DRIVER_MODE_ASHTECH
} gps_driver_mode_t;
diff --git a/src/drivers/drv_gyro.h b/src/drivers/drv_gyro.h
index 2ae8c7058..41b013a44 100644
--- a/src/drivers/drv_gyro.h
+++ b/src/drivers/drv_gyro.h
@@ -81,7 +81,9 @@ struct gyro_scale {
/*
* ObjDev tag for raw gyro data.
*/
-ORB_DECLARE(sensor_gyro);
+ORB_DECLARE(sensor_gyro0);
+ORB_DECLARE(sensor_gyro1);
+ORB_DECLARE(sensor_gyro2);
/*
* ioctl() definitions
diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h
index 06107bd3d..5ddf5d08e 100644
--- a/src/drivers/drv_mag.h
+++ b/src/drivers/drv_mag.h
@@ -79,7 +79,15 @@ struct mag_scale {
/*
* ObjDev tag for raw magnetometer data.
*/
-ORB_DECLARE(sensor_mag);
+ORB_DECLARE(sensor_mag0);
+ORB_DECLARE(sensor_mag1);
+ORB_DECLARE(sensor_mag2);
+
+/*
+ * mag device types, for _device_id
+ */
+#define DRV_MAG_DEVTYPE_HMC5883 1
+#define DRV_MAG_DEVTYPE_LSM303D 2
/*
* ioctl() definitions
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index 972573f9f..b10c3e18a 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -95,6 +95,11 @@ __BEGIN_DECLS
#define PWM_LOWEST_MAX 1700
/**
+ * Do not output a channel with this value
+ */
+#define PWM_IGNORE_THIS_CHANNEL UINT16_MAX
+
+/**
* Servo output signal type, value is actual servo output pulse
* width in microseconds.
*/
@@ -112,6 +117,23 @@ struct pwm_output_values {
unsigned channel_count;
};
+
+/**
+ * RC config values for a channel
+ *
+ * This allows for PX4IO_PAGE_RC_CONFIG values to be set without a
+ * param_get() dependency
+ */
+struct pwm_output_rc_config {
+ uint8_t channel;
+ uint16_t rc_min;
+ uint16_t rc_trim;
+ uint16_t rc_max;
+ uint16_t rc_dz;
+ uint16_t rc_assignment;
+ bool rc_reverse;
+};
+
/*
* ORB tag for PWM outputs.
*/
@@ -160,7 +182,7 @@ ORB_DECLARE(output_pwm);
#define DSM2_BIND_PULSES 3 /* DSM_BIND_START ioctl parameter, pulses required to start dsm2 pairing */
#define DSMX_BIND_PULSES 7 /* DSM_BIND_START ioctl parameter, pulses required to start dsmx pairing */
-#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
+#define DSMX8_BIND_PULSES 9 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
/** power up DSM receiver */
#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 11)
@@ -200,7 +222,28 @@ ORB_DECLARE(output_pwm);
#define PWM_SERVO_GET_DISABLE_LOCKDOWN _IOC(_PWM_SERVO_BASE, 22)
/** force safety switch off (to disable use of safety switch) */
-#define PWM_SERVO_SET_FORCE_SAFETY_OFF _IOC(_PWM_SERVO_BASE, 23)
+#define PWM_SERVO_SET_FORCE_SAFETY_OFF _IOC(_PWM_SERVO_BASE, 23)
+
+/** force failsafe mode (failsafe values are set immediately even if failsafe condition not met) */
+#define PWM_SERVO_SET_FORCE_FAILSAFE _IOC(_PWM_SERVO_BASE, 24)
+
+/** make failsafe non-recoverable (termination) if it occurs */
+#define PWM_SERVO_SET_TERMINATION_FAILSAFE _IOC(_PWM_SERVO_BASE, 25)
+
+/** force safety switch on (to enable use of safety switch) */
+#define PWM_SERVO_SET_FORCE_SAFETY_ON _IOC(_PWM_SERVO_BASE, 26)
+
+/** set RC config for a channel. This takes a pointer to pwm_output_rc_config */
+#define PWM_SERVO_SET_RC_CONFIG _IOC(_PWM_SERVO_BASE, 27)
+
+/** set the 'OVERRIDE OK' bit, which allows for RC control on FMU loss */
+#define PWM_SERVO_SET_OVERRIDE_OK _IOC(_PWM_SERVO_BASE, 28)
+
+/** clear the 'OVERRIDE OK' bit, which allows for RC control on FMU loss */
+#define PWM_SERVO_CLEAR_OVERRIDE_OK _IOC(_PWM_SERVO_BASE, 29)
+
+/** setup OVERRIDE_IMMEDIATE behaviour on FMU fail */
+#define PWM_SERVO_SET_OVERRIDE_IMMEDIATE _IOC(_PWM_SERVO_BASE, 30)
/*
*
diff --git a/src/drivers/drv_px4flow.h b/src/drivers/drv_px4flow.h
index bef02d54e..ab640837b 100644
--- a/src/drivers/drv_px4flow.h
+++ b/src/drivers/drv_px4flow.h
@@ -46,25 +46,6 @@
#define PX4FLOW_DEVICE_PATH "/dev/px4flow"
-/**
- * Optical flow in NED body frame in SI units.
- *
- * @see http://en.wikipedia.org/wiki/International_System_of_Units
- */
-struct px4flow_report {
-
- uint64_t timestamp; /**< in microseconds since system start */
-
- int16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */
- int16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */
- float flow_comp_x_m; /**< speed over ground in meters, rotation-compensated */
- float flow_comp_y_m; /**< speed over ground in meters, rotation-compensated */
- float ground_distance_m; /**< Altitude / distance to ground in meters */
- uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */
- uint8_t sensor_id; /**< id of the sensor emitting the flow value */
-
-};
-
/*
* ObjDev tag for px4flow data.
*/
diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h
index e45939b37..0f8362f58 100644
--- a/src/drivers/drv_range_finder.h
+++ b/src/drivers/drv_range_finder.h
@@ -51,6 +51,11 @@ enum RANGE_FINDER_TYPE {
};
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* range finder report structure. Reads from the device must be in multiples of this
* structure.
*/
@@ -64,6 +69,10 @@ struct range_finder_report {
uint8_t valid; /**< 1 == within sensor range, 0 = outside sensor range */
};
+/**
+ * @}
+ */
+
/*
* ObjDev tag for raw range finder data.
*/
diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h
index 20763e265..b249c2a09 100644
--- a/src/drivers/drv_rc_input.h
+++ b/src/drivers/drv_rc_input.h
@@ -68,6 +68,11 @@
#define RC_INPUT_RSSI_MAX 255
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* Input signal type, value is a control position from zero to 100
* percent.
*/
@@ -78,7 +83,8 @@ enum RC_INPUT_SOURCE {
RC_INPUT_SOURCE_PX4FMU_PPM,
RC_INPUT_SOURCE_PX4IO_PPM,
RC_INPUT_SOURCE_PX4IO_SPEKTRUM,
- RC_INPUT_SOURCE_PX4IO_SBUS
+ RC_INPUT_SOURCE_PX4IO_SBUS,
+ RC_INPUT_SOURCE_PX4IO_ST24
};
/**
@@ -141,6 +147,10 @@ struct rc_input_values {
rc_input_t values[RC_INPUT_MAX_CHANNELS];
};
+/**
+ * @}
+ */
+
/*
* ObjDev tag for R/C inputs.
*/
diff --git a/src/drivers/drv_tone_alarm.h b/src/drivers/drv_tone_alarm.h
index b7981e9c4..307f7dbc7 100644
--- a/src/drivers/drv_tone_alarm.h
+++ b/src/drivers/drv_tone_alarm.h
@@ -149,6 +149,8 @@ enum {
TONE_GPS_WARNING_TUNE,
TONE_ARMING_FAILURE_TUNE,
TONE_PARACHUTE_RELEASE_TUNE,
+ TONE_EKF_WARNING_TUNE,
+ TONE_BARO_WARNING_TUNE,
TONE_NUMBER_OF_TUNES
};
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index 2de7063ea..0f77bb805 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -155,7 +155,6 @@ ETSAirspeed::collect()
}
uint16_t diff_pres_pa_raw = val[1] << 8 | val[0];
- uint16_t diff_pres_pa;
if (diff_pres_pa_raw == 0) {
// a zero value means the pressure sensor cannot give us a
// value. We need to return, and not report a value or the
@@ -166,27 +165,22 @@ ETSAirspeed::collect()
return -1;
}
- if (diff_pres_pa_raw < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
- diff_pres_pa = 0;
- } else {
- diff_pres_pa = diff_pres_pa_raw - _diff_pres_offset;
- }
+ // The raw value still should be compensated for the known offset
+ diff_pres_pa_raw -= _diff_pres_offset;
// Track maximum differential pressure measured (so we can work out top speed).
- if (diff_pres_pa > _max_differential_pressure_pa) {
- _max_differential_pressure_pa = diff_pres_pa;
+ if (diff_pres_pa_raw > _max_differential_pressure_pa) {
+ _max_differential_pressure_pa = diff_pres_pa_raw;
}
differential_pressure_s report;
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
- report.differential_pressure_pa = (float)diff_pres_pa;
// XXX we may want to smooth out the readings to remove noise.
- report.differential_pressure_filtered_pa = (float)diff_pres_pa;
- report.differential_pressure_raw_pa = (float)diff_pres_pa_raw;
+ report.differential_pressure_filtered_pa = diff_pres_pa_raw;
+ report.differential_pressure_raw_pa = diff_pres_pa_raw;
report.temperature = -1000.0f;
- report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
if (_airspeed_pub > 0 && !(_pub_blocked)) {
@@ -284,6 +278,9 @@ void info();
/**
* Start the driver.
+ *
+ * This function only returns if the sensor is up and running
+ * or could not be detected successfully.
*/
void
start(int i2c_bus)
@@ -364,7 +361,7 @@ test()
err(1, "immediate read failed");
warnx("single read");
- warnx("diff pressure: %d pa", report.differential_pressure_pa);
+ warnx("diff pressure: %f pa", (double)report.differential_pressure_filtered_pa);
/* start the sensor polling at 2Hz */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
@@ -389,7 +386,7 @@ test()
err(1, "periodic read failed");
warnx("periodic read %u", i);
- warnx("diff pressure: %d pa", report.differential_pressure_pa);
+ warnx("diff pressure: %f pa", (double)report.differential_pressure_filtered_pa);
}
/* reset the sensor polling to its default rate */
diff --git a/src/drivers/ets_airspeed/module.mk b/src/drivers/ets_airspeed/module.mk
index 15346c5c5..8aaaf0ebb 100644
--- a/src/drivers/ets_airspeed/module.mk
+++ b/src/drivers/ets_airspeed/module.mk
@@ -36,6 +36,9 @@
#
MODULE_COMMAND = ets_airspeed
-MODULE_STACKSIZE = 2048
SRCS = ets_airspeed.cpp
+
+MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/frsky_telemetry/frsky_telemetry.c b/src/drivers/frsky_telemetry/frsky_telemetry.c
index 6e0839043..bccdf1190 100644
--- a/src/drivers/frsky_telemetry/frsky_telemetry.c
+++ b/src/drivers/frsky_telemetry/frsky_telemetry.c
@@ -84,7 +84,7 @@ static int frsky_open_uart(const char *uart_name, struct termios *uart_config_or
/* Back up the original UART configuration to restore it after exit */
int termios_state;
if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
- warnx("ERROR get termios config %s: %d\n", uart_name, termios_state);
+ warnx("ERR: tcgetattr%s: %d\n", uart_name, termios_state);
close(uart);
return -1;
}
@@ -100,13 +100,13 @@ static int frsky_open_uart(const char *uart_name, struct termios *uart_config_or
static const speed_t speed = B9600;
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
- warnx("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
+ warnx("ERR: %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
close(uart);
return -1;
}
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
- warnx("ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
+ warnx("ERR: %s (tcsetattr)\n", uart_name);
close(uart);
return -1;
}
@@ -151,9 +151,6 @@ static int frsky_telemetry_thread_main(int argc, char *argv[])
}
}
- /* Print welcome text */
- warnx("FrSky telemetry interface starting...");
-
/* Open UART */
struct termios uart_config_original;
const int uart = frsky_open_uart(device_name, &uart_config_original);
diff --git a/src/drivers/frsky_telemetry/module.mk b/src/drivers/frsky_telemetry/module.mk
index 9a49589ee..78ad6f67e 100644
--- a/src/drivers/frsky_telemetry/module.mk
+++ b/src/drivers/frsky_telemetry/module.mk
@@ -41,3 +41,5 @@ SRCS = frsky_data.c \
frsky_telemetry.c
MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/gps/ashtech.cpp b/src/drivers/gps/ashtech.cpp
new file mode 100644
index 000000000..a2e292de2
--- /dev/null
+++ b/src/drivers/gps/ashtech.cpp
@@ -0,0 +1,641 @@
+#include "ashtech.h"
+
+#include <unistd.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <poll.h>
+#include <math.h>
+#include <string.h>
+#include <assert.h>
+#include <systemlib/err.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/satellite_info.h>
+#include <drivers/drv_hrt.h>
+
+#include <fcntl.h>
+#include <math.h>
+
+ASHTECH::ASHTECH(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info):
+ _fd(fd),
+ _satellite_info(satellite_info),
+ _gps_position(gps_position)
+{
+ decode_init();
+ _decode_state = NME_DECODE_UNINIT;
+ _rx_buffer_bytes = 0;
+}
+
+ASHTECH::~ASHTECH()
+{
+}
+
+/*
+ * All NMEA descriptions are taken from
+ * http://www.trimble.com/OEM_ReceiverHelp/V4.44/en/NMEA-0183messages_MessageOverview.html
+ */
+
+int ASHTECH::handle_message(int len)
+{
+ char * endp;
+
+ if (len < 7) { return 0; }
+
+ int uiCalcComma = 0;
+
+ for (int i = 0 ; i < len; i++) {
+ if (_rx_buffer[i] == ',') { uiCalcComma++; }
+ }
+
+ char *bufptr = (char *)(_rx_buffer + 6);
+
+ if ((memcmp(_rx_buffer + 3, "ZDA,", 3) == 0) && (uiCalcComma == 6)) {
+ /*
+ UTC day, month, and year, and local time zone offset
+ An example of the ZDA message string is:
+
+ $GPZDA,172809.456,12,07,1996,00,00*45
+
+ ZDA message fields
+ Field Meaning
+ 0 Message ID $GPZDA
+ 1 UTC
+ 2 Day, ranging between 01 and 31
+ 3 Month, ranging between 01 and 12
+ 4 Year
+ 5 Local time zone offset from GMT, ranging from 00 through 13 hours
+ 6 Local time zone offset from GMT, ranging from 00 through 59 minutes
+ 7 The checksum data, always begins with *
+ Fields 5 and 6 together yield the total offset. For example, if field 5 is -5 and field 6 is +15, local time is 5 hours and 15 minutes earlier than GMT.
+ */
+ double ashtech_time = 0.0;
+ int day = 0, month = 0, year = 0, local_time_off_hour __attribute__((unused)) = 0, local_time_off_min __attribute__((unused)) = 0;
+
+ if (bufptr && *(++bufptr) != ',') { ashtech_time = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { day = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { month = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { year = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { local_time_off_hour = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { local_time_off_min = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+
+ int ashtech_hour = ashtech_time / 10000;
+ int ashtech_minute = (ashtech_time - ashtech_hour * 10000) / 100;
+ double ashtech_sec = ashtech_time - ashtech_hour * 10000 - ashtech_minute * 100;
+ /*
+ * convert to unix timestamp
+ */
+ struct tm timeinfo;
+ timeinfo.tm_year = year - 1900;
+ timeinfo.tm_mon = month - 1;
+ timeinfo.tm_mday = day;
+ timeinfo.tm_hour = ashtech_hour;
+ timeinfo.tm_min = ashtech_minute;
+ timeinfo.tm_sec = int(ashtech_sec);
+ time_t epoch = mktime(&timeinfo);
+
+ _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
+ _gps_position->time_gps_usec += (uint64_t)((ashtech_sec - int(ashtech_sec)) * 1e6);
+ _gps_position->timestamp_time = hrt_absolute_time();
+ }
+
+ else if ((memcmp(_rx_buffer + 3, "GGA,", 3) == 0) && (uiCalcComma == 14)) {
+ /*
+ Time, position, and fix related data
+ An example of the GBS message string is:
+
+ $GPGGA,172814.0,3723.46587704,N,12202.26957864,W,2,6,1.2,18.893,M,-25.669,M,2.0,0031*4F
+
+ Note - The data string exceeds the ASHTECH standard length.
+ GGA message fields
+ Field Meaning
+ 0 Message ID $GPGGA
+ 1 UTC of position fix
+ 2 Latitude
+ 3 Direction of latitude:
+ N: North
+ S: South
+ 4 Longitude
+ 5 Direction of longitude:
+ E: East
+ W: West
+ 6 GPS Quality indicator:
+ 0: Fix not valid
+ 1: GPS fix
+ 2: Differential GPS fix, OmniSTAR VBS
+ 4: Real-Time Kinematic, fixed integers
+ 5: Real-Time Kinematic, float integers, OmniSTAR XP/HP or Location RTK
+ 7 Number of SVs in use, range from 00 through to 24+
+ 8 HDOP
+ 9 Orthometric height (MSL reference)
+ 10 M: unit of measure for orthometric height is meters
+ 11 Geoid separation
+ 12 M: geoid separation measured in meters
+ 13 Age of differential GPS data record, Type 1 or Type 9. Null field when DGPS is not used.
+ 14 Reference station ID, range 0000-4095. A null field when any reference station ID is selected and no corrections are received1.
+ 15
+ The checksum data, always begins with *
+ Note - If a user-defined geoid model, or an inclined
+ */
+ double ashtech_time __attribute__((unused)) = 0.0, lat = 0.0, lon = 0.0, alt = 0.0;
+ int num_of_sv __attribute__((unused)) = 0, fix_quality = 0;
+ double hdop __attribute__((unused)) = 99.9;
+ char ns = '?', ew = '?';
+
+ if (bufptr && *(++bufptr) != ',') { ashtech_time = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { lat = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { ns = *(bufptr++); }
+
+ if (bufptr && *(++bufptr) != ',') { lon = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { ew = *(bufptr++); }
+
+ if (bufptr && *(++bufptr) != ',') { fix_quality = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { num_of_sv = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { hdop = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { alt = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (ns == 'S') {
+ lat = -lat;
+ }
+
+ if (ew == 'W') {
+ lon = -lon;
+ }
+
+ _gps_position->lat = (int(lat * 0.01) + (lat * 0.01 - int(lat * 0.01)) * 100.0 / 60.0) * 10000000;
+ _gps_position->lon = (int(lon * 0.01) + (lon * 0.01 - int(lon * 0.01)) * 100.0 / 60.0) * 10000000;
+ _gps_position->alt = alt * 1000;
+ _rate_count_lat_lon++;
+
+ if (fix_quality <= 0) {
+ _gps_position->fix_type = 0;
+
+ } else {
+ /*
+ * in this NMEA message float integers (value 5) mode has higher value than fixed integers (value 4), whereas it provides lower quality,
+ * and since value 3 is not being used, I "moved" value 5 to 3 to add it to _gps_position->fix_type
+ */
+ if (fix_quality == 5) { fix_quality = 3; }
+
+ /*
+ * fix quality 1 means just a normal 3D fix, so I'm subtracting 1 here. This way we'll have 3 for auto, 4 for DGPS, 5 for floats, 6 for fixed.
+ */
+ _gps_position->fix_type = 3 + fix_quality - 1;
+ }
+
+ _gps_position->timestamp_position = hrt_absolute_time();
+
+ _gps_position->vel_m_s = 0; /**< GPS ground speed (m/s) */
+ _gps_position->vel_n_m_s = 0; /**< GPS ground speed in m/s */
+ _gps_position->vel_e_m_s = 0; /**< GPS ground speed in m/s */
+ _gps_position->vel_d_m_s = 0; /**< GPS ground speed in m/s */
+ _gps_position->cog_rad =
+ 0; /**< Course over ground (NOT heading, but direction of movement) in rad, -PI..PI */
+ _gps_position->vel_ned_valid = true; /**< Flag to indicate if NED speed is valid */
+ _gps_position->c_variance_rad = 0.1;
+ _gps_position->timestamp_velocity = hrt_absolute_time();
+ return 1;
+
+ } else if ((memcmp(_rx_buffer, "$PASHR,POS,", 11) == 0) && (uiCalcComma == 18)) {
+ /*
+ Example $PASHR,POS,2,10,125410.00,5525.8138702,N,03833.9587380,E,131.555,1.0,0.0,0.007,-0.001,2.0,1.0,1.7,1.0,*34
+
+ $PASHR,POS,d1,d2,m3,m4,c5,m6,c7,f8,f9,f10,f11,f12,f13,f14,f15,f16,s17*cc
+ Parameter Description Range
+ d1 Position mode 0: standalone
+ 1: differential
+ 2: RTK float
+ 3: RTK fixed
+ 5: Dead reckoning
+ 9: SBAS (see NPT setting)
+ d2 Number of satellite used in position fix 0-99
+ m3 Current UTC time of position fix (hhmmss.ss) 000000.00-235959.99
+ m4 Latitude of position (ddmm.mmmmmm) 0-90 degrees 00-59.9999999 minutes
+ c5 Latitude sector N, S
+ m6 Longitude of position (dddmm.mmmmmm) 0-180 degrees 00-59.9999999 minutes
+ c7 Longitude sector E,W
+ f8 Altitude above ellipsoid +9999.000
+ f9 Differential age (data link age), seconds 0.0-600.0
+ f10 True track/course over ground in degrees 0.0-359.9
+ f11 Speed over ground in knots 0.0-999.9
+ f12 Vertical velocity in decimeters per second +999.9
+ f13 PDOP 0-99.9
+ f14 HDOP 0-99.9
+ f15 VDOP 0-99.9
+ f16 TDOP 0-99.9
+ s17 Reserved no data
+ *cc Checksum
+ */
+ bufptr = (char *)(_rx_buffer + 10);
+
+ /*
+ * Ashtech would return empty space as coordinate (lat, lon or alt) if it doesn't have a fix yet
+ */
+ int coordinatesFound = 0;
+ double ashtech_time __attribute__((unused)) = 0.0, lat = 0.0, lon = 0.0, alt = 0.0;
+ int num_of_sv __attribute__((unused)) = 0, fix_quality = 0;
+ double track_true = 0.0, ground_speed = 0.0 , age_of_corr __attribute__((unused)) = 0.0;
+ double hdop __attribute__((unused)) = 99.9, vdop __attribute__((unused)) = 99.9, pdop __attribute__((unused)) = 99.9, tdop __attribute__((unused)) = 99.9, vertic_vel = 0.0;
+ char ns = '?', ew = '?';
+
+ if (bufptr && *(++bufptr) != ',') { fix_quality = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { num_of_sv = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { ashtech_time = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') {
+ /*
+ * if a coordinate is skipped (i.e. no fix), it either won't get into this block (two commas in a row)
+ * or strtod won't find anything and endp will point exactly where bufptr is. The same is for lon and alt.
+ */
+ lat = strtod(bufptr, &endp);
+ if (bufptr != endp) {coordinatesFound++;}
+ bufptr = endp;
+ }
+
+ if (bufptr && *(++bufptr) != ',') { ns = *(bufptr++); }
+
+ if (bufptr && *(++bufptr) != ',') {
+ lon = strtod(bufptr, &endp);
+ if (bufptr != endp) {coordinatesFound++;}
+ bufptr = endp;
+ }
+
+ if (bufptr && *(++bufptr) != ',') { ew = *(bufptr++); }
+
+ if (bufptr && *(++bufptr) != ',') {
+ alt = strtod(bufptr, &endp);
+ if (bufptr != endp) {coordinatesFound++;}
+ bufptr = endp;
+ }
+
+ if (bufptr && *(++bufptr) != ',') { age_of_corr = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { track_true = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { ground_speed = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { vertic_vel = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { pdop = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { hdop = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { vdop = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { tdop = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (ns == 'S') {
+ lat = -lat;
+ }
+
+ if (ew == 'W') {
+ lon = -lon;
+ }
+
+ _gps_position->lat = (int(lat * 0.01) + (lat * 0.01 - int(lat * 0.01)) * 100.0 / 60.0) * 10000000;
+ _gps_position->lon = (int(lon * 0.01) + (lon * 0.01 - int(lon * 0.01)) * 100.0 / 60.0) * 10000000;
+ _gps_position->alt = alt * 1000;
+ _rate_count_lat_lon++;
+
+ if (coordinatesFound < 3) {
+ _gps_position->fix_type = 0;
+
+ } else {
+ _gps_position->fix_type = 3 + fix_quality;
+ }
+
+ _gps_position->timestamp_position = hrt_absolute_time();
+
+ double track_rad = track_true * M_PI / 180.0;
+
+ double velocity_ms = ground_speed / 1.9438445; /** knots to m/s */
+ double velocity_north = velocity_ms * cos(track_rad);
+ double velocity_east = velocity_ms * sin(track_rad);
+
+ _gps_position->vel_m_s = velocity_ms; /**< GPS ground speed (m/s) */
+ _gps_position->vel_n_m_s = velocity_north; /**< GPS ground speed in m/s */
+ _gps_position->vel_e_m_s = velocity_east; /**< GPS ground speed in m/s */
+ _gps_position->vel_d_m_s = -vertic_vel; /**< GPS ground speed in m/s */
+ _gps_position->cog_rad =
+ track_rad; /**< Course over ground (NOT heading, but direction of movement) in rad, -PI..PI */
+ _gps_position->vel_ned_valid = true; /**< Flag to indicate if NED speed is valid */
+ _gps_position->c_variance_rad = 0.1;
+ _gps_position->timestamp_velocity = hrt_absolute_time();
+ return 1;
+
+ } else if ((memcmp(_rx_buffer + 3, "GST,", 3) == 0) && (uiCalcComma == 8)) {
+ /*
+ Position error statistics
+ An example of the GST message string is:
+
+ $GPGST,172814.0,0.006,0.023,0.020,273.6,0.023,0.020,0.031*6A
+
+ The Talker ID ($--) will vary depending on the satellite system used for the position solution:
+
+ $GP - GPS only
+ $GL - GLONASS only
+ $GN - Combined
+ GST message fields
+ Field Meaning
+ 0 Message ID $GPGST
+ 1 UTC of position fix
+ 2 RMS value of the pseudorange residuals; includes carrier phase residuals during periods of RTK (float) and RTK (fixed) processing
+ 3 Error ellipse semi-major axis 1 sigma error, in meters
+ 4 Error ellipse semi-minor axis 1 sigma error, in meters
+ 5 Error ellipse orientation, degrees from true north
+ 6 Latitude 1 sigma error, in meters
+ 7 Longitude 1 sigma error, in meters
+ 8 Height 1 sigma error, in meters
+ 9 The checksum data, always begins with *
+ */
+ double ashtech_time __attribute__((unused)) = 0.0, lat_err = 0.0, lon_err = 0.0, alt_err = 0.0;
+ double min_err __attribute__((unused)) = 0.0, maj_err __attribute__((unused)) = 0.0, deg_from_north __attribute__((unused)) = 0.0, rms_err __attribute__((unused)) = 0.0;
+
+ if (bufptr && *(++bufptr) != ',') { ashtech_time = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { rms_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { maj_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { min_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { deg_from_north = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { lat_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { lon_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { alt_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ _gps_position->eph = sqrt(lat_err * lat_err + lon_err * lon_err);
+ _gps_position->epv = alt_err;
+
+ _gps_position->s_variance_m_s = 0;
+ _gps_position->timestamp_variance = hrt_absolute_time();
+
+ } else if ((memcmp(_rx_buffer + 3, "GSV,", 3) == 0)) {
+ /*
+ The GSV message string identifies the number of SVs in view, the PRN numbers, elevations, azimuths, and SNR values. An example of the GSV message string is:
+
+ $GPGSV,4,1,13,02,02,213,,03,-3,000,,11,00,121,,14,13,172,05*67
+
+ GSV message fields
+ Field Meaning
+ 0 Message ID $GPGSV
+ 1 Total number of messages of this type in this cycle
+ 2 Message number
+ 3 Total number of SVs visible
+ 4 SV PRN number
+ 5 Elevation, in degrees, 90 maximum
+ 6 Azimuth, degrees from True North, 000 through 359
+ 7 SNR, 00 through 99 dB (null when not tracking)
+ 8-11 Information about second SV, same format as fields 4 through 7
+ 12-15 Information about third SV, same format as fields 4 through 7
+ 16-19 Information about fourth SV, same format as fields 4 through 7
+ 20 The checksum data, always begins with *
+ */
+ /*
+ * currently process only gps, because do not know what
+ * Global satellite ID I should use for non GPS sats
+ */
+ bool bGPS = false;
+
+ if (memcmp(_rx_buffer, "$GP", 3) != 0) {
+ return 0;
+
+ } else {
+ bGPS = true;
+ }
+
+ int all_msg_num = 0, this_msg_num = 0, tot_sv_visible = 0;
+ struct gsv_sat {
+ int svid;
+ int elevation;
+ int azimuth;
+ int snr;
+ } sat[4];
+ memset(sat, 0, sizeof(sat));
+
+ if (bufptr && *(++bufptr) != ',') { all_msg_num = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { this_msg_num = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { tot_sv_visible = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if ((this_msg_num < 1) || (this_msg_num > all_msg_num)) {
+ return 0;
+ }
+
+ if ((this_msg_num == 0) && (bGPS == true)) {
+ memset(_satellite_info->svid, 0, sizeof(_satellite_info->svid));
+ memset(_satellite_info->used, 0, sizeof(_satellite_info->used));
+ memset(_satellite_info->snr, 0, sizeof(_satellite_info->snr));
+ memset(_satellite_info->elevation, 0, sizeof(_satellite_info->elevation));
+ memset(_satellite_info->azimuth, 0, sizeof(_satellite_info->azimuth));
+ }
+
+ int end = 4;
+
+ if (this_msg_num == all_msg_num) {
+ end = tot_sv_visible - (this_msg_num - 1) * 4;
+ _gps_position->satellites_used = tot_sv_visible;
+ _satellite_info->count = SAT_INFO_MAX_SATELLITES;
+ _satellite_info->timestamp = hrt_absolute_time();
+ }
+
+ for (int y = 0 ; y < end ; y++) {
+ if (bufptr && *(++bufptr) != ',') { sat[y].svid = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { sat[y].elevation = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { sat[y].azimuth = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { sat[y].snr = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ _satellite_info->svid[y + (this_msg_num - 1) * 4] = sat[y].svid;
+ _satellite_info->used[y + (this_msg_num - 1) * 4] = ((sat[y].snr > 0) ? true : false);
+ _satellite_info->snr[y + (this_msg_num - 1) * 4] = sat[y].snr;
+ _satellite_info->elevation[y + (this_msg_num - 1) * 4] = sat[y].elevation;
+ _satellite_info->azimuth[y + (this_msg_num - 1) * 4] = sat[y].azimuth;
+ }
+ }
+
+ return 0;
+}
+
+
+int ASHTECH::receive(unsigned timeout)
+{
+ {
+ /* poll descriptor */
+ pollfd fds[1];
+ fds[0].fd = _fd;
+ fds[0].events = POLLIN;
+
+ uint8_t buf[32];
+
+ /* timeout additional to poll */
+ uint64_t time_started = hrt_absolute_time();
+
+ int j = 0;
+ ssize_t bytes_count = 0;
+
+ while (true) {
+
+ /* pass received bytes to the packet decoder */
+ while (j < bytes_count) {
+ int l = 0;
+
+ if ((l = parse_char(buf[j])) > 0) {
+ /* return to configure during configuration or to the gps driver during normal work
+ * if a packet has arrived */
+ if (handle_message(l) > 0) {
+ return 1;
+ }
+ }
+
+ /* in case we keep trying but only get crap from GPS */
+ if (time_started + timeout * 1000 * 2 < hrt_absolute_time()) {
+ return -1;
+ }
+
+ j++;
+ }
+
+ /* everything is read */
+ j = bytes_count = 0;
+
+ /* then poll for new data */
+ int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), timeout * 2);
+
+ if (ret < 0) {
+ /* something went wrong when polling */
+ return -1;
+
+ } else if (ret == 0) {
+ /* Timeout */
+ return -1;
+
+ } else if (ret > 0) {
+ /* if we have new data from GPS, go handle it */
+ if (fds[0].revents & POLLIN) {
+ /*
+ * We are here because poll says there is some data, so this
+ * won't block even on a blocking device. If more bytes are
+ * available, we'll go back to poll() again...
+ */
+ bytes_count = ::read(_fd, buf, sizeof(buf));
+ }
+ }
+ }
+ }
+
+}
+#define HEXDIGIT_CHAR(d) ((char)((d) + (((d) < 0xA) ? '0' : 'A'-0xA)))
+
+int ASHTECH::parse_char(uint8_t b)
+{
+ int iRet = 0;
+
+ switch (_decode_state) {
+ /* First, look for sync1 */
+ case NME_DECODE_UNINIT:
+ if (b == '$') {
+ _decode_state = NME_DECODE_GOT_SYNC1;
+ _rx_buffer_bytes = 0;
+ _rx_buffer[_rx_buffer_bytes++] = b;
+ }
+
+ break;
+
+ case NME_DECODE_GOT_SYNC1:
+ if (b == '$') {
+ _decode_state = NME_DECODE_GOT_SYNC1;
+ _rx_buffer_bytes = 0;
+
+ } else if (b == '*') {
+ _decode_state = NME_DECODE_GOT_ASTERIKS;
+ }
+
+ if (_rx_buffer_bytes >= (sizeof(_rx_buffer) - 5)) {
+ _decode_state = NME_DECODE_UNINIT;
+ _rx_buffer_bytes = 0;
+
+ } else {
+ _rx_buffer[_rx_buffer_bytes++] = b;
+ }
+
+ break;
+
+ case NME_DECODE_GOT_ASTERIKS:
+ _rx_buffer[_rx_buffer_bytes++] = b;
+ _decode_state = NME_DECODE_GOT_FIRST_CS_BYTE;
+ break;
+
+ case NME_DECODE_GOT_FIRST_CS_BYTE:
+ _rx_buffer[_rx_buffer_bytes++] = b;
+ uint8_t checksum = 0;
+ uint8_t *buffer = _rx_buffer + 1;
+ uint8_t *bufend = _rx_buffer + _rx_buffer_bytes - 3;
+
+ for (; buffer < bufend; buffer++) { checksum ^= *buffer; }
+
+ if ((HEXDIGIT_CHAR(checksum >> 4) == *(_rx_buffer + _rx_buffer_bytes - 2)) &&
+ (HEXDIGIT_CHAR(checksum & 0x0F) == *(_rx_buffer + _rx_buffer_bytes - 1))) {
+ iRet = _rx_buffer_bytes;
+ }
+
+ _decode_state = NME_DECODE_UNINIT;
+ _rx_buffer_bytes = 0;
+ break;
+ }
+
+ return iRet;
+}
+
+void ASHTECH::decode_init(void)
+{
+
+}
+
+/*
+ * ashtech board configuration script
+ */
+
+const char comm[] = "$PASHS,POP,20\r\n"\
+ "$PASHS,NME,ZDA,B,ON,3\r\n"\
+ "$PASHS,NME,GGA,B,OFF\r\n"\
+ "$PASHS,NME,GST,B,ON,3\r\n"\
+ "$PASHS,NME,POS,B,ON,0.05\r\n"\
+ "$PASHS,NME,GSV,B,ON,3\r\n"\
+ "$PASHS,SPD,A,8\r\n"\
+ "$PASHS,SPD,B,9\r\n";
+
+int ASHTECH::configure(unsigned &baudrate)
+{
+ /* try different baudrates */
+ const unsigned baudrates_to_try[] = {9600, 38400, 19200, 57600, 115200};
+
+
+ for (unsigned int baud_i = 0; baud_i < sizeof(baudrates_to_try) / sizeof(baudrates_to_try[0]); baud_i++) {
+ baudrate = baudrates_to_try[baud_i];
+ set_baudrate(_fd, baudrate);
+ write(_fd, (uint8_t *)comm, sizeof(comm));
+ }
+
+ set_baudrate(_fd, 115200);
+ return 0;
+}
diff --git a/src/drivers/gps/ashtech.h b/src/drivers/gps/ashtech.h
new file mode 100644
index 000000000..6ba522b9c
--- /dev/null
+++ b/src/drivers/gps/ashtech.h
@@ -0,0 +1,96 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013. All rights reserved.
+ * Author: Boriskin Aleksey <a.d.boriskin@gmail.com>
+ * Kistanov Alexander <akistanov@gramant.ru>
+ *
+ * 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 ASHTECH protocol definitions */
+
+#ifndef ASHTECH_H_
+#define ASHTECH_H_
+
+#include "gps_helper.h"
+
+#ifndef RECV_BUFFER_SIZE
+#define RECV_BUFFER_SIZE 512
+
+#define SAT_INFO_MAX_SATELLITES 20
+#endif
+
+
+class ASHTECH : public GPS_Helper
+{
+ enum ashtech_decode_state_t {
+ NME_DECODE_UNINIT,
+ NME_DECODE_GOT_SYNC1,
+ NME_DECODE_GOT_ASTERIKS,
+ NME_DECODE_GOT_FIRST_CS_BYTE
+ };
+
+ int _fd;
+ struct satellite_info_s *_satellite_info;
+ struct vehicle_gps_position_s *_gps_position;
+ int ashtechlog_fd;
+
+ ashtech_decode_state_t _decode_state;
+ uint8_t _rx_buffer[RECV_BUFFER_SIZE];
+ uint16_t _rx_buffer_bytes;
+ bool _parse_error; /** parse error flag */
+ char *_parse_pos; /** parse position */
+
+ bool _gsv_in_progress; /**< Indicates that gsv data parsing is in progress */
+ /* int _satellites_count; **< Number of satellites info parsed. */
+ uint8_t count; /**< Number of satellites in satellite info */
+ uint8_t svid[SAT_INFO_MAX_SATELLITES]; /**< Space vehicle ID [1..255], see scheme below */
+ uint8_t used[SAT_INFO_MAX_SATELLITES]; /**< 0: Satellite not used, 1: used for navigation */
+ uint8_t elevation[SAT_INFO_MAX_SATELLITES]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
+ uint8_t azimuth[SAT_INFO_MAX_SATELLITES]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
+ uint8_t snr[SAT_INFO_MAX_SATELLITES]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */
+
+public:
+ ASHTECH(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info);
+ ~ASHTECH();
+ int receive(unsigned timeout);
+ int configure(unsigned &baudrate);
+ void decode_init(void);
+ int handle_message(int len);
+ int parse_char(uint8_t b);
+ /** Read int ASHTECH parameter */
+ int32_t read_int();
+ /** Read float ASHTECH parameter */
+ double read_float();
+ /** Read char ASHTECH parameter */
+ char read_char();
+
+};
+
+#endif /* ASHTECH_H_ */
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index 5342ccf78..47c907bd3 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -63,11 +63,13 @@
#include <drivers/drv_gps.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/satellite_info.h>
#include <board_config.h>
#include "ubx.h"
#include "mtk.h"
+#include "ashtech.h"
#define TIMEOUT_5HZ 500
@@ -79,10 +81,18 @@
#endif
static const int ERROR = -1;
+/* class for dynamic allocation of satellite info data */
+class GPS_Sat_Info
+{
+public:
+ struct satellite_info_s _data;
+};
+
+
class GPS : public device::CDev
{
public:
- GPS(const char *uart_path, bool fake_gps);
+ GPS(const char *uart_path, bool fake_gps, bool enable_sat_info);
virtual ~GPS();
virtual int init();
@@ -100,14 +110,17 @@ private:
int _serial_fd; ///< serial interface to GPS
unsigned _baudrate; ///< current baudrate
char _port[20]; ///< device / serial port path
- volatile int _task; //< worker task
+ volatile int _task; ///< worker task
bool _healthy; ///< flag to signal if the GPS is ok
- bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed
+ bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed
bool _mode_changed; ///< flag that the GPS mode has changed
gps_driver_mode_t _mode; ///< current mode
GPS_Helper *_Helper; ///< instance of GPS parser
- struct vehicle_gps_position_s _report; ///< uORB topic for gps position
- orb_advert_t _report_pub; ///< uORB pub for gps position
+ GPS_Sat_Info *_Sat_Info; ///< instance of GPS sat info data object
+ struct vehicle_gps_position_s _report_gps_pos; ///< uORB topic for gps position
+ orb_advert_t _report_gps_pos_pub; ///< uORB pub for gps position
+ struct satellite_info_s *_p_report_sat_info; ///< pointer to uORB topic for satellite info
+ orb_advert_t _report_sat_info_pub; ///< uORB pub for satellite info
float _rate; ///< position update rate
bool _fake_gps; ///< fake gps output
@@ -115,7 +128,7 @@ private:
/**
* Try to configure the GPS, handle outgoing communication to the GPS
*/
- void config();
+ void config();
/**
* Trampoline to the worker task
@@ -154,14 +167,17 @@ GPS *g_dev;
}
-GPS::GPS(const char *uart_path, bool fake_gps) :
+GPS::GPS(const char *uart_path, bool fake_gps, bool enable_sat_info) :
CDev("gps", GPS_DEVICE_PATH),
_task_should_exit(false),
_healthy(false),
_mode_changed(false),
_mode(GPS_DRIVER_MODE_UBX),
_Helper(nullptr),
- _report_pub(-1),
+ _Sat_Info(nullptr),
+ _report_gps_pos_pub(-1),
+ _p_report_sat_info(nullptr),
+ _report_sat_info_pub(-1),
_rate(0.0f),
_fake_gps(fake_gps)
{
@@ -172,7 +188,14 @@ GPS::GPS(const char *uart_path, bool fake_gps) :
/* we need this potentially before it could be set in task_main */
g_dev = this;
- memset(&_report, 0, sizeof(_report));
+ memset(&_report_gps_pos, 0, sizeof(_report_gps_pos));
+
+ /* create satellite info data object if requested */
+ if (enable_sat_info) {
+ _Sat_Info = new(GPS_Sat_Info);
+ _p_report_sat_info = &_Sat_Info->_data;
+ memset(_p_report_sat_info, 0, sizeof(*_p_report_sat_info));
+ }
_debug_enabled = true;
}
@@ -207,7 +230,7 @@ GPS::init()
/* start the GPS driver worker task */
_task = task_spawn_cmd("gps", SCHED_DEFAULT,
- SCHED_PRIORITY_SLOW_DRIVER, 2000, (main_t)&GPS::task_main_trampoline, nullptr);
+ SCHED_PRIORITY_SLOW_DRIVER, 1500, (main_t)&GPS::task_main_trampoline, nullptr);
if (_task < 0) {
warnx("task start failed: %d", errno);
@@ -251,7 +274,6 @@ GPS::task_main_trampoline(void *arg)
void
GPS::task_main()
{
- log("starting");
/* open the serial port */
_serial_fd = ::open(_port, O_RDWR);
@@ -271,33 +293,32 @@ GPS::task_main()
if (_fake_gps) {
- _report.timestamp_position = hrt_absolute_time();
- _report.lat = (int32_t)47.378301e7f;
- _report.lon = (int32_t)8.538777e7f;
- _report.alt = (int32_t)1200e3f;
- _report.timestamp_variance = hrt_absolute_time();
- _report.s_variance_m_s = 10.0f;
- _report.p_variance_m = 10.0f;
- _report.c_variance_rad = 0.1f;
- _report.fix_type = 3;
- _report.eph_m = 0.9f;
- _report.epv_m = 1.8f;
- _report.timestamp_velocity = hrt_absolute_time();
- _report.vel_n_m_s = 0.0f;
- _report.vel_e_m_s = 0.0f;
- _report.vel_d_m_s = 0.0f;
- _report.vel_m_s = sqrtf(_report.vel_n_m_s * _report.vel_n_m_s + _report.vel_e_m_s * _report.vel_e_m_s + _report.vel_d_m_s * _report.vel_d_m_s);
- _report.cog_rad = 0.0f;
- _report.vel_ned_valid = true;
+ _report_gps_pos.timestamp_position = hrt_absolute_time();
+ _report_gps_pos.lat = (int32_t)47.378301e7f;
+ _report_gps_pos.lon = (int32_t)8.538777e7f;
+ _report_gps_pos.alt = (int32_t)1200e3f;
+ _report_gps_pos.timestamp_variance = hrt_absolute_time();
+ _report_gps_pos.s_variance_m_s = 10.0f;
+ _report_gps_pos.c_variance_rad = 0.1f;
+ _report_gps_pos.fix_type = 3;
+ _report_gps_pos.eph = 0.9f;
+ _report_gps_pos.epv = 1.8f;
+ _report_gps_pos.timestamp_velocity = hrt_absolute_time();
+ _report_gps_pos.vel_n_m_s = 0.0f;
+ _report_gps_pos.vel_e_m_s = 0.0f;
+ _report_gps_pos.vel_d_m_s = 0.0f;
+ _report_gps_pos.vel_m_s = sqrtf(_report_gps_pos.vel_n_m_s * _report_gps_pos.vel_n_m_s + _report_gps_pos.vel_e_m_s * _report_gps_pos.vel_e_m_s + _report_gps_pos.vel_d_m_s * _report_gps_pos.vel_d_m_s);
+ _report_gps_pos.cog_rad = 0.0f;
+ _report_gps_pos.vel_ned_valid = true;
//no time and satellite information simulated
if (!(_pub_blocked)) {
- if (_report_pub > 0) {
- orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+ if (_report_gps_pos_pub > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
} else {
- _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ _report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
}
}
@@ -313,11 +334,15 @@ GPS::task_main()
switch (_mode) {
case GPS_DRIVER_MODE_UBX:
- _Helper = new UBX(_serial_fd, &_report);
+ _Helper = new UBX(_serial_fd, &_report_gps_pos, _p_report_sat_info);
break;
case GPS_DRIVER_MODE_MTK:
- _Helper = new MTK(_serial_fd, &_report);
+ _Helper = new MTK(_serial_fd, &_report_gps_pos);
+ break;
+
+ case GPS_DRIVER_MODE_ASHTECH:
+ _Helper = new ASHTECH(_serial_fd, &_report_gps_pos, _p_report_sat_info);
break;
default:
@@ -332,20 +357,33 @@ GPS::task_main()
// GPS is obviously detected successfully, reset statistics
_Helper->reset_update_rates();
- while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) {
+ int helper_ret;
+ while ((helper_ret = _Helper->receive(TIMEOUT_5HZ)) > 0 && !_task_should_exit) {
// lock();
/* opportunistic publishing - else invalid data would end up on the bus */
if (!(_pub_blocked)) {
- if (_report_pub > 0) {
- orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+ if (helper_ret & 1) {
+ if (_report_gps_pos_pub > 0) {
+ orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos);
+
+ } else {
+ _report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos);
+ }
+ }
+ if (_p_report_sat_info && (helper_ret & 2)) {
+ if (_report_sat_info_pub > 0) {
+ orb_publish(ORB_ID(satellite_info), _report_sat_info_pub, _p_report_sat_info);
- } else {
- _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ } else {
+ _report_sat_info_pub = orb_advertise(ORB_ID(satellite_info), _p_report_sat_info);
+ }
}
}
- last_rate_count++;
+ if (helper_ret & 1) { // consider only pos info updates for rate calculation */
+ last_rate_count++;
+ }
/* measure update rate every 5 seconds */
if (hrt_absolute_time() - last_rate_measurement > RATE_MEASUREMENT_PERIOD) {
@@ -357,7 +395,7 @@ GPS::task_main()
}
if (!_healthy) {
- char *mode_str = "unknown";
+ const char *mode_str = "unknown";
switch (_mode) {
case GPS_DRIVER_MODE_UBX:
@@ -368,6 +406,10 @@ GPS::task_main()
mode_str = "MTK";
break;
+ case GPS_DRIVER_MODE_ASHTECH:
+ mode_str = "ASHTECH";
+ break;
+
default:
break;
}
@@ -395,6 +437,10 @@ GPS::task_main()
break;
case GPS_DRIVER_MODE_MTK:
+ _mode = GPS_DRIVER_MODE_ASHTECH;
+ break;
+
+ case GPS_DRIVER_MODE_ASHTECH:
_mode = GPS_DRIVER_MODE_UBX;
break;
@@ -441,17 +487,24 @@ GPS::print_info()
warnx("protocol: MTK");
break;
+ case GPS_DRIVER_MODE_ASHTECH:
+ warnx("protocol: ASHTECH");
+ break;
+
default:
break;
}
warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK");
-
- if (_report.timestamp_position != 0) {
- warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report.fix_type,
- _report.satellites_visible, (double)(hrt_absolute_time() - _report.timestamp_position) / 1000.0f);
- warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt);
- warnx("eph: %.2fm, epv: %.2fm", (double)_report.eph_m, (double)_report.epv_m);
+ warnx("sat info: %s", (_p_report_sat_info != nullptr) ? "enabled" : "disabled");
+
+ if (_report_gps_pos.timestamp_position != 0) {
+ warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report_gps_pos.fix_type,
+ _report_gps_pos.satellites_used, (double)(hrt_absolute_time() - _report_gps_pos.timestamp_position) / 1000.0);
+ warnx("lat: %d, lon: %d, alt: %d", _report_gps_pos.lat, _report_gps_pos.lon, _report_gps_pos.alt);
+ warnx("vel: %.2fm/s, %.2fm/s, %.2fm/s", (double)_report_gps_pos.vel_n_m_s,
+ (double)_report_gps_pos.vel_e_m_s, (double)_report_gps_pos.vel_d_m_s);
+ warnx("eph: %.2fm, epv: %.2fm", (double)_report_gps_pos.eph, (double)_report_gps_pos.epv);
warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate());
warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate());
warnx("rate publication:\t%6.2f Hz", (double)_rate);
@@ -469,7 +522,7 @@ namespace gps
GPS *g_dev;
-void start(const char *uart_path, bool fake_gps);
+void start(const char *uart_path, bool fake_gps, bool enable_sat_info);
void stop();
void test();
void reset();
@@ -479,7 +532,7 @@ void info();
* Start the driver.
*/
void
-start(const char *uart_path, bool fake_gps)
+start(const char *uart_path, bool fake_gps, bool enable_sat_info)
{
int fd;
@@ -487,7 +540,7 @@ start(const char *uart_path, bool fake_gps)
errx(1, "already started");
/* create the driver */
- g_dev = new GPS(uart_path, fake_gps);
+ g_dev = new GPS(uart_path, fake_gps, enable_sat_info);
if (g_dev == nullptr)
goto fail;
@@ -578,8 +631,9 @@ gps_main(int argc, char *argv[])
{
/* set to default */
- char *device_name = GPS_DEFAULT_UART_PORT;
+ const char *device_name = GPS_DEFAULT_UART_PORT;
bool fake_gps = false;
+ bool enable_sat_info = false;
/*
* Start/load the driver.
@@ -601,7 +655,13 @@ gps_main(int argc, char *argv[])
fake_gps = true;
}
- gps::start(device_name, fake_gps);
+ /* Detect sat info option */
+ for (int i = 2; i < argc; i++) {
+ if (!strcmp(argv[i], "-s"))
+ enable_sat_info = true;
+ }
+
+ gps::start(device_name, fake_gps, enable_sat_info);
}
if (!strcmp(argv[1], "stop"))
@@ -626,5 +686,5 @@ gps_main(int argc, char *argv[])
gps::info();
out:
- errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n][-f]");
+ errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n][-f][-s]");
}
diff --git a/src/drivers/gps/gps_helper.h b/src/drivers/gps/gps_helper.h
index d14a95afe..3623397b2 100644
--- a/src/drivers/gps/gps_helper.h
+++ b/src/drivers/gps/gps_helper.h
@@ -62,8 +62,8 @@ protected:
uint8_t _rate_count_lat_lon;
uint8_t _rate_count_vel;
- float _rate_lat_lon;
- float _rate_vel;
+ float _rate_lat_lon = 0.0f;
+ float _rate_vel = 0.0f;
uint64_t _interval_rate_start;
};
diff --git a/src/drivers/gps/module.mk b/src/drivers/gps/module.mk
index eb382c4b2..4f99b0d3b 100644
--- a/src/drivers/gps/module.mk
+++ b/src/drivers/gps/module.mk
@@ -40,6 +40,9 @@ MODULE_COMMAND = gps
SRCS = gps.cpp \
gps_helper.cpp \
mtk.cpp \
+ ashtech.cpp \
ubx.cpp
MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp
index 680f00d97..c4f4f7bec 100644
--- a/src/drivers/gps/mtk.cpp
+++ b/src/drivers/gps/mtk.cpp
@@ -251,19 +251,19 @@ MTK::handle_message(gps_mtk_packet_t &packet)
_gps_position->lon = 0;
// Indicate this data is not usable and bail out
- _gps_position->eph_m = 1000.0f;
- _gps_position->epv_m = 1000.0f;
+ _gps_position->eph = 1000.0f;
+ _gps_position->epv = 1000.0f;
_gps_position->fix_type = 0;
return;
}
_gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm
_gps_position->fix_type = packet.fix_type;
- _gps_position->eph_m = packet.hdop / 100.0f; // from cm to m
- _gps_position->epv_m = _gps_position->eph_m; // unknown in mtk custom mode, so we cheat with eph
+ _gps_position->eph = packet.hdop / 100.0f; // from cm to m
+ _gps_position->epv = _gps_position->eph; // unknown in mtk custom mode, so we cheat with eph
_gps_position->vel_m_s = ((float)packet.ground_speed) * 1e-2f; // from cm/s to m/s
_gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad
- _gps_position->satellites_visible = packet.satellites;
+ _gps_position->satellites_used = packet.satellites;
/* convert time and date information to unix timestamp */
struct tm timeinfo; //TODO: test this conversion
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index c143eeb0c..b0eb4ab66 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,14 +34,18 @@
/**
* @file ubx.cpp
*
- * U-Blox protocol implementation. Following u-blox 6/7 Receiver Description
+ * U-Blox protocol implementation. Following u-blox 6/7/8 Receiver Description
* including Prototol Specification.
*
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
*
+ * @author Hannes Delago
+ * (rework, add ubx7+ compatibility)
+ *
* @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
+ * @see http://www.u-blox.com/images/downloads/Product_Docs/u-bloxM8-V15_ReceiverDescriptionProtocolSpec_Public_%28UBX-13003221%29.pdf
*/
#include <assert.h>
@@ -55,24 +59,44 @@
#include <systemlib/err.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/satellite_info.h>
#include <drivers/drv_hrt.h>
#include "ubx.h"
-#define UBX_CONFIG_TIMEOUT 200 // ms, timeout for waiting ACK
-#define UBX_PACKET_TIMEOUT 2 // ms, if now data during this delay assume that full update received
+#define UBX_CONFIG_TIMEOUT 200 // ms, timeout for waiting ACK
+#define UBX_PACKET_TIMEOUT 2 // ms, if now data during this delay assume that full update received
#define UBX_WAIT_BEFORE_READ 20 // ms, wait before reading to save read() calls
-#define DISABLE_MSG_INTERVAL 1000000 // us, try to disable message with this interval
+#define DISABLE_MSG_INTERVAL 1000000 // us, try to disable message with this interval
+
+#define MIN(X,Y) ((X) < (Y) ? (X) : (Y))
+#define SWAP16(X) ((((X) >> 8) & 0x00ff) | (((X) << 8) & 0xff00))
+
+#define FNV1_32_INIT ((uint32_t)0x811c9dc5) // init value for FNV1 hash algorithm
+#define FNV1_32_PRIME ((uint32_t)0x01000193) // magic prime for FNV1 hash algorithm
+
-UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) :
+/**** Trace macros, disable for production builds */
+#define UBX_TRACE_PARSER(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* decoding progress in parse_char() */
+#define UBX_TRACE_RXMSG(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* Rx msgs in payload_rx_done() */
+#define UBX_TRACE_SVINFO(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* NAV-SVINFO processing (debug use only, will cause rx buffer overflows) */
+
+/**** Warning macros, disable to save memory */
+#define UBX_WARN(s, ...) {warnx(s, ## __VA_ARGS__);}
+
+
+UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info) :
_fd(fd),
_gps_position(gps_position),
+ _satellite_info(satellite_info),
_configured(false),
- _waiting_for_ack(false),
+ _ack_state(UBX_ACK_IDLE),
_got_posllh(false),
_got_velned(false),
- _got_timeutc(false),
- _disable_cmd_last(0)
+ _disable_cmd_last(0),
+ _ack_waiting_msg(0),
+ _ubx_version(0),
+ _use_nav_pvt(false)
{
decode_init();
}
@@ -86,182 +110,179 @@ UBX::configure(unsigned &baudrate)
{
_configured = false;
/* try different baudrates */
- const unsigned baudrates_to_try[] = {9600, 38400, 19200, 57600, 115200};
+ const unsigned baudrates[] = {9600, 38400, 19200, 57600, 115200};
- int baud_i;
+ unsigned baud_i;
- for (baud_i = 0; baud_i < 5; baud_i++) {
- baudrate = baudrates_to_try[baud_i];
+ for (baud_i = 0; baud_i < sizeof(baudrates) / sizeof(baudrates[0]); baud_i++) {
+ baudrate = baudrates[baud_i];
set_baudrate(_fd, baudrate);
+ /* flush input and wait for at least 20 ms silence */
+ decode_init();
+ receive(20);
+ decode_init();
+
/* Send a CFG-PRT message to set the UBX protocol for in and out
- * and leave the baudrate as it is, we just want an ACK-ACK from this
- */
- type_gps_bin_cfg_prt_packet_t cfg_prt_packet;
- /* Set everything else of the packet to 0, otherwise the module wont accept it */
- memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet));
-
- _message_class_needed = UBX_CLASS_CFG;
- _message_id_needed = UBX_MESSAGE_CFG_PRT;
-
- /* Define the package contents, don't change the baudrate */
- cfg_prt_packet.clsID = UBX_CLASS_CFG;
- cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT;
- cfg_prt_packet.length = UBX_CFG_PRT_LENGTH;
- cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID;
- cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE;
- cfg_prt_packet.baudRate = baudrate;
- cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK;
- cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
-
- send_config_packet(_fd, (uint8_t *)&cfg_prt_packet, sizeof(cfg_prt_packet));
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ * and leave the baudrate as it is, we just want an ACK-ACK for this */
+ memset(&_buf.payload_tx_cfg_prt, 0, sizeof(_buf.payload_tx_cfg_prt));
+ _buf.payload_tx_cfg_prt.portID = UBX_TX_CFG_PRT_PORTID;
+ _buf.payload_tx_cfg_prt.mode = UBX_TX_CFG_PRT_MODE;
+ _buf.payload_tx_cfg_prt.baudRate = baudrate;
+ _buf.payload_tx_cfg_prt.inProtoMask = UBX_TX_CFG_PRT_INPROTOMASK;
+ _buf.payload_tx_cfg_prt.outProtoMask = UBX_TX_CFG_PRT_OUTPROTOMASK;
+
+ send_message(UBX_MSG_CFG_PRT, _buf.raw, sizeof(_buf.payload_tx_cfg_prt));
+
+ if (wait_for_ack(UBX_MSG_CFG_PRT, UBX_CONFIG_TIMEOUT, false) < 0) {
/* try next baudrate */
continue;
}
/* Send a CFG-PRT message again, this time change the baudrate */
+ memset(&_buf.payload_tx_cfg_prt, 0, sizeof(_buf.payload_tx_cfg_prt));
+ _buf.payload_tx_cfg_prt.portID = UBX_TX_CFG_PRT_PORTID;
+ _buf.payload_tx_cfg_prt.mode = UBX_TX_CFG_PRT_MODE;
+ _buf.payload_tx_cfg_prt.baudRate = UBX_TX_CFG_PRT_BAUDRATE;
+ _buf.payload_tx_cfg_prt.inProtoMask = UBX_TX_CFG_PRT_INPROTOMASK;
+ _buf.payload_tx_cfg_prt.outProtoMask = UBX_TX_CFG_PRT_OUTPROTOMASK;
- cfg_prt_packet.clsID = UBX_CLASS_CFG;
- cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT;
- cfg_prt_packet.length = UBX_CFG_PRT_LENGTH;
- cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID;
- cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE;
- cfg_prt_packet.baudRate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
- cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK;
- cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
-
- send_config_packet(_fd, (uint8_t *)&cfg_prt_packet, sizeof(cfg_prt_packet));
+ send_message(UBX_MSG_CFG_PRT, _buf.raw, sizeof(_buf.payload_tx_cfg_prt));
/* no ACK is expected here, but read the buffer anyway in case we actually get an ACK */
- wait_for_ack(UBX_CONFIG_TIMEOUT);
+ wait_for_ack(UBX_MSG_CFG_PRT, UBX_CONFIG_TIMEOUT, false);
- if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) {
- set_baudrate(_fd, UBX_CFG_PRT_PAYLOAD_BAUDRATE);
- baudrate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
+ if (UBX_TX_CFG_PRT_BAUDRATE != baudrate) {
+ set_baudrate(_fd, UBX_TX_CFG_PRT_BAUDRATE);
+ baudrate = UBX_TX_CFG_PRT_BAUDRATE;
}
/* at this point we have correct baudrate on both ends */
break;
}
- if (baud_i >= 5) {
- return 1;
+ if (baud_i >= sizeof(baudrates) / sizeof(baudrates[0])) {
+ return 1; // connection and/or baudrate detection failed
}
- /* send a CFG-RATE message to define update rate */
- type_gps_bin_cfg_rate_packet_t cfg_rate_packet;
- memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet));
+ /* Send a CFG-RATE message to define update rate */
+ memset(&_buf.payload_tx_cfg_rate, 0, sizeof(_buf.payload_tx_cfg_rate));
+ _buf.payload_tx_cfg_rate.measRate = UBX_TX_CFG_RATE_MEASINTERVAL;
+ _buf.payload_tx_cfg_rate.navRate = UBX_TX_CFG_RATE_NAVRATE;
+ _buf.payload_tx_cfg_rate.timeRef = UBX_TX_CFG_RATE_TIMEREF;
- _message_class_needed = UBX_CLASS_CFG;
- _message_id_needed = UBX_MESSAGE_CFG_RATE;
+ send_message(UBX_MSG_CFG_RATE, _buf.raw, sizeof(_buf.payload_tx_cfg_rate));
- cfg_rate_packet.clsID = UBX_CLASS_CFG;
- cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE;
- cfg_rate_packet.length = UBX_CFG_RATE_LENGTH;
- cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASINTERVAL;
- cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE;
- cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF;
-
- send_config_packet(_fd, (uint8_t *)&cfg_rate_packet, sizeof(cfg_rate_packet));
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("CFG FAIL: RATE");
+ if (wait_for_ack(UBX_MSG_CFG_RATE, UBX_CONFIG_TIMEOUT, true) < 0) {
return 1;
}
/* send a NAV5 message to set the options for the internal filter */
- type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet;
- memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet));
+ memset(&_buf.payload_tx_cfg_nav5, 0, sizeof(_buf.payload_tx_cfg_nav5));
+ _buf.payload_tx_cfg_nav5.mask = UBX_TX_CFG_NAV5_MASK;
+ _buf.payload_tx_cfg_nav5.dynModel = UBX_TX_CFG_NAV5_DYNMODEL;
+ _buf.payload_tx_cfg_nav5.fixMode = UBX_TX_CFG_NAV5_FIXMODE;
+
+ send_message(UBX_MSG_CFG_NAV5, _buf.raw, sizeof(_buf.payload_tx_cfg_nav5));
- _message_class_needed = UBX_CLASS_CFG;
- _message_id_needed = UBX_MESSAGE_CFG_NAV5;
+ if (wait_for_ack(UBX_MSG_CFG_NAV5, UBX_CONFIG_TIMEOUT, true) < 0) {
+ return 1;
+ }
- cfg_nav5_packet.clsID = UBX_CLASS_CFG;
- cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5;
- cfg_nav5_packet.length = UBX_CFG_NAV5_LENGTH;
- cfg_nav5_packet.mask = UBX_CFG_NAV5_PAYLOAD_MASK;
- cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL;
- cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE;
+#ifdef UBX_CONFIGURE_SBAS
+ /* send a SBAS message to set the SBAS options */
+ memset(&_buf.payload_tx_cfg_sbas, 0, sizeof(_buf.payload_tx_cfg_sbas));
+ _buf.payload_tx_cfg_sbas.mode = UBX_TX_CFG_SBAS_MODE;
- send_config_packet(_fd, (uint8_t *)&cfg_nav5_packet, sizeof(cfg_nav5_packet));
+ send_message(UBX_MSG_CFG_SBAS, _buf.raw, sizeof(_buf.payload_tx_cfg_sbas));
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("CFG FAIL: NAV5");
+ if (wait_for_ack(UBX_MSG_CFG_SBAS, UBX_CONFIG_TIMEOUT, true) < 0) {
return 1;
}
+#endif
/* configure message rates */
/* the last argument is divisor for measurement rate (set by CFG RATE), i.e. 1 means 5Hz */
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_POSLLH, 1);
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: NAV POSLLH");
- return 1;
+ /* try to set rate for NAV-PVT */
+ /* (implemented for ubx7+ modules only, use NAV-SOL, NAV-POSLLH, NAV-VELNED and NAV-TIMEUTC for ubx6) */
+ configure_message_rate(UBX_MSG_NAV_PVT, 1);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
+ _use_nav_pvt = false;
+ } else {
+ _use_nav_pvt = true;
}
+ UBX_WARN("%susing NAV-PVT", _use_nav_pvt ? "" : "not ");
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, 1);
+ if (!_use_nav_pvt) {
+ configure_message_rate(UBX_MSG_NAV_TIMEUTC, 5);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
+ return 1;
+ }
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: NAV TIMEUTC");
- return 1;
- }
+ configure_message_rate(UBX_MSG_NAV_POSLLH, 1);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
+ return 1;
+ }
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL, 1);
+ configure_message_rate(UBX_MSG_NAV_SOL, 1);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
+ return 1;
+ }
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: NAV SOL");
- return 1;
+ configure_message_rate(UBX_MSG_NAV_VELNED, 1);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
+ return 1;
+ }
}
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED, 1);
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: NAV VELNED");
+ configure_message_rate(UBX_MSG_NAV_SVINFO, (_satellite_info != nullptr) ? 5 : 0);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
return 1;
}
- configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5);
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: NAV SVINFO");
+ configure_message_rate(UBX_MSG_MON_HW, 1);
+ if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) {
return 1;
}
- configure_message_rate(UBX_CLASS_MON, UBX_MESSAGE_MON_HW, 1);
-
- if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("MSG CFG FAIL: MON HW");
- return 1;
- }
+ /* request module version information by sending an empty MON-VER message */
+ send_message(UBX_MSG_MON_VER, nullptr, 0);
_configured = true;
return 0;
}
-int
-UBX::wait_for_ack(unsigned timeout)
+int // -1 = NAK, error or timeout, 0 = ACK
+UBX::wait_for_ack(const uint16_t msg, const unsigned timeout, const bool report)
{
- _waiting_for_ack = true;
- uint64_t time_started = hrt_absolute_time();
+ int ret = -1;
- while (hrt_absolute_time() < time_started + timeout * 1000) {
- if (receive(timeout) > 0) {
- if (!_waiting_for_ack) {
- return 1;
- }
+ _ack_state = UBX_ACK_WAITING;
+ _ack_waiting_msg = msg; // memorize sent msg class&ID for ACK check
+
+ hrt_abstime time_started = hrt_absolute_time();
+
+ while ((_ack_state == UBX_ACK_WAITING) && (hrt_absolute_time() < time_started + timeout * 1000)) {
+ receive(timeout);
+ }
+ if (_ack_state == UBX_ACK_GOT_ACK) {
+ ret = 0; // ACK received ok
+ } else if (report) {
+ if (_ack_state == UBX_ACK_GOT_NAK) {
+ UBX_WARN("ubx msg 0x%04x NAK", SWAP16((unsigned)msg));
} else {
- return -1; // timeout or error receiving, or NAK
+ UBX_WARN("ubx msg 0x%04x ACK timeout", SWAP16((unsigned)msg));
}
}
- return -1; // timeout
+ _ack_state = UBX_ACK_IDLE;
+ return ret;
}
-int
-UBX::receive(unsigned timeout)
+int // -1 = error, 0 = no message handled, 1 = message handled, 2 = sat info message handled
+UBX::receive(const unsigned timeout)
{
/* poll descriptor */
pollfd fds[1];
@@ -275,17 +296,17 @@ UBX::receive(unsigned timeout)
ssize_t count = 0;
- bool handled = false;
+ int handled = 0;
while (true) {
- bool ready_to_return = _configured ? (_got_posllh && _got_velned && _got_timeutc) : handled;
+ bool ready_to_return = _configured ? (_got_posllh && _got_velned) : handled;
/* poll for new data, wait for only UBX_PACKET_TIMEOUT (2ms) if something already received */
int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), ready_to_return ? UBX_PACKET_TIMEOUT : timeout);
if (ret < 0) {
/* something went wrong when polling */
- warnx("poll error");
+ UBX_WARN("ubx poll() err");
return -1;
} else if (ret == 0) {
@@ -293,8 +314,7 @@ UBX::receive(unsigned timeout)
if (ready_to_return) {
_got_posllh = false;
_got_velned = false;
- _got_timeutc = false;
- return 1;
+ return handled;
} else {
return -1;
@@ -314,440 +334,675 @@ UBX::receive(unsigned timeout)
/* pass received bytes to the packet decoder */
for (int i = 0; i < count; i++) {
- if (parse_char(buf[i]) > 0) {
- if (handle_message() > 0)
- handled = true;
- }
+ handled |= parse_char(buf[i]);
}
}
}
/* abort after timeout if no useful packets received */
if (time_started + timeout * 1000 < hrt_absolute_time()) {
- warnx("timeout - no useful messages");
return -1;
}
}
}
-int
-UBX::parse_char(uint8_t b)
+int // 0 = decoding, 1 = message handled, 2 = sat info message handled
+UBX::parse_char(const uint8_t b)
{
+ int ret = 0;
+
switch (_decode_state) {
- /* First, look for sync1 */
- case UBX_DECODE_UNINIT:
- if (b == UBX_SYNC1) {
- _decode_state = UBX_DECODE_GOT_SYNC1;
- }
+ /* Expecting Sync1 */
+ case UBX_DECODE_SYNC1:
+ if (b == UBX_SYNC1) { // Sync1 found --> expecting Sync2
+ UBX_TRACE_PARSER("\nA");
+ _decode_state = UBX_DECODE_SYNC2;
+ }
break;
- /* Second, look for sync2 */
- case UBX_DECODE_GOT_SYNC1:
- if (b == UBX_SYNC2) {
- _decode_state = UBX_DECODE_GOT_SYNC2;
+ /* Expecting Sync2 */
+ case UBX_DECODE_SYNC2:
+ if (b == UBX_SYNC2) { // Sync2 found --> expecting Class
+ UBX_TRACE_PARSER("B");
+ _decode_state = UBX_DECODE_CLASS;
- } else {
- /* Second start symbol was wrong, reset state machine */
+ } else { // Sync1 not followed by Sync2: reset parser
decode_init();
- /* don't return error, it can be just false sync1 */
}
+ break;
+ /* Expecting Class */
+ case UBX_DECODE_CLASS:
+ UBX_TRACE_PARSER("C");
+ add_byte_to_checksum(b); // checksum is calculated for everything except Sync and Checksum bytes
+ _rx_msg = b;
+ _decode_state = UBX_DECODE_ID;
break;
- /* Now look for class */
- case UBX_DECODE_GOT_SYNC2:
- /* everything except sync1 and sync2 needs to be added to the checksum */
+ /* Expecting ID */
+ case UBX_DECODE_ID:
+ UBX_TRACE_PARSER("D");
add_byte_to_checksum(b);
- _message_class = b;
- _decode_state = UBX_DECODE_GOT_CLASS;
+ _rx_msg |= b << 8;
+ _decode_state = UBX_DECODE_LENGTH1;
break;
- case UBX_DECODE_GOT_CLASS:
+ /* Expecting first length byte */
+ case UBX_DECODE_LENGTH1:
+ UBX_TRACE_PARSER("E");
add_byte_to_checksum(b);
- _message_id = b;
- _decode_state = UBX_DECODE_GOT_MESSAGEID;
+ _rx_payload_length = b;
+ _decode_state = UBX_DECODE_LENGTH2;
break;
- case UBX_DECODE_GOT_MESSAGEID:
+ /* Expecting second length byte */
+ case UBX_DECODE_LENGTH2:
+ UBX_TRACE_PARSER("F");
add_byte_to_checksum(b);
- _payload_size = b; //this is the first length byte
- _decode_state = UBX_DECODE_GOT_LENGTH1;
+ _rx_payload_length |= b << 8; // calculate payload size
+ if (payload_rx_init() != 0) { // start payload reception
+ // payload will not be handled, discard message
+ decode_init();
+ } else {
+ _decode_state = (_rx_payload_length > 0) ? UBX_DECODE_PAYLOAD : UBX_DECODE_CHKSUM1;
+ }
break;
- case UBX_DECODE_GOT_LENGTH1:
+ /* Expecting payload */
+ case UBX_DECODE_PAYLOAD:
+ UBX_TRACE_PARSER(".");
add_byte_to_checksum(b);
- _payload_size += b << 8; // here comes the second byte of length
- _decode_state = UBX_DECODE_GOT_LENGTH2;
+ switch (_rx_msg) {
+ case UBX_MSG_NAV_SVINFO:
+ ret = payload_rx_add_nav_svinfo(b); // add a NAV-SVINFO payload byte
+ break;
+ case UBX_MSG_MON_VER:
+ ret = payload_rx_add_mon_ver(b); // add a MON-VER payload byte
+ break;
+ default:
+ ret = payload_rx_add(b); // add a payload byte
+ break;
+ }
+ if (ret < 0) {
+ // payload not handled, discard message
+ decode_init();
+ } else if (ret > 0) {
+ // payload complete, expecting checksum
+ _decode_state = UBX_DECODE_CHKSUM1;
+ } else {
+ // expecting more payload, stay in state UBX_DECODE_PAYLOAD
+ }
+ ret = 0;
break;
- case UBX_DECODE_GOT_LENGTH2:
+ /* Expecting first checksum byte */
+ case UBX_DECODE_CHKSUM1:
+ if (_rx_ck_a != b) {
+ UBX_WARN("ubx checksum err");
+ decode_init();
+ } else {
+ _decode_state = UBX_DECODE_CHKSUM2;
+ }
+ break;
- /* Add to checksum if not yet at checksum byte */
- if (_rx_count < _payload_size)
- add_byte_to_checksum(b);
+ /* Expecting second checksum byte */
+ case UBX_DECODE_CHKSUM2:
+ if (_rx_ck_b != b) {
+ UBX_WARN("ubx checksum err");
+ } else {
+ ret = payload_rx_done(); // finish payload processing
+ }
+ decode_init();
+ break;
- _rx_buffer[_rx_count] = b;
+ default:
+ break;
+ }
- /* once the payload has arrived, we can process the information */
- if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes
- /* compare checksum */
- if (_rx_ck_a == _rx_buffer[_rx_count - 1] && _rx_ck_b == _rx_buffer[_rx_count]) {
- decode_init();
- return 1; // message received successfully
+ return ret;
+}
- } else {
- warnx("checksum wrong");
- decode_init();
- return -1;
- }
+/**
+ * Start payload rx
+ */
+int // -1 = abort, 0 = continue
+UBX::payload_rx_init()
+{
+ int ret = 0;
- } else if (_rx_count < RECV_BUFFER_SIZE) {
- _rx_count++;
+ _rx_state = UBX_RXMSG_HANDLE; // handle by default
+
+ switch (_rx_msg) {
+ case UBX_MSG_NAV_PVT:
+ if ( (_rx_payload_length != UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7) /* u-blox 7 msg format */
+ && (_rx_payload_length != UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8)) /* u-blox 8+ msg format */
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else if (!_use_nav_pvt)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if not using NAV-PVT
+ break;
- } else {
- warnx("buffer full");
- decode_init();
- return -1;
- }
+ case UBX_MSG_NAV_POSLLH:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_nav_posllh_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else if (_use_nav_pvt)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead
+ break;
+
+ case UBX_MSG_NAV_SOL:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_nav_sol_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else if (_use_nav_pvt)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead
+ break;
+
+ case UBX_MSG_NAV_TIMEUTC:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_nav_timeutc_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else if (_use_nav_pvt)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead
+ break;
+
+ case UBX_MSG_NAV_SVINFO:
+ if (_satellite_info == nullptr)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if sat info not requested
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else
+ memset(_satellite_info, 0, sizeof(*_satellite_info)); // initialize sat info
+ break;
+
+ case UBX_MSG_NAV_VELNED:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_nav_velned_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ else if (_use_nav_pvt)
+ _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead
+ break;
+
+ case UBX_MSG_MON_VER:
+ break; // unconditionally handle this message
+
+ case UBX_MSG_MON_HW:
+ if ( (_rx_payload_length != sizeof(ubx_payload_rx_mon_hw_ubx6_t)) /* u-blox 6 msg format */
+ && (_rx_payload_length != sizeof(ubx_payload_rx_mon_hw_ubx7_t))) /* u-blox 7+ msg format */
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (!_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured
+ break;
+
+ case UBX_MSG_ACK_ACK:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_ack_ack_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if _configured
+ break;
+ case UBX_MSG_ACK_NAK:
+ if (_rx_payload_length != sizeof(ubx_payload_rx_ack_nak_t))
+ _rx_state = UBX_RXMSG_ERROR_LENGTH;
+ else if (_configured)
+ _rx_state = UBX_RXMSG_IGNORE; // ignore if _configured
break;
default:
+ _rx_state = UBX_RXMSG_DISABLE; // disable all other messages
+ break;
+ }
+
+ switch (_rx_state) {
+ case UBX_RXMSG_HANDLE: // handle message
+ case UBX_RXMSG_IGNORE: // ignore message but don't report error
+ ret = 0;
+ break;
+
+ case UBX_RXMSG_DISABLE: // disable unexpected messages
+ UBX_WARN("ubx msg 0x%04x len %u unexpected", SWAP16((unsigned)_rx_msg), (unsigned)_rx_payload_length);
+
+ {
+ hrt_abstime t = hrt_absolute_time();
+
+ if (t > _disable_cmd_last + DISABLE_MSG_INTERVAL) {
+ /* don't attempt for every message to disable, some might not be disabled */
+ _disable_cmd_last = t;
+ UBX_WARN("ubx disabling msg 0x%04x", SWAP16((unsigned)_rx_msg));
+ configure_message_rate(_rx_msg, 0);
+ }
+ }
+
+ ret = -1; // return error, abort handling this message
+ break;
+
+ case UBX_RXMSG_ERROR_LENGTH: // error: invalid length
+ UBX_WARN("ubx msg 0x%04x invalid len %u", SWAP16((unsigned)_rx_msg), (unsigned)_rx_payload_length);
+ ret = -1; // return error, abort handling this message
+ break;
+
+ default: // invalid message state
+ UBX_WARN("ubx internal err1");
+ ret = -1; // return error, abort handling this message
break;
}
- return 0; // message decoding in progress
+ return ret;
}
+/**
+ * Add payload rx byte
+ */
+int // -1 = error, 0 = ok, 1 = payload completed
+UBX::payload_rx_add(const uint8_t b)
+{
+ int ret = 0;
+ _buf.raw[_rx_payload_index] = b;
-int
-UBX::handle_message()
+ if (++_rx_payload_index >= _rx_payload_length) {
+ ret = 1; // payload received completely
+ }
+
+ return ret;
+}
+
+/**
+ * Add NAV-SVINFO payload rx byte
+ */
+int // -1 = error, 0 = ok, 1 = payload completed
+UBX::payload_rx_add_nav_svinfo(const uint8_t b)
{
int ret = 0;
- if (_configured) {
- /* handle only info messages when configured */
- switch (_message_class) {
- case UBX_CLASS_NAV:
- switch (_message_id) {
- case UBX_MESSAGE_NAV_POSLLH: {
- // printf("GOT NAV_POSLLH\n");
- gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer;
-
- _gps_position->lat = packet->lat;
- _gps_position->lon = packet->lon;
- _gps_position->alt = packet->height_msl;
- _gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m
- _gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m
- _gps_position->timestamp_position = hrt_absolute_time();
-
- _rate_count_lat_lon++;
-
- _got_posllh = true;
- ret = 1;
- break;
- }
+ if (_rx_payload_index < sizeof(ubx_payload_rx_nav_svinfo_part1_t)) {
+ // Fill Part 1 buffer
+ _buf.raw[_rx_payload_index] = b;
+ } else {
+ if (_rx_payload_index == sizeof(ubx_payload_rx_nav_svinfo_part1_t)) {
+ // Part 1 complete: decode Part 1 buffer
+ _satellite_info->count = MIN(_buf.payload_rx_nav_svinfo_part1.numCh, SAT_INFO_MAX_SATELLITES);
+ UBX_TRACE_SVINFO("SVINFO len %u numCh %u\n", (unsigned)_rx_payload_length, (unsigned)_buf.payload_rx_nav_svinfo_part1.numCh);
+ }
+ if (_rx_payload_index < sizeof(ubx_payload_rx_nav_svinfo_part1_t) + _satellite_info->count * sizeof(ubx_payload_rx_nav_svinfo_part2_t)) {
+ // Still room in _satellite_info: fill Part 2 buffer
+ unsigned buf_index = (_rx_payload_index - sizeof(ubx_payload_rx_nav_svinfo_part1_t)) % sizeof(ubx_payload_rx_nav_svinfo_part2_t);
+ _buf.raw[buf_index] = b;
+ if (buf_index == sizeof(ubx_payload_rx_nav_svinfo_part2_t) - 1) {
+ // Part 2 complete: decode Part 2 buffer
+ unsigned sat_index = (_rx_payload_index - sizeof(ubx_payload_rx_nav_svinfo_part1_t)) / sizeof(ubx_payload_rx_nav_svinfo_part2_t);
+ _satellite_info->used[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.flags & 0x01);
+ _satellite_info->snr[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.cno);
+ _satellite_info->elevation[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.elev);
+ _satellite_info->azimuth[sat_index] = (uint8_t)((float)_buf.payload_rx_nav_svinfo_part2.azim * 255.0f / 360.0f);
+ _satellite_info->svid[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.svid);
+ UBX_TRACE_SVINFO("SVINFO #%02u used %u snr %3u elevation %3u azimuth %3u svid %3u\n",
+ (unsigned)sat_index + 1,
+ (unsigned)_satellite_info->used[sat_index],
+ (unsigned)_satellite_info->snr[sat_index],
+ (unsigned)_satellite_info->elevation[sat_index],
+ (unsigned)_satellite_info->azimuth[sat_index],
+ (unsigned)_satellite_info->svid[sat_index]
+ );
+ }
+ }
+ }
- case UBX_MESSAGE_NAV_SOL: {
- // printf("GOT NAV_SOL\n");
- gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer;
+ if (++_rx_payload_index >= _rx_payload_length) {
+ ret = 1; // payload received completely
+ }
- _gps_position->fix_type = packet->gpsFix;
- _gps_position->s_variance_m_s = (float)packet->sAcc * 1e-2f; // from cm/s to m/s
- _gps_position->p_variance_m = (float)packet->pAcc * 1e-2f; // from cm to m
- _gps_position->timestamp_variance = hrt_absolute_time();
+ return ret;
+}
- ret = 1;
- break;
- }
+/**
+ * Add MON-VER payload rx byte
+ */
+int // -1 = error, 0 = ok, 1 = payload completed
+UBX::payload_rx_add_mon_ver(const uint8_t b)
+{
+ int ret = 0;
+
+ if (_rx_payload_index < sizeof(ubx_payload_rx_mon_ver_part1_t)) {
+ // Fill Part 1 buffer
+ _buf.raw[_rx_payload_index] = b;
+ } else {
+ if (_rx_payload_index == sizeof(ubx_payload_rx_mon_ver_part1_t)) {
+ // Part 1 complete: decode Part 1 buffer and calculate hash for SW&HW version strings
+ _ubx_version = fnv1_32_str(_buf.payload_rx_mon_ver_part1.swVersion, FNV1_32_INIT);
+ _ubx_version = fnv1_32_str(_buf.payload_rx_mon_ver_part1.hwVersion, _ubx_version);
+ UBX_WARN("VER hash 0x%08x", _ubx_version);
+ UBX_WARN("VER hw \"%10s\"", _buf.payload_rx_mon_ver_part1.hwVersion);
+ UBX_WARN("VER sw \"%30s\"", _buf.payload_rx_mon_ver_part1.swVersion);
+ }
+ // fill Part 2 buffer
+ unsigned buf_index = (_rx_payload_index - sizeof(ubx_payload_rx_mon_ver_part1_t)) % sizeof(ubx_payload_rx_mon_ver_part2_t);
+ _buf.raw[buf_index] = b;
+ if (buf_index == sizeof(ubx_payload_rx_mon_ver_part2_t) - 1) {
+ // Part 2 complete: decode Part 2 buffer
+ UBX_WARN("VER ext \" %30s\"", _buf.payload_rx_mon_ver_part2.extension);
+ }
+ }
+
+ if (++_rx_payload_index >= _rx_payload_length) {
+ ret = 1; // payload received completely
+ }
- case UBX_MESSAGE_NAV_TIMEUTC: {
- // printf("GOT NAV_TIMEUTC\n");
- gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer;
+ return ret;
+}
+
+/**
+ * Finish payload rx
+ */
+int // 0 = no message handled, 1 = message handled, 2 = sat info message handled
+UBX::payload_rx_done(void)
+{
+ int ret = 0;
+
+ // return if no message handled
+ if (_rx_state != UBX_RXMSG_HANDLE) {
+ return ret;
+ }
+
+ // handle message
+ switch (_rx_msg) {
+
+ case UBX_MSG_NAV_PVT:
+ UBX_TRACE_RXMSG("Rx NAV-PVT\n");
+
+ _gps_position->fix_type = _buf.payload_rx_nav_pvt.fixType;
+ _gps_position->satellites_used = _buf.payload_rx_nav_pvt.numSV;
+
+ _gps_position->lat = _buf.payload_rx_nav_pvt.lat;
+ _gps_position->lon = _buf.payload_rx_nav_pvt.lon;
+ _gps_position->alt = _buf.payload_rx_nav_pvt.hMSL;
+
+ _gps_position->eph = (float)_buf.payload_rx_nav_pvt.hAcc * 1e-3f;
+ _gps_position->epv = (float)_buf.payload_rx_nav_pvt.vAcc * 1e-3f;
+ _gps_position->s_variance_m_s = (float)_buf.payload_rx_nav_pvt.sAcc * 1e-3f;
+
+ _gps_position->vel_m_s = (float)_buf.payload_rx_nav_pvt.gSpeed * 1e-3f;
- /* convert to unix timestamp */
- struct tm timeinfo;
- timeinfo.tm_year = packet->year - 1900;
- timeinfo.tm_mon = packet->month - 1;
- timeinfo.tm_mday = packet->day;
- timeinfo.tm_hour = packet->hour;
- timeinfo.tm_min = packet->min;
- timeinfo.tm_sec = packet->sec;
- time_t epoch = mktime(&timeinfo);
+ _gps_position->vel_n_m_s = (float)_buf.payload_rx_nav_pvt.velN * 1e-3f;
+ _gps_position->vel_e_m_s = (float)_buf.payload_rx_nav_pvt.velE * 1e-3f;
+ _gps_position->vel_d_m_s = (float)_buf.payload_rx_nav_pvt.velD * 1e-3f;
+ _gps_position->vel_ned_valid = true;
+
+ _gps_position->cog_rad = (float)_buf.payload_rx_nav_pvt.headMot * M_DEG_TO_RAD_F * 1e-5f;
+ _gps_position->c_variance_rad = (float)_buf.payload_rx_nav_pvt.headAcc * M_DEG_TO_RAD_F * 1e-5f;
+
+ {
+ /* convert to unix timestamp */
+ struct tm timeinfo;
+ timeinfo.tm_year = _buf.payload_rx_nav_pvt.year - 1900;
+ timeinfo.tm_mon = _buf.payload_rx_nav_pvt.month - 1;
+ timeinfo.tm_mday = _buf.payload_rx_nav_pvt.day;
+ timeinfo.tm_hour = _buf.payload_rx_nav_pvt.hour;
+ timeinfo.tm_min = _buf.payload_rx_nav_pvt.min;
+ timeinfo.tm_sec = _buf.payload_rx_nav_pvt.sec;
+ time_t epoch = mktime(&timeinfo);
#ifndef CONFIG_RTC
- //Since we lack a hardware RTC, set the system time clock based on GPS UTC
- //TODO generalize this by moving into gps.cpp?
- timespec ts;
- ts.tv_sec = epoch;
- ts.tv_nsec = packet->time_nanoseconds;
- clock_settime(CLOCK_REALTIME, &ts);
+ //Since we lack a hardware RTC, set the system time clock based on GPS UTC
+ //TODO generalize this by moving into gps.cpp?
+ timespec ts;
+ ts.tv_sec = epoch;
+ ts.tv_nsec = _buf.payload_rx_nav_pvt.nano;
+ clock_settime(CLOCK_REALTIME, &ts);
#endif
- _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
- _gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f);
- _gps_position->timestamp_time = hrt_absolute_time();
+ _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
+ _gps_position->time_gps_usec += (uint64_t)(_buf.payload_rx_nav_pvt.nano * 1e-3f);
+ }
- _got_timeutc = true;
- ret = 1;
- break;
- }
+ _gps_position->timestamp_time = hrt_absolute_time();
+ _gps_position->timestamp_velocity = hrt_absolute_time();
+ _gps_position->timestamp_variance = hrt_absolute_time();
+ _gps_position->timestamp_position = hrt_absolute_time();
- case UBX_MESSAGE_NAV_SVINFO: {
- //printf("GOT NAV_SVINFO\n");
- const int length_part1 = 8;
- gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer;
- const int length_part2 = 12;
- gps_bin_nav_svinfo_part2_packet_t *packet_part2;
-
- uint8_t satellites_used = 0;
- int i;
-
- //printf("Number of Channels: %d\n", packet_part1->numCh);
- for (i = 0; i < packet_part1->numCh; i++) {
- /* set pointer to sattelite_i information */
- packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) & (_rx_buffer[length_part1 + i * length_part2]);
-
- /* write satellite information to global storage */
- uint8_t sv_used = packet_part2->flags & 0x01;
-
- if (sv_used) {
- /* count SVs used for NAV */
- satellites_used++;
- }
-
- /* record info for all channels, whether or not the SV is used for NAV */
- _gps_position->satellite_used[i] = sv_used;
- _gps_position->satellite_snr[i] = packet_part2->cno;
- _gps_position->satellite_elevation[i] = (uint8_t)(packet_part2->elev);
- _gps_position->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f);
- _gps_position->satellite_prn[i] = packet_part2->svid;
- //printf("SAT %d: %d %d %d %d\n", i, (int)sv_used, (int)packet_part2->cno, (int)(uint8_t)(packet_part2->elev), (int)packet_part2->svid);
- }
-
- for (i = packet_part1->numCh; i < 20; i++) {
- /* unused channels have to be set to zero for e.g. MAVLink */
- _gps_position->satellite_prn[i] = 0;
- _gps_position->satellite_used[i] = 0;
- _gps_position->satellite_snr[i] = 0;
- _gps_position->satellite_elevation[i] = 0;
- _gps_position->satellite_azimuth[i] = 0;
- }
-
- _gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones
-
- if (packet_part1->numCh > 0) {
- _gps_position->satellite_info_available = true;
-
- } else {
- _gps_position->satellite_info_available = false;
- }
-
- _gps_position->timestamp_satellites = hrt_absolute_time();
-
- ret = 1;
- break;
- }
+ _rate_count_vel++;
+ _rate_count_lat_lon++;
- case UBX_MESSAGE_NAV_VELNED: {
- // printf("GOT NAV_VELNED\n");
- gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer;
+ _got_posllh = true;
+ _got_velned = true;
- _gps_position->vel_m_s = (float)packet->speed * 1e-2f;
- _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; /* NED NORTH velocity */
- _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; /* NED EAST velocity */
- _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; /* NED DOWN velocity */
- _gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f;
- _gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f;
- _gps_position->vel_ned_valid = true;
- _gps_position->timestamp_velocity = hrt_absolute_time();
+ ret = 1;
+ break;
- _rate_count_vel++;
+ case UBX_MSG_NAV_POSLLH:
+ UBX_TRACE_RXMSG("Rx NAV-POSLLH\n");
- _got_velned = true;
- ret = 1;
- break;
- }
+ _gps_position->lat = _buf.payload_rx_nav_posllh.lat;
+ _gps_position->lon = _buf.payload_rx_nav_posllh.lon;
+ _gps_position->alt = _buf.payload_rx_nav_posllh.hMSL;
+ _gps_position->eph = (float)_buf.payload_rx_nav_posllh.hAcc * 1e-3f; // from mm to m
+ _gps_position->epv = (float)_buf.payload_rx_nav_posllh.vAcc * 1e-3f; // from mm to m
- default:
- break;
- }
+ _gps_position->timestamp_position = hrt_absolute_time();
- break;
+ _rate_count_lat_lon++;
+ _got_posllh = true;
- case UBX_CLASS_ACK: {
- /* ignore ACK when already configured */
- ret = 1;
- break;
- }
+ ret = 1;
+ break;
- case UBX_CLASS_MON: {
- switch (_message_id) {
- case UBX_MESSAGE_MON_HW: {
+ case UBX_MSG_NAV_SOL:
+ UBX_TRACE_RXMSG("Rx NAV-SOL\n");
- struct gps_bin_mon_hw_packet *p = (struct gps_bin_mon_hw_packet*) _rx_buffer;
+ _gps_position->fix_type = _buf.payload_rx_nav_sol.gpsFix;
+ _gps_position->s_variance_m_s = (float)_buf.payload_rx_nav_sol.sAcc * 1e-2f; // from cm to m
+ _gps_position->satellites_used = _buf.payload_rx_nav_sol.numSV;
- _gps_position->noise_per_ms = p->noisePerMS;
- _gps_position->jamming_indicator = p->jamInd;
+ _gps_position->timestamp_variance = hrt_absolute_time();
- ret = 1;
- break;
- }
+ ret = 1;
+ break;
- default:
- break;
- }
+ case UBX_MSG_NAV_TIMEUTC:
+ UBX_TRACE_RXMSG("Rx NAV-TIMEUTC\n");
+
+ {
+ /* convert to unix timestamp */
+ struct tm timeinfo;
+ timeinfo.tm_year = _buf.payload_rx_nav_timeutc.year - 1900;
+ timeinfo.tm_mon = _buf.payload_rx_nav_timeutc.month - 1;
+ timeinfo.tm_mday = _buf.payload_rx_nav_timeutc.day;
+ timeinfo.tm_hour = _buf.payload_rx_nav_timeutc.hour;
+ timeinfo.tm_min = _buf.payload_rx_nav_timeutc.min;
+ timeinfo.tm_sec = _buf.payload_rx_nav_timeutc.sec;
+ time_t epoch = mktime(&timeinfo);
+
+#ifndef CONFIG_RTC
+ //Since we lack a hardware RTC, set the system time clock based on GPS UTC
+ //TODO generalize this by moving into gps.cpp?
+ timespec ts;
+ ts.tv_sec = epoch;
+ ts.tv_nsec = _buf.payload_rx_nav_timeutc.nano;
+ clock_settime(CLOCK_REALTIME, &ts);
+#endif
+
+ _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
+ _gps_position->time_gps_usec += (uint64_t)(_buf.payload_rx_nav_timeutc.nano * 1e-3f);
}
- default:
+ _gps_position->timestamp_time = hrt_absolute_time();
+
+ ret = 1;
+ break;
+
+ case UBX_MSG_NAV_SVINFO:
+ UBX_TRACE_RXMSG("Rx NAV-SVINFO\n");
+
+ // _satellite_info already populated by payload_rx_add_svinfo(), just add a timestamp
+ _satellite_info->timestamp = hrt_absolute_time();
+
+ ret = 2;
+ break;
+
+ case UBX_MSG_NAV_VELNED:
+ UBX_TRACE_RXMSG("Rx NAV-VELNED\n");
+
+ _gps_position->vel_m_s = (float)_buf.payload_rx_nav_velned.speed * 1e-2f;
+ _gps_position->vel_n_m_s = (float)_buf.payload_rx_nav_velned.velN * 1e-2f; /* NED NORTH velocity */
+ _gps_position->vel_e_m_s = (float)_buf.payload_rx_nav_velned.velE * 1e-2f; /* NED EAST velocity */
+ _gps_position->vel_d_m_s = (float)_buf.payload_rx_nav_velned.velD * 1e-2f; /* NED DOWN velocity */
+ _gps_position->cog_rad = (float)_buf.payload_rx_nav_velned.heading * M_DEG_TO_RAD_F * 1e-5f;
+ _gps_position->c_variance_rad = (float)_buf.payload_rx_nav_velned.cAcc * M_DEG_TO_RAD_F * 1e-5f;
+ _gps_position->vel_ned_valid = true;
+
+ _gps_position->timestamp_velocity = hrt_absolute_time();
+
+ _rate_count_vel++;
+ _got_velned = true;
+
+ ret = 1;
+ break;
+
+ case UBX_MSG_MON_VER:
+ UBX_TRACE_RXMSG("Rx MON-VER\n");
+
+ ret = 1;
+ break;
+
+ case UBX_MSG_MON_HW:
+ UBX_TRACE_RXMSG("Rx MON-HW\n");
+
+ switch (_rx_payload_length) {
+
+ case sizeof(ubx_payload_rx_mon_hw_ubx6_t): /* u-blox 6 msg format */
+ _gps_position->noise_per_ms = _buf.payload_rx_mon_hw_ubx6.noisePerMS;
+ _gps_position->jamming_indicator = _buf.payload_rx_mon_hw_ubx6.jamInd;
+
+ ret = 1;
break;
- }
- if (ret == 0) {
- /* message not handled */
- warnx("ubx: unknown message received: 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id);
+ case sizeof(ubx_payload_rx_mon_hw_ubx7_t): /* u-blox 7+ msg format */
+ _gps_position->noise_per_ms = _buf.payload_rx_mon_hw_ubx7.noisePerMS;
+ _gps_position->jamming_indicator = _buf.payload_rx_mon_hw_ubx7.jamInd;
- hrt_abstime t = hrt_absolute_time();
+ ret = 1;
+ break;
- if (t > _disable_cmd_last + DISABLE_MSG_INTERVAL) {
- /* don't attempt for every message to disable, some might not be disabled */
- _disable_cmd_last = t;
- warnx("ubx: disabling message 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id);
- configure_message_rate(_message_class, _message_id, 0);
- }
+ default: // unexpected payload size:
+ ret = 0; // don't handle message
+ break;
}
+ break;
- } else {
- /* handle only ACK while configuring */
- if (_message_class == UBX_CLASS_ACK) {
- switch (_message_id) {
- case UBX_MESSAGE_ACK_ACK: {
- // printf("GOT ACK_ACK\n");
- gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer;
-
- if (_waiting_for_ack) {
- if (packet->clsID == _message_class_needed && packet->msgID == _message_id_needed) {
- _waiting_for_ack = false;
- ret = 1;
- }
- }
-
- break;
- }
+ case UBX_MSG_ACK_ACK:
+ UBX_TRACE_RXMSG("Rx ACK-ACK\n");
- case UBX_MESSAGE_ACK_NAK: {
- // printf("GOT ACK_NAK\n");
- warnx("ubx: not acknowledged");
- /* configuration obviously not successful */
- _waiting_for_ack = false;
- ret = -1;
- break;
- }
+ if ((_ack_state == UBX_ACK_WAITING) && (_buf.payload_rx_ack_ack.msg == _ack_waiting_msg)) {
+ _ack_state = UBX_ACK_GOT_ACK;
+ }
- default:
- break;
- }
+ ret = 1;
+ break;
+
+ case UBX_MSG_ACK_NAK:
+ UBX_TRACE_RXMSG("Rx ACK-NAK\n");
+
+ if ((_ack_state == UBX_ACK_WAITING) && (_buf.payload_rx_ack_ack.msg == _ack_waiting_msg)) {
+ _ack_state = UBX_ACK_GOT_NAK;
}
+
+ ret = 1;
+ break;
+
+ default:
+ break;
}
- decode_init();
return ret;
}
void
UBX::decode_init(void)
{
+ _decode_state = UBX_DECODE_SYNC1;
_rx_ck_a = 0;
_rx_ck_b = 0;
- _rx_count = 0;
- _decode_state = UBX_DECODE_UNINIT;
- _payload_size = 0;
- /* don't reset _message_class, _message_id, _rx_buffer leave it for message handler */
+ _rx_payload_length = 0;
+ _rx_payload_index = 0;
}
void
-UBX::add_byte_to_checksum(uint8_t b)
+UBX::add_byte_to_checksum(const uint8_t b)
{
_rx_ck_a = _rx_ck_a + b;
_rx_ck_b = _rx_ck_b + _rx_ck_a;
}
void
-UBX::add_checksum_to_message(uint8_t *message, const unsigned length)
+UBX::calc_checksum(const uint8_t *buffer, const uint16_t length, ubx_checksum_t *checksum)
{
- uint8_t ck_a = 0;
- uint8_t ck_b = 0;
- unsigned i;
-
- for (i = 0; i < length - 2; i++) {
- ck_a = ck_a + message[i];
- ck_b = ck_b + ck_a;
+ for (uint16_t i = 0; i < length; i++) {
+ checksum->ck_a = checksum->ck_a + buffer[i];
+ checksum->ck_b = checksum->ck_b + checksum->ck_a;
}
-
- /* the checksum is written to the last to bytes of a message */
- message[length - 2] = ck_a;
- message[length - 1] = ck_b;
}
void
-UBX::add_checksum(uint8_t *message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b)
+UBX::configure_message_rate(const uint16_t msg, const uint8_t rate)
{
- for (unsigned i = 0; i < length; i++) {
- ck_a = ck_a + message[i];
- ck_b = ck_b + ck_a;
- }
+ ubx_payload_tx_cfg_msg_t cfg_msg; // don't use _buf (allow interleaved operation)
+
+ cfg_msg.msg = msg;
+ cfg_msg.rate = rate;
+
+ send_message(UBX_MSG_CFG_MSG, (uint8_t *)&cfg_msg, sizeof(cfg_msg));
}
void
-UBX::configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
+UBX::send_message(const uint16_t msg, const uint8_t *payload, const uint16_t length)
{
- struct ubx_cfg_msg_rate msg;
- msg.msg_class = msg_class;
- msg.msg_id = msg_id;
- msg.rate = rate;
- send_message(UBX_CLASS_CFG, UBX_MESSAGE_CFG_MSG, &msg, sizeof(msg));
+ ubx_header_t header = {UBX_SYNC1, UBX_SYNC2};
+ ubx_checksum_t checksum = {0, 0};
+
+ // Populate header
+ header.msg = msg;
+ header.length = length;
+
+ // Calculate checksum
+ calc_checksum(((uint8_t*)&header) + 2, sizeof(header) - 2, &checksum); // skip 2 sync bytes
+ if (payload != nullptr)
+ calc_checksum(payload, length, &checksum);
+
+ // Send message
+ write(_fd, (const void *)&header, sizeof(header));
+ if (payload != nullptr)
+ write(_fd, (const void *)payload, length);
+ write(_fd, (const void *)&checksum, sizeof(checksum));
}
-void
-UBX::send_config_packet(const int &fd, uint8_t *packet, const unsigned length)
+uint32_t
+UBX::fnv1_32_str(uint8_t *str, uint32_t hval)
{
- ssize_t ret = 0;
-
- /* calculate the checksum now */
- add_checksum_to_message(packet, length);
-
- const uint8_t sync_bytes[] = {UBX_SYNC1, UBX_SYNC2};
+ uint8_t *s = str;
+
+ /*
+ * FNV-1 hash each octet in the buffer
+ */
+ while (*s) {
+
+ /* multiply by the 32 bit FNV magic prime mod 2^32 */
+#if defined(NO_FNV_GCC_OPTIMIZATION)
+ hval *= FNV1_32_PRIME;
+#else
+ hval += (hval<<1) + (hval<<4) + (hval<<7) + (hval<<8) + (hval<<24);
+#endif
- /* start with the two sync bytes */
- ret += write(fd, sync_bytes, sizeof(sync_bytes));
- ret += write(fd, packet, length);
+ /* xor the bottom with the current octet */
+ hval ^= (uint32_t)*s++;
+ }
- if (ret != (int)length + (int)sizeof(sync_bytes)) // XXX is there a neater way to get rid of the unsigned signed warning?
- warnx("ubx: configuration write fail");
+ /* return our new hash value */
+ return hval;
}
-void
-UBX::send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size)
-{
- struct ubx_header header;
- uint8_t ck_a = 0, ck_b = 0;
- header.sync1 = UBX_SYNC1;
- header.sync2 = UBX_SYNC2;
- header.msg_class = msg_class;
- header.msg_id = msg_id;
- header.length = size;
-
- add_checksum((uint8_t *)&header.msg_class, sizeof(header) - 2, ck_a, ck_b);
- add_checksum((uint8_t *)msg, size, ck_a, ck_b);
-
- /* configure ACK check */
- _message_class_needed = msg_class;
- _message_id_needed = msg_id;
-
- write(_fd, (const char *)&header, sizeof(header));
- write(_fd, (const char *)msg, size);
- write(_fd, (const char *)&ck_a, 1);
- write(_fd, (const char *)&ck_b, 1);
-}
diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h
index 43d688893..c74eb9168 100644
--- a/src/drivers/gps/ubx.h
+++ b/src/drivers/gps/ubx.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,13 +34,16 @@
/**
* @file ubx.h
*
- * U-Blox protocol definition. Following u-blox 6/7 Receiver Description
+ * U-Blox protocol definition. Following u-blox 6/7/8 Receiver Description
* including Prototol Specification.
*
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
*
+ * @author Hannes Delago
+ * (rework, add ubx7+ compatibility)
+ *
*/
#ifndef UBX_H_
@@ -51,319 +54,450 @@
#define UBX_SYNC1 0xB5
#define UBX_SYNC2 0x62
-/* ClassIDs (the ones that are used) */
-#define UBX_CLASS_NAV 0x01
-//#define UBX_CLASS_RXM 0x02
-#define UBX_CLASS_ACK 0x05
-#define UBX_CLASS_CFG 0x06
-#define UBX_CLASS_MON 0x0A
-
-/* MessageIDs (the ones that are used) */
-#define UBX_MESSAGE_NAV_POSLLH 0x02
-//#define UBX_MESSAGE_NAV_DOP 0x04
-#define UBX_MESSAGE_NAV_SOL 0x06
-#define UBX_MESSAGE_NAV_VELNED 0x12
-//#define UBX_MESSAGE_RXM_SVSI 0x20
-#define UBX_MESSAGE_NAV_TIMEUTC 0x21
-#define UBX_MESSAGE_NAV_SVINFO 0x30
-#define UBX_MESSAGE_ACK_NAK 0x00
-#define UBX_MESSAGE_ACK_ACK 0x01
-#define UBX_MESSAGE_CFG_PRT 0x00
-#define UBX_MESSAGE_CFG_MSG 0x01
-#define UBX_MESSAGE_CFG_RATE 0x08
-#define UBX_MESSAGE_CFG_NAV5 0x24
-
-#define UBX_MESSAGE_MON_HW 0x09
-
-#define UBX_CFG_PRT_LENGTH 20
-#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */
-#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
-#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< choose 38400 as GPS baudrate */
-#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< UBX in */
-#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */
-
-#define UBX_CFG_RATE_LENGTH 6
-#define UBX_CFG_RATE_PAYLOAD_MEASINTERVAL 200 /**< 200ms for 5Hz */
-#define UBX_CFG_RATE_PAYLOAD_NAVRATE 1 /**< cannot be changed */
-#define UBX_CFG_RATE_PAYLOAD_TIMEREF 0 /**< 0: UTC, 1: GPS time */
-
-
-#define UBX_CFG_NAV5_LENGTH 36
-#define UBX_CFG_NAV5_PAYLOAD_MASK 0x0005 /**< XXX only update dynamic model and fix mode */
-#define UBX_CFG_NAV5_PAYLOAD_DYNMODEL 7 /**< 0: portable, 2: stationary, 3: pedestrian, 4: automotive, 5: sea, 6: airborne <1g, 7: airborne <2g, 8: airborne <4g */
-#define UBX_CFG_NAV5_PAYLOAD_FIXMODE 2 /**< 1: 2D only, 2: 3D only, 3: Auto 2D/3D */
-
-#define UBX_CFG_MSG_LENGTH 8
-#define UBX_CFG_MSG_PAYLOAD_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
-#define UBX_CFG_MSG_PAYLOAD_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
-#define UBX_CFG_MSG_PAYLOAD_RATE1_05HZ 10
-
-#define UBX_MAX_PAYLOAD_LENGTH 500
-
-// ************
-/** the structures of the binary packets */
+/* Message Classes */
+#define UBX_CLASS_NAV 0x01
+#define UBX_CLASS_ACK 0x05
+#define UBX_CLASS_CFG 0x06
+#define UBX_CLASS_MON 0x0A
+
+/* Message IDs */
+#define UBX_ID_NAV_POSLLH 0x02
+#define UBX_ID_NAV_SOL 0x06
+#define UBX_ID_NAV_PVT 0x07
+#define UBX_ID_NAV_VELNED 0x12
+#define UBX_ID_NAV_TIMEUTC 0x21
+#define UBX_ID_NAV_SVINFO 0x30
+#define UBX_ID_ACK_NAK 0x00
+#define UBX_ID_ACK_ACK 0x01
+#define UBX_ID_CFG_PRT 0x00
+#define UBX_ID_CFG_MSG 0x01
+#define UBX_ID_CFG_RATE 0x08
+#define UBX_ID_CFG_NAV5 0x24
+#define UBX_ID_CFG_SBAS 0x16
+#define UBX_ID_MON_VER 0x04
+#define UBX_ID_MON_HW 0x09
+
+/* Message Classes & IDs */
+#define UBX_MSG_NAV_POSLLH ((UBX_CLASS_NAV) | UBX_ID_NAV_POSLLH << 8)
+#define UBX_MSG_NAV_SOL ((UBX_CLASS_NAV) | UBX_ID_NAV_SOL << 8)
+#define UBX_MSG_NAV_PVT ((UBX_CLASS_NAV) | UBX_ID_NAV_PVT << 8)
+#define UBX_MSG_NAV_VELNED ((UBX_CLASS_NAV) | UBX_ID_NAV_VELNED << 8)
+#define UBX_MSG_NAV_TIMEUTC ((UBX_CLASS_NAV) | UBX_ID_NAV_TIMEUTC << 8)
+#define UBX_MSG_NAV_SVINFO ((UBX_CLASS_NAV) | UBX_ID_NAV_SVINFO << 8)
+#define UBX_MSG_ACK_NAK ((UBX_CLASS_ACK) | UBX_ID_ACK_NAK << 8)
+#define UBX_MSG_ACK_ACK ((UBX_CLASS_ACK) | UBX_ID_ACK_ACK << 8)
+#define UBX_MSG_CFG_PRT ((UBX_CLASS_CFG) | UBX_ID_CFG_PRT << 8)
+#define UBX_MSG_CFG_MSG ((UBX_CLASS_CFG) | UBX_ID_CFG_MSG << 8)
+#define UBX_MSG_CFG_RATE ((UBX_CLASS_CFG) | UBX_ID_CFG_RATE << 8)
+#define UBX_MSG_CFG_NAV5 ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8)
+#define UBX_MSG_CFG_SBAS ((UBX_CLASS_CFG) | UBX_ID_CFG_SBAS << 8)
+#define UBX_MSG_MON_HW ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8)
+#define UBX_MSG_MON_VER ((UBX_CLASS_MON) | UBX_ID_MON_VER << 8)
+
+/* RX NAV-PVT message content details */
+/* Bitfield "valid" masks */
+#define UBX_RX_NAV_PVT_VALID_VALIDDATE 0x01 /**< validDate (Valid UTC Date) */
+#define UBX_RX_NAV_PVT_VALID_VALIDTIME 0x02 /**< validTime (Valid UTC Time) */
+#define UBX_RX_NAV_PVT_VALID_FULLYRESOLVED 0x04 /**< fullyResolved (1 = UTC Time of Day has been fully resolved (no seconds uncertainty)) */
+
+/* Bitfield "flags" masks */
+#define UBX_RX_NAV_PVT_FLAGS_GNSSFIXOK 0x01 /**< gnssFixOK (A valid fix (i.e within DOP & accuracy masks)) */
+#define UBX_RX_NAV_PVT_FLAGS_DIFFSOLN 0x02 /**< diffSoln (1 if differential corrections were applied) */
+#define UBX_RX_NAV_PVT_FLAGS_PSMSTATE 0x1C /**< psmState (Power Save Mode state (see Power Management)) */
+#define UBX_RX_NAV_PVT_FLAGS_HEADVEHVALID 0x20 /**< headVehValid (Heading of vehicle is valid) */
+
+/* RX NAV-TIMEUTC message content details */
+/* Bitfield "valid" masks */
+#define UBX_RX_NAV_TIMEUTC_VALID_VALIDTOW 0x01 /**< validTOW (1 = Valid Time of Week) */
+#define UBX_RX_NAV_TIMEUTC_VALID_VALIDKWN 0x02 /**< validWKN (1 = Valid Week Number) */
+#define UBX_RX_NAV_TIMEUTC_VALID_VALIDUTC 0x04 /**< validUTC (1 = Valid UTC Time) */
+#define UBX_RX_NAV_TIMEUTC_VALID_UTCSTANDARD 0xF0 /**< utcStandard (0..15 = UTC standard identifier) */
+
+/* TX CFG-PRT message contents */
+#define UBX_TX_CFG_PRT_PORTID 0x01 /**< UART1 */
+#define UBX_TX_CFG_PRT_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
+#define UBX_TX_CFG_PRT_BAUDRATE 38400 /**< choose 38400 as GPS baudrate */
+#define UBX_TX_CFG_PRT_INPROTOMASK 0x01 /**< UBX in */
+#define UBX_TX_CFG_PRT_OUTPROTOMASK 0x01 /**< UBX out */
+
+/* TX CFG-RATE message contents */
+#define UBX_TX_CFG_RATE_MEASINTERVAL 200 /**< 200ms for 5Hz */
+#define UBX_TX_CFG_RATE_NAVRATE 1 /**< cannot be changed */
+#define UBX_TX_CFG_RATE_TIMEREF 0 /**< 0: UTC, 1: GPS time */
+
+/* TX CFG-NAV5 message contents */
+#define UBX_TX_CFG_NAV5_MASK 0x0005 /**< Only update dynamic model and fix mode */
+#define UBX_TX_CFG_NAV5_DYNMODEL 7 /**< 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g */
+#define UBX_TX_CFG_NAV5_FIXMODE 2 /**< 1 2D only, 2 3D only, 3 Auto 2D/3D */
+
+/* TX CFG-SBAS message contents */
+#define UBX_TX_CFG_SBAS_MODE_ENABLED 1 /**< SBAS enabled */
+#define UBX_TX_CFG_SBAS_MODE_DISABLED 0 /**< SBAS disabled */
+#define UBX_TX_CFG_SBAS_MODE UBX_TX_CFG_SBAS_MODE_DISABLED /**< SBAS enabled or disabled */
+
+/* TX CFG-MSG message contents */
+#define UBX_TX_CFG_MSG_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
+#define UBX_TX_CFG_MSG_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
+#define UBX_TX_CFG_MSG_RATE1_05HZ 10
+
+
+/*** u-blox protocol binary message and payload definitions ***/
#pragma pack(push, 1)
-struct ubx_header {
- uint8_t sync1;
- uint8_t sync2;
- uint8_t msg_class;
- uint8_t msg_id;
- uint16_t length;
-};
-
+/* General: Header */
typedef struct {
- uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
- int32_t lon; /**< Longitude * 1e-7, deg */
- int32_t lat; /**< Latitude * 1e-7, deg */
- int32_t height; /**< Height above Ellipsoid, mm */
- int32_t height_msl; /**< Height above mean sea level, mm */
- uint32_t hAcc; /**< Horizontal Accuracy Estimate, mm */
- uint32_t vAcc; /**< Vertical Accuracy Estimate, mm */
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_nav_posllh_packet_t;
+ uint8_t sync1;
+ uint8_t sync2;
+ uint16_t msg;
+ uint16_t length;
+} ubx_header_t;
+/* General: Checksum */
typedef struct {
- uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
- int32_t time_nanoseconds; /**< Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 */
- int16_t week; /**< GPS week (GPS time) */
- uint8_t gpsFix; /**< GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */
- uint8_t flags;
- int32_t ecefX;
- int32_t ecefY;
- int32_t ecefZ;
- uint32_t pAcc;
- int32_t ecefVX;
- int32_t ecefVY;
- int32_t ecefVZ;
- uint32_t sAcc;
- uint16_t pDOP;
- uint8_t reserved1;
- uint8_t numSV;
- uint32_t reserved2;
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_nav_sol_packet_t;
+ uint8_t ck_a;
+ uint8_t ck_b;
+} ubx_checksum_t ;
+/* Rx NAV-POSLLH */
typedef struct {
- uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
- uint32_t time_accuracy; /**< Time Accuracy Estimate, ns */
- int32_t time_nanoseconds; /**< Nanoseconds of second, range -1e9 .. 1e9 (UTC) */
- uint16_t year; /**< Year, range 1999..2099 (UTC) */
- uint8_t month; /**< Month, range 1..12 (UTC) */
- uint8_t day; /**< Day of Month, range 1..31 (UTC) */
- uint8_t hour; /**< Hour of Day, range 0..23 (UTC) */
- uint8_t min; /**< Minute of Hour, range 0..59 (UTC) */
- uint8_t sec; /**< Seconds of Minute, range 0..59 (UTC) */
- uint8_t valid_flag; /**< Validity Flags (see ubx documentation) */
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_nav_timeutc_packet_t;
-
-//typedef struct {
-// uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
-// uint16_t gDOP; /**< Geometric DOP (scaling 0.01) */
-// uint16_t pDOP; /**< Position DOP (scaling 0.01) */
-// uint16_t tDOP; /**< Time DOP (scaling 0.01) */
-// uint16_t vDOP; /**< Vertical DOP (scaling 0.01) */
-// uint16_t hDOP; /**< Horizontal DOP (scaling 0.01) */
-// uint16_t nDOP; /**< Northing DOP (scaling 0.01) */
-// uint16_t eDOP; /**< Easting DOP (scaling 0.01) */
-// uint8_t ck_a;
-// uint8_t ck_b;
-//} gps_bin_nav_dop_packet_t;
-
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ int32_t lon; /**< Longitude [1e-7 deg] */
+ int32_t lat; /**< Latitude [1e-7 deg] */
+ int32_t height; /**< Height above ellipsoid [mm] */
+ int32_t hMSL; /**< Height above mean sea level [mm] */
+ uint32_t hAcc; /**< Horizontal accuracy estimate [mm] */
+ uint32_t vAcc; /**< Vertical accuracy estimate [mm] */
+} ubx_payload_rx_nav_posllh_t;
+
+/* Rx NAV-SOL */
typedef struct {
- uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */
- uint8_t numCh; /**< Number of channels */
- uint8_t globalFlags;
- uint16_t reserved2;
-
-} gps_bin_nav_svinfo_part1_packet_t;
-
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ int32_t fTOW; /**< Fractional part of iTOW (range: +/-500000) [ns] */
+ int16_t week; /**< GPS week */
+ uint8_t gpsFix; /**< GPSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */
+ uint8_t flags;
+ int32_t ecefX;
+ int32_t ecefY;
+ int32_t ecefZ;
+ uint32_t pAcc;
+ int32_t ecefVX;
+ int32_t ecefVY;
+ int32_t ecefVZ;
+ uint32_t sAcc;
+ uint16_t pDOP;
+ uint8_t reserved1;
+ uint8_t numSV; /**< Number of SVs used in Nav Solution */
+ uint32_t reserved2;
+} ubx_payload_rx_nav_sol_t;
+
+/* Rx NAV-PVT (ubx8) */
typedef struct {
- uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */
- uint8_t svid; /**< Satellite ID */
- uint8_t flags;
- uint8_t quality;
- uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength), dbHz */
- int8_t elev; /**< Elevation in integer degrees */
- int16_t azim; /**< Azimuth in integer degrees */
- int32_t prRes; /**< Pseudo range residual in centimetres */
-
-} gps_bin_nav_svinfo_part2_packet_t;
-
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ uint16_t year; /**< Year (UTC)*/
+ uint8_t month; /**< Month, range 1..12 (UTC) */
+ uint8_t day; /**< Day of month, range 1..31 (UTC) */
+ uint8_t hour; /**< Hour of day, range 0..23 (UTC) */
+ uint8_t min; /**< Minute of hour, range 0..59 (UTC) */
+ uint8_t sec; /**< Seconds of minute, range 0..60 (UTC) */
+ uint8_t valid; /**< Validity flags (see UBX_RX_NAV_PVT_VALID_...) */
+ uint32_t tAcc; /**< Time accuracy estimate (UTC) [ns] */
+ int32_t nano; /**< Fraction of second (UTC) [-1e9...1e9 ns] */
+ uint8_t fixType; /**< GNSSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GNSS + dead reckoning, 5 = time only fix */
+ uint8_t flags; /**< Fix Status Flags (see UBX_RX_NAV_PVT_FLAGS_...) */
+ uint8_t reserved1;
+ uint8_t numSV; /**< Number of SVs used in Nav Solution */
+ int32_t lon; /**< Longitude [1e-7 deg] */
+ int32_t lat; /**< Latitude [1e-7 deg] */
+ int32_t height; /**< Height above ellipsoid [mm] */
+ int32_t hMSL; /**< Height above mean sea level [mm] */
+ uint32_t hAcc; /**< Horizontal accuracy estimate [mm] */
+ uint32_t vAcc; /**< Vertical accuracy estimate [mm] */
+ int32_t velN; /**< NED north velocity [mm/s]*/
+ int32_t velE; /**< NED east velocity [mm/s]*/
+ int32_t velD; /**< NED down velocity [mm/s]*/
+ int32_t gSpeed; /**< Ground Speed (2-D) [mm/s] */
+ int32_t headMot; /**< Heading of motion (2-D) [1e-5 deg] */
+ uint32_t sAcc; /**< Speed accuracy estimate [mm/s] */
+ uint32_t headAcc; /**< Heading accuracy estimate (motion and vehicle) [1e-5 deg] */
+ uint16_t pDOP; /**< Position DOP [0.01] */
+ uint16_t reserved2;
+ uint32_t reserved3;
+ int32_t headVeh; /**< (ubx8+ only) Heading of vehicle (2-D) [1e-5 deg] */
+ uint32_t reserved4; /**< (ubx8+ only) */
+} ubx_payload_rx_nav_pvt_t;
+#define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7 (sizeof(ubx_payload_rx_nav_pvt_t) - 8)
+#define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8 (sizeof(ubx_payload_rx_nav_pvt_t))
+
+/* Rx NAV-TIMEUTC */
typedef struct {
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_nav_svinfo_part3_packet_t;
-
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ uint32_t tAcc; /**< Time accuracy estimate (UTC) [ns] */
+ int32_t nano; /**< Fraction of second, range -1e9 .. 1e9 (UTC) [ns] */
+ uint16_t year; /**< Year, range 1999..2099 (UTC) */
+ uint8_t month; /**< Month, range 1..12 (UTC) */
+ uint8_t day; /**< Day of month, range 1..31 (UTC) */
+ uint8_t hour; /**< Hour of day, range 0..23 (UTC) */
+ uint8_t min; /**< Minute of hour, range 0..59 (UTC) */
+ uint8_t sec; /**< Seconds of minute, range 0..60 (UTC) */
+ uint8_t valid; /**< Validity Flags (see UBX_RX_NAV_TIMEUTC_VALID_...) */
+} ubx_payload_rx_nav_timeutc_t;
+
+/* Rx NAV-SVINFO Part 1 */
typedef struct {
- uint32_t time_milliseconds; // GPS Millisecond Time of Week
- int32_t velN; //NED north velocity, cm/s
- int32_t velE; //NED east velocity, cm/s
- int32_t velD; //NED down velocity, cm/s
- uint32_t speed; //Speed (3-D), cm/s
- uint32_t gSpeed; //Ground Speed (2-D), cm/s
- int32_t heading; //Heading of motion 2-D, deg, scaling: 1e-5
- uint32_t sAcc; //Speed Accuracy Estimate, cm/s
- uint32_t cAcc; //Course / Heading Accuracy Estimate, scaling: 1e-5
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_nav_velned_packet_t;
-
-struct gps_bin_mon_hw_packet {
- uint32_t pinSel;
- uint32_t pinBank;
- uint32_t pinDir;
- uint32_t pinVal;
- uint16_t noisePerMS;
- uint16_t agcCnt;
- uint8_t aStatus;
- uint8_t aPower;
- uint8_t flags;
- uint8_t __reserved1;
- uint32_t usedMask;
- uint8_t VP[25];
- uint8_t jamInd;
- uint16_t __reserved3;
- uint32_t pinIrq;
- uint32_t pulLH;
- uint32_t pullL;
-};
-
-
-//typedef struct {
-// int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */
-// int16_t week; /**< Measurement GPS week number */
-// uint8_t numVis; /**< Number of visible satellites */
-//
-// //... rest of package is not used in this implementation
-//
-//} gps_bin_rxm_svsi_packet_t;
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ uint8_t numCh; /**< Number of channels */
+ uint8_t globalFlags;
+ uint16_t reserved2;
+} ubx_payload_rx_nav_svinfo_part1_t;
+/* Rx NAV-SVINFO Part 2 (repeated) */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_ack_ack_packet_t;
-
+ uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */
+ uint8_t svid; /**< Satellite ID */
+ uint8_t flags;
+ uint8_t quality;
+ uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength) [dbHz] */
+ int8_t elev; /**< Elevation [deg] */
+ int16_t azim; /**< Azimuth [deg] */
+ int32_t prRes; /**< Pseudo range residual [cm] */
+} ubx_payload_rx_nav_svinfo_part2_t;
+
+/* Rx NAV-VELNED */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint8_t ck_a;
- uint8_t ck_b;
-} gps_bin_ack_nak_packet_t;
-
+ uint32_t iTOW; /**< GPS Time of Week [ms] */
+ int32_t velN; /**< North velocity component [cm/s]*/
+ int32_t velE; /**< East velocity component [cm/s]*/
+ int32_t velD; /**< Down velocity component [cm/s]*/
+ uint32_t speed; /**< Speed (3-D) [cm/s] */
+ uint32_t gSpeed; /**< Ground speed (2-D) [cm/s] */
+ int32_t heading; /**< Heading of motion 2-D [1e-5 deg] */
+ uint32_t sAcc; /**< Speed accuracy estimate [cm/s] */
+ uint32_t cAcc; /**< Course / Heading accuracy estimate [1e-5 deg] */
+} ubx_payload_rx_nav_velned_t;
+
+/* Rx MON-HW (ubx6) */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint8_t portID;
- uint8_t res0;
- uint16_t res1;
- uint32_t mode;
- uint32_t baudRate;
- uint16_t inProtoMask;
- uint16_t outProtoMask;
- uint16_t flags;
- uint16_t pad;
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_prt_packet_t;
-
+ uint32_t pinSel;
+ uint32_t pinBank;
+ uint32_t pinDir;
+ uint32_t pinVal;
+ uint16_t noisePerMS;
+ uint16_t agcCnt;
+ uint8_t aStatus;
+ uint8_t aPower;
+ uint8_t flags;
+ uint8_t reserved1;
+ uint32_t usedMask;
+ uint8_t VP[25];
+ uint8_t jamInd;
+ uint16_t reserved3;
+ uint32_t pinIrq;
+ uint32_t pullH;
+ uint32_t pullL;
+} ubx_payload_rx_mon_hw_ubx6_t;
+
+/* Rx MON-HW (ubx7+) */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint16_t measRate;
- uint16_t navRate;
- uint16_t timeRef;
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_rate_packet_t;
-
+ uint32_t pinSel;
+ uint32_t pinBank;
+ uint32_t pinDir;
+ uint32_t pinVal;
+ uint16_t noisePerMS;
+ uint16_t agcCnt;
+ uint8_t aStatus;
+ uint8_t aPower;
+ uint8_t flags;
+ uint8_t reserved1;
+ uint32_t usedMask;
+ uint8_t VP[17];
+ uint8_t jamInd;
+ uint16_t reserved3;
+ uint32_t pinIrq;
+ uint32_t pullH;
+ uint32_t pullL;
+} ubx_payload_rx_mon_hw_ubx7_t;
+
+/* Rx MON-VER Part 1 */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint16_t mask;
- uint8_t dynModel;
- uint8_t fixMode;
- int32_t fixedAlt;
- uint32_t fixedAltVar;
- int8_t minElev;
- uint8_t drLimit;
- uint16_t pDop;
- uint16_t tDop;
- uint16_t pAcc;
- uint16_t tAcc;
- uint8_t staticHoldThresh;
- uint8_t dgpsTimeOut;
- uint32_t reserved2;
- uint32_t reserved3;
- uint32_t reserved4;
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_nav5_packet_t;
+ uint8_t swVersion[30];
+ uint8_t hwVersion[10];
+} ubx_payload_rx_mon_ver_part1_t;
+/* Rx MON-VER Part 2 (repeated) */
typedef struct {
- uint8_t clsID;
- uint8_t msgID;
- uint16_t length;
- uint8_t msgClass_payload;
- uint8_t msgID_payload;
- uint8_t rate;
- uint8_t ck_a;
- uint8_t ck_b;
-} type_gps_bin_cfg_msg_packet_t;
+ uint8_t extension[30];
+} ubx_payload_rx_mon_ver_part2_t;
+
+/* Rx ACK-ACK */
+typedef union {
+ uint16_t msg;
+ struct {
+ uint8_t clsID;
+ uint8_t msgID;
+ };
+} ubx_payload_rx_ack_ack_t;
+
+/* Rx ACK-NAK */
+typedef union {
+ uint16_t msg;
+ struct {
+ uint8_t clsID;
+ uint8_t msgID;
+ };
+} ubx_payload_rx_ack_nak_t;
+
+/* Tx CFG-PRT */
+typedef struct {
+ uint8_t portID;
+ uint8_t reserved0;
+ uint16_t txReady;
+ uint32_t mode;
+ uint32_t baudRate;
+ uint16_t inProtoMask;
+ uint16_t outProtoMask;
+ uint16_t flags;
+ uint16_t reserved5;
+} ubx_payload_tx_cfg_prt_t;
+
+/* Tx CFG-RATE */
+typedef struct {
+ uint16_t measRate; /**< Measurement Rate, GPS measurements are taken every measRate milliseconds */
+ uint16_t navRate; /**< Navigation Rate, in number of measurement cycles. This parameter cannot be changed, and must be set to 1 */
+ uint16_t timeRef; /**< Alignment to reference time: 0 = UTC time, 1 = GPS time */
+} ubx_payload_tx_cfg_rate_t;
-struct ubx_cfg_msg_rate {
- uint8_t msg_class;
- uint8_t msg_id;
+/* Tx CFG-NAV5 */
+typedef struct {
+ uint16_t mask;
+ uint8_t dynModel; /**< Dynamic Platform model: 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g */
+ uint8_t fixMode; /**< Position Fixing Mode: 1 2D only, 2 3D only, 3 Auto 2D/3D */
+ int32_t fixedAlt;
+ uint32_t fixedAltVar;
+ int8_t minElev;
+ uint8_t drLimit;
+ uint16_t pDop;
+ uint16_t tDop;
+ uint16_t pAcc;
+ uint16_t tAcc;
+ uint8_t staticHoldThresh;
+ uint8_t dgpsTimeOut;
+ uint8_t cnoThreshNumSVs; /**< (ubx7+ only, else 0) */
+ uint8_t cnoThresh; /**< (ubx7+ only, else 0) */
+ uint16_t reserved;
+ uint16_t staticHoldMaxDist; /**< (ubx8+ only, else 0) */
+ uint8_t utcStandard; /**< (ubx8+ only, else 0) */
+ uint8_t reserved3;
+ uint32_t reserved4;
+} ubx_payload_tx_cfg_nav5_t;
+
+/* tx cfg-sbas */
+typedef struct {
+ uint8_t mode;
+ uint8_t usage;
+ uint8_t maxSBAS;
+ uint8_t scanmode2;
+ uint32_t scanmode1;
+} ubx_payload_tx_cfg_sbas_t;
+
+/* Tx CFG-MSG */
+typedef struct {
+ union {
+ uint16_t msg;
+ struct {
+ uint8_t msgClass;
+ uint8_t msgID;
+ };
+ };
uint8_t rate;
-};
-
+} ubx_payload_tx_cfg_msg_t;
+
+/* General message and payload buffer union */
+typedef union {
+ ubx_payload_rx_nav_pvt_t payload_rx_nav_pvt;
+ ubx_payload_rx_nav_posllh_t payload_rx_nav_posllh;
+ ubx_payload_rx_nav_sol_t payload_rx_nav_sol;
+ ubx_payload_rx_nav_timeutc_t payload_rx_nav_timeutc;
+ ubx_payload_rx_nav_svinfo_part1_t payload_rx_nav_svinfo_part1;
+ ubx_payload_rx_nav_svinfo_part2_t payload_rx_nav_svinfo_part2;
+ ubx_payload_rx_nav_velned_t payload_rx_nav_velned;
+ ubx_payload_rx_mon_hw_ubx6_t payload_rx_mon_hw_ubx6;
+ ubx_payload_rx_mon_hw_ubx7_t payload_rx_mon_hw_ubx7;
+ ubx_payload_rx_mon_ver_part1_t payload_rx_mon_ver_part1;
+ ubx_payload_rx_mon_ver_part2_t payload_rx_mon_ver_part2;
+ ubx_payload_rx_ack_ack_t payload_rx_ack_ack;
+ ubx_payload_rx_ack_nak_t payload_rx_ack_nak;
+ ubx_payload_tx_cfg_prt_t payload_tx_cfg_prt;
+ ubx_payload_tx_cfg_rate_t payload_tx_cfg_rate;
+ ubx_payload_tx_cfg_nav5_t payload_tx_cfg_nav5;
+ ubx_payload_tx_cfg_sbas_t payload_tx_cfg_sbas;
+ ubx_payload_tx_cfg_msg_t payload_tx_cfg_msg;
+ uint8_t raw[];
+} ubx_buf_t;
-// END the structures of the binary packets
-// ************
+#pragma pack(pop)
+/*** END OF u-blox protocol binary message and payload definitions ***/
+/* Decoder state */
typedef enum {
- UBX_DECODE_UNINIT = 0,
- UBX_DECODE_GOT_SYNC1,
- UBX_DECODE_GOT_SYNC2,
- UBX_DECODE_GOT_CLASS,
- UBX_DECODE_GOT_MESSAGEID,
- UBX_DECODE_GOT_LENGTH1,
- UBX_DECODE_GOT_LENGTH2
+ UBX_DECODE_SYNC1 = 0,
+ UBX_DECODE_SYNC2,
+ UBX_DECODE_CLASS,
+ UBX_DECODE_ID,
+ UBX_DECODE_LENGTH1,
+ UBX_DECODE_LENGTH2,
+ UBX_DECODE_PAYLOAD,
+ UBX_DECODE_CHKSUM1,
+ UBX_DECODE_CHKSUM2
} ubx_decode_state_t;
-//typedef type_gps_bin_ubx_state gps_bin_ubx_state_t;
-#pragma pack(pop)
+/* Rx message state */
+typedef enum {
+ UBX_RXMSG_IGNORE = 0,
+ UBX_RXMSG_HANDLE,
+ UBX_RXMSG_DISABLE,
+ UBX_RXMSG_ERROR_LENGTH
+} ubx_rxmsg_state_t;
+
+/* ACK state */
+typedef enum {
+ UBX_ACK_IDLE = 0,
+ UBX_ACK_WAITING,
+ UBX_ACK_GOT_ACK,
+ UBX_ACK_GOT_NAK
+} ubx_ack_state_t;
-#define RECV_BUFFER_SIZE 300 //The NAV-SOL messages really need such a big buffer
class UBX : public GPS_Helper
{
public:
- UBX(const int &fd, struct vehicle_gps_position_s *gps_position);
+ UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info);
~UBX();
- int receive(unsigned timeout);
+ int receive(const unsigned timeout);
int configure(unsigned &baudrate);
private:
/**
- * Parse the binary MTK packet
+ * Parse the binary UBX packet
+ */
+ int parse_char(const uint8_t b);
+
+ /**
+ * Start payload rx
*/
- int parse_char(uint8_t b);
+ int payload_rx_init(void);
/**
- * Handle the package once it has arrived
+ * Add payload rx byte
*/
- int handle_message(void);
+ int payload_rx_add(const uint8_t b);
+ int payload_rx_add_nav_svinfo(const uint8_t b);
+ int payload_rx_add_mon_ver(const uint8_t b);
+
+ /**
+ * Finish payload rx
+ */
+ int payload_rx_done(void);
/**
* Reset the parse state machine for a fresh start
@@ -373,44 +507,53 @@ private:
/**
* While parsing add every byte (except the sync bytes) to the checksum
*/
- void add_byte_to_checksum(uint8_t);
+ void add_byte_to_checksum(const uint8_t);
/**
- * Add the two checksum bytes to an outgoing message
+ * Send a message
*/
- void add_checksum_to_message(uint8_t *message, const unsigned length);
+ void send_message(const uint16_t msg, const uint8_t *payload, const uint16_t length);
/**
- * Helper to send a config packet
+ * Configure message rate
*/
- void send_config_packet(const int &fd, uint8_t *packet, const unsigned length);
+ void configure_message_rate(const uint16_t msg, const uint8_t rate);
- void configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
-
- void send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size);
+ /**
+ * Calculate & add checksum for given buffer
+ */
+ void calc_checksum(const uint8_t *buffer, const uint16_t length, ubx_checksum_t *checksum);
- void add_checksum(uint8_t *message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b);
+ /**
+ * Wait for message acknowledge
+ */
+ int wait_for_ack(const uint16_t msg, const unsigned timeout, const bool report);
- int wait_for_ack(unsigned timeout);
+ /**
+ * Calculate FNV1 hash
+ */
+ uint32_t fnv1_32_str(uint8_t *str, uint32_t hval);
int _fd;
struct vehicle_gps_position_s *_gps_position;
+ struct satellite_info_s *_satellite_info;
+ bool _enable_sat_info;
bool _configured;
- bool _waiting_for_ack;
+ ubx_ack_state_t _ack_state;
bool _got_posllh;
bool _got_velned;
- bool _got_timeutc;
- uint8_t _message_class_needed;
- uint8_t _message_id_needed;
ubx_decode_state_t _decode_state;
- uint8_t _rx_buffer[RECV_BUFFER_SIZE];
- unsigned _rx_count;
+ uint16_t _rx_msg;
+ ubx_rxmsg_state_t _rx_state;
+ uint16_t _rx_payload_length;
+ uint16_t _rx_payload_index;
uint8_t _rx_ck_a;
uint8_t _rx_ck_b;
- uint8_t _message_class;
- uint8_t _message_id;
- unsigned _payload_size;
hrt_abstime _disable_cmd_last;
+ uint16_t _ack_waiting_msg;
+ ubx_buf_t _buf;
+ uint32_t _ubx_version;
+ bool _use_nav_pvt;
};
#endif /* UBX_H_ */
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index 55cc077fb..9b5c8133b 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -229,7 +229,7 @@ HIL::init()
_task = task_spawn_cmd("fmuhil",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 1200,
(main_t)&HIL::task_main_trampoline,
nullptr);
@@ -392,7 +392,8 @@ HIL::task_main()
if (fds[0].revents & POLLIN) {
/* get controls - must always do this to avoid spinning */
- orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls);
+ orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
+ ORB_ID(actuator_controls_1), _t_actuators, &_controls);
/* can we mix? */
if (_mixers != nullptr) {
@@ -441,8 +442,6 @@ HIL::task_main()
/* make sure servos are off */
// up_pwm_servo_deinit();
- log("stopping");
-
/* note - someone else is responsible for restoring the GPIO config */
/* tell the dtor that we are exiting */
diff --git a/src/drivers/hil/module.mk b/src/drivers/hil/module.mk
index f8895f5d5..f1fc49fb3 100644
--- a/src/drivers/hil/module.mk
+++ b/src/drivers/hil/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = hil
SRCS = hil.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index fddba806e..81f767965 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -71,13 +71,16 @@
#include <uORB/topics/subsystem_info.h>
#include <float.h>
+#include <getopt.h>
+#include <lib/conversion/rotation.h>
/*
* HMC5883 internal constants and data structures.
*/
#define HMC5883L_ADDRESS PX4_I2C_OBDEV_HMC5883
-#define HMC5883L_DEVICE_PATH "/dev/hmc5883"
+#define HMC5883L_DEVICE_PATH_INT "/dev/hmc5883_int"
+#define HMC5883L_DEVICE_PATH_EXT "/dev/hmc5883_ext"
/* Max measurement rate is 160Hz, however with 160 it will be set to 166 Hz, therefore workaround using 150 */
#define HMC5883_CONVERSION_INTERVAL (1000000 / 150) /* microseconds */
@@ -130,7 +133,7 @@ static const int ERROR = -1;
class HMC5883 : public device::I2C
{
public:
- HMC5883(int bus);
+ HMC5883(int bus, const char *path, enum Rotation rotation);
virtual ~HMC5883();
virtual int init();
@@ -159,19 +162,26 @@ private:
orb_advert_t _mag_topic;
orb_advert_t _subsystem_pub;
+ orb_id_t _mag_orb_id;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
+ perf_counter_t _range_errors;
+ perf_counter_t _conf_errors;
/* status reporting */
bool _sensor_ok; /**< sensor was found and reports ok */
bool _calibrated; /**< the calibration is valid */
int _bus; /**< the bus the device is connected to */
+ enum Rotation _rotation;
struct mag_report _last_report; /**< used for info() */
+ uint8_t _range_bits;
+ uint8_t _conf_reg;
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -230,6 +240,23 @@ private:
int set_range(unsigned range);
/**
+ * check the sensor range.
+ *
+ * checks that the range of the sensor is correctly set, to
+ * cope with communication errors causing the range to change
+ */
+ void check_range(void);
+
+ /**
+ * check the sensor configuration.
+ *
+ * checks that the config of the sensor is correctly set, to
+ * cope with communication errors causing the configuration to
+ * change
+ */
+ void check_conf(void);
+
+ /**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
*
@@ -311,6 +338,9 @@ private:
*/
int check_offset();
+ /* this class has pointer data members, do not allow copying it */
+ HMC5883(const HMC5883&);
+ HMC5883 operator=(const HMC5883&);
};
/*
@@ -319,23 +349,34 @@ private:
extern "C" __EXPORT int hmc5883_main(int argc, char *argv[]);
-HMC5883::HMC5883(int bus) :
- I2C("HMC5883", HMC5883L_DEVICE_PATH, bus, HMC5883L_ADDRESS, 400000),
+HMC5883::HMC5883(int bus, const char *path, enum Rotation rotation) :
+ I2C("HMC5883", path, bus, HMC5883L_ADDRESS, 400000),
+ _work{},
_measure_ticks(0),
_reports(nullptr),
+ _scale{},
_range_scale(0), /* default range scale from counts to gauss */
_range_ga(1.3f),
_collect_phase(false),
+ _class_instance(-1),
_mag_topic(-1),
_subsystem_pub(-1),
- _class_instance(-1),
+ _mag_orb_id(nullptr),
_sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")),
_comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")),
_buffer_overflows(perf_alloc(PC_COUNT, "hmc5883_buffer_overflows")),
+ _range_errors(perf_alloc(PC_COUNT, "hmc5883_range_errors")),
+ _conf_errors(perf_alloc(PC_COUNT, "hmc5883_conf_errors")),
_sensor_ok(false),
_calibrated(false),
- _bus(bus)
+ _bus(bus),
+ _rotation(rotation),
+ _last_report{0},
+ _range_bits(0),
+ _conf_reg(0)
{
+ _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_HMC5883;
+
// enable debug() calls
_debug_enabled = false;
@@ -366,6 +407,8 @@ HMC5883::~HMC5883()
perf_free(_sample_perf);
perf_free(_comms_errors);
perf_free(_buffer_overflows);
+ perf_free(_range_errors);
+ perf_free(_conf_errors);
}
int
@@ -387,6 +430,20 @@ HMC5883::init()
_class_instance = register_class_devname(MAG_DEVICE_PATH);
+ switch (_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _mag_orb_id = ORB_ID(sensor_mag0);
+ break;
+
+ case CLASS_DEVICE_SECONDARY:
+ _mag_orb_id = ORB_ID(sensor_mag1);
+ break;
+
+ case CLASS_DEVICE_TERTIARY:
+ _mag_orb_id = ORB_ID(sensor_mag2);
+ break;
+ }
+
ret = OK;
/* sensor is ok, but not calibrated */
_sensor_ok = true;
@@ -396,45 +453,43 @@ out:
int HMC5883::set_range(unsigned range)
{
- uint8_t range_bits;
-
if (range < 1) {
- range_bits = 0x00;
+ _range_bits = 0x00;
_range_scale = 1.0f / 1370.0f;
_range_ga = 0.88f;
} else if (range <= 1) {
- range_bits = 0x01;
+ _range_bits = 0x01;
_range_scale = 1.0f / 1090.0f;
_range_ga = 1.3f;
} else if (range <= 2) {
- range_bits = 0x02;
+ _range_bits = 0x02;
_range_scale = 1.0f / 820.0f;
_range_ga = 1.9f;
} else if (range <= 3) {
- range_bits = 0x03;
+ _range_bits = 0x03;
_range_scale = 1.0f / 660.0f;
_range_ga = 2.5f;
} else if (range <= 4) {
- range_bits = 0x04;
+ _range_bits = 0x04;
_range_scale = 1.0f / 440.0f;
_range_ga = 4.0f;
} else if (range <= 4.7f) {
- range_bits = 0x05;
+ _range_bits = 0x05;
_range_scale = 1.0f / 390.0f;
_range_ga = 4.7f;
} else if (range <= 5.6f) {
- range_bits = 0x06;
+ _range_bits = 0x06;
_range_scale = 1.0f / 330.0f;
_range_ga = 5.6f;
} else {
- range_bits = 0x07;
+ _range_bits = 0x07;
_range_scale = 1.0f / 230.0f;
_range_ga = 8.1f;
}
@@ -444,7 +499,7 @@ int HMC5883::set_range(unsigned range)
/*
* Send the command to set the range
*/
- ret = write_reg(ADDR_CONF_B, (range_bits << 5));
+ ret = write_reg(ADDR_CONF_B, (_range_bits << 5));
if (OK != ret)
perf_count(_comms_errors);
@@ -455,7 +510,53 @@ int HMC5883::set_range(unsigned range)
if (OK != ret)
perf_count(_comms_errors);
- return !(range_bits_in == (range_bits << 5));
+ return !(range_bits_in == (_range_bits << 5));
+}
+
+/**
+ check that the range register has the right value. This is done
+ periodically to cope with I2C bus noise causing the range of the
+ compass changing.
+ */
+void HMC5883::check_range(void)
+{
+ int ret;
+
+ uint8_t range_bits_in;
+ ret = read_reg(ADDR_CONF_B, range_bits_in);
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ return;
+ }
+ if (range_bits_in != (_range_bits<<5)) {
+ perf_count(_range_errors);
+ ret = write_reg(ADDR_CONF_B, (_range_bits << 5));
+ if (OK != ret)
+ perf_count(_comms_errors);
+ }
+}
+
+/**
+ check that the configuration register has the right value. This is
+ done periodically to cope with I2C bus noise causing the
+ configuration of the compass to change.
+ */
+void HMC5883::check_conf(void)
+{
+ int ret;
+
+ uint8_t conf_reg_in;
+ ret = read_reg(ADDR_CONF_A, conf_reg_in);
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ return;
+ }
+ if (conf_reg_in != _conf_reg) {
+ perf_count(_conf_errors);
+ ret = write_reg(ADDR_CONF_A, _conf_reg);
+ if (OK != ret)
+ perf_count(_comms_errors);
+ }
}
int
@@ -787,9 +888,10 @@ HMC5883::collect()
struct {
int16_t x, y, z;
} report;
- int ret = -EIO;
- uint8_t cmd;
+ int ret;
+ uint8_t cmd;
+ uint8_t check_counter;
perf_begin(_sample_perf);
struct mag_report new_report;
@@ -862,16 +964,19 @@ HMC5883::collect()
/* z remains z */
new_report.z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
- if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) {
+ // apply user specified rotation
+ rotate_3f(_rotation, new_report.x, new_report.y, new_report.z);
+
+ if (!(_pub_blocked)) {
if (_mag_topic != -1) {
/* publish it */
- orb_publish(ORB_ID(sensor_mag), _mag_topic, &new_report);
+ orb_publish(_mag_orb_id, _mag_topic, &new_report);
} else {
- _mag_topic = orb_advertise(ORB_ID(sensor_mag), &new_report);
+ _mag_topic = orb_advertise(_mag_orb_id, &new_report);
if (_mag_topic < 0)
- debug("failed to create sensor_mag publication");
+ debug("ADVERT FAIL");
}
}
@@ -885,6 +990,21 @@ HMC5883::collect()
/* notify anyone waiting for data */
poll_notify(POLLIN);
+ /*
+ periodically check the range register and configuration
+ registers. With a bad I2C cable it is possible for the
+ registers to become corrupt, leading to bad readings. It
+ doesn't happen often, but given the poor cables some
+ vehicles have it is worth checking for.
+ */
+ check_counter = perf_event_count(_sample_perf) % 256;
+ if (check_counter == 0) {
+ check_range();
+ }
+ if (check_counter == 128) {
+ check_conf();
+ }
+
ret = OK;
out:
@@ -929,11 +1049,9 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
* LSM/Ga, giving 1.16 and 1.08 */
float expected_cal[3] = { 1.16f, 1.08f, 1.08f };
- warnx("starting mag scale calibration");
-
/* start the sensor polling at 50 Hz */
if (OK != ioctl(filp, SENSORIOCSPOLLRATE, 50)) {
- warn("failed to set 2Hz poll rate");
+ warn("FAILED: SENSORIOCSPOLLRATE 2Hz");
ret = 1;
goto out;
}
@@ -941,25 +1059,25 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
/* Set to 2.5 Gauss. We ask for 3 to get the right part of
* the chained if statement above. */
if (OK != ioctl(filp, MAGIOCSRANGE, 3)) {
- warnx("failed to set 2.5 Ga range");
+ warnx("FAILED: MAGIOCSRANGE 3.3 Ga");
ret = 1;
goto out;
}
if (OK != ioctl(filp, MAGIOCEXSTRAP, 1)) {
- warnx("failed to enable sensor calibration mode");
+ warnx("FAILED: MAGIOCEXSTRAP 1");
ret = 1;
goto out;
}
if (OK != ioctl(filp, MAGIOCGSCALE, (long unsigned int)&mscale_previous)) {
- warn("WARNING: failed to get scale / offsets for mag");
+ warn("FAILED: MAGIOCGSCALE 1");
ret = 1;
goto out;
}
if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
- warn("WARNING: failed to set null scale / offsets for mag");
+ warn("FAILED: MAGIOCSSCALE 1");
ret = 1;
goto out;
}
@@ -974,7 +1092,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
ret = ::poll(&fds, 1, 2000);
if (ret != 1) {
- warn("timed out waiting for sensor data");
+ warn("ERROR: TIMEOUT 1");
goto out;
}
@@ -982,7 +1100,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
sz = ::read(fd, &report, sizeof(report));
if (sz != sizeof(report)) {
- warn("periodic read failed");
+ warn("ERROR: READ 1");
ret = -EIO;
goto out;
}
@@ -998,7 +1116,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
ret = ::poll(&fds, 1, 2000);
if (ret != 1) {
- warn("timed out waiting for sensor data");
+ warn("ERROR: TIMEOUT 2");
goto out;
}
@@ -1006,7 +1124,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
sz = ::read(fd, &report, sizeof(report));
if (sz != sizeof(report)) {
- warn("periodic read failed");
+ warn("ERROR: READ 2");
ret = -EIO;
goto out;
}
@@ -1022,33 +1140,19 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
sum_excited[1] += cal[1];
sum_excited[2] += cal[2];
}
-
- //warnx("periodic read %u", i);
- //warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
- //warnx("cal: %.6f %.6f %.6f", (double)cal[0], (double)cal[1], (double)cal[2]);
}
if (good_count < 5) {
- warn("failed calibration");
ret = -EIO;
goto out;
}
-#if 0
- warnx("measurement avg: %.6f %.6f %.6f",
- (double)sum_excited[0]/good_count,
- (double)sum_excited[1]/good_count,
- (double)sum_excited[2]/good_count);
-#endif
-
float scaling[3];
scaling[0] = sum_excited[0] / good_count;
scaling[1] = sum_excited[1] / good_count;
scaling[2] = sum_excited[2] / good_count;
- warnx("axes scaling: %.6f %.6f %.6f", (double)scaling[0], (double)scaling[1], (double)scaling[2]);
-
/* set scaling in device */
mscale_previous.x_scale = scaling[0];
mscale_previous.y_scale = scaling[1];
@@ -1059,29 +1163,26 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
out:
if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_previous)) {
- warn("WARNING: failed to set new scale / offsets for mag");
+ warn("FAILED: MAGIOCSSCALE 2");
}
/* set back to normal mode */
/* Set to 1.1 Gauss */
if (OK != ::ioctl(fd, MAGIOCSRANGE, 1)) {
- warnx("failed to set 1.1 Ga range");
+ warnx("FAILED: MAGIOCSRANGE 1.1 Ga");
}
if (OK != ::ioctl(fd, MAGIOCEXSTRAP, 0)) {
- warnx("failed to disable sensor calibration mode");
+ warnx("FAILED: MAGIOCEXSTRAP 0");
}
if (ret == OK) {
- if (!check_scale()) {
- warnx("mag scale calibration successfully finished.");
- } else {
- warnx("mag scale calibration finished with invalid results.");
+ if (check_scale()) {
+ /* failed */
+ warnx("FAILED: SCALE");
ret = ERROR;
}
- } else {
- warnx("mag scale calibration failed.");
}
return ret;
@@ -1158,25 +1259,23 @@ int HMC5883::set_excitement(unsigned enable)
{
int ret;
/* arm the excitement strap */
- uint8_t conf_reg;
- ret = read_reg(ADDR_CONF_A, conf_reg);
+ ret = read_reg(ADDR_CONF_A, _conf_reg);
if (OK != ret)
perf_count(_comms_errors);
+ _conf_reg &= ~0x03; // reset previous excitement mode
if (((int)enable) < 0) {
- conf_reg |= 0x01;
+ _conf_reg |= 0x01;
} else if (enable > 0) {
- conf_reg |= 0x02;
+ _conf_reg |= 0x02;
- } else {
- conf_reg &= ~0x03;
}
- // ::printf("set_excitement enable=%d regA=0x%x\n", (int)enable, (unsigned)conf_reg);
+ // ::printf("set_excitement enable=%d regA=0x%x\n", (int)enable, (unsigned)_conf_reg);
- ret = write_reg(ADDR_CONF_A, conf_reg);
+ ret = write_reg(ADDR_CONF_A, _conf_reg);
if (OK != ret)
perf_count(_comms_errors);
@@ -1186,7 +1285,7 @@ int HMC5883::set_excitement(unsigned enable)
//print_info();
- return !(conf_reg == conf_reg_ret);
+ return !(_conf_reg == conf_reg_ret);
}
int
@@ -1228,7 +1327,7 @@ HMC5883::print_info()
printf("offsets (%.2f %.2f %.2f)\n", (double)_scale.x_offset, (double)_scale.y_offset, (double)_scale.z_offset);
printf("scaling (%.2f %.2f %.2f) 1/range_scale %.2f range_ga %.2f\n",
(double)_scale.x_scale, (double)_scale.y_scale, (double)_scale.z_scale,
- (double)1.0/_range_scale, (double)_range_ga);
+ (double)(1.0f/_range_scale), (double)_range_ga);
_reports->print_info("report queue");
}
@@ -1244,63 +1343,95 @@ namespace hmc5883
#endif
const int ERROR = -1;
-HMC5883 *g_dev;
+HMC5883 *g_dev_int = nullptr;
+HMC5883 *g_dev_ext = nullptr;
-void start();
-void test();
-void reset();
-void info();
-int calibrate();
+void start(int bus, enum Rotation rotation);
+void test(int bus);
+void reset(int bus);
+void info(int bus);
+int calibrate(int bus);
+void usage();
/**
* Start the driver.
+ *
+ * This function call only returns once the driver
+ * is either successfully up and running or failed to start.
*/
void
-start()
+start(int bus, enum Rotation rotation)
{
int fd;
- if (g_dev != nullptr)
- /* if already started, the still command succeeded */
- errx(0, "already started");
-
/* create the driver, attempt expansion bus first */
- g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION);
- if (g_dev != nullptr && OK != g_dev->init()) {
- delete g_dev;
- g_dev = nullptr;
+ if (bus == -1 || bus == PX4_I2C_BUS_EXPANSION) {
+ if (g_dev_ext != nullptr)
+ errx(0, "already started external");
+ g_dev_ext = new HMC5883(PX4_I2C_BUS_EXPANSION, HMC5883L_DEVICE_PATH_EXT, rotation);
+ if (g_dev_ext != nullptr && OK != g_dev_ext->init()) {
+ delete g_dev_ext;
+ g_dev_ext = nullptr;
+ }
}
#ifdef PX4_I2C_BUS_ONBOARD
/* if this failed, attempt onboard sensor */
- if (g_dev == nullptr) {
- g_dev = new HMC5883(PX4_I2C_BUS_ONBOARD);
- if (g_dev != nullptr && OK != g_dev->init()) {
+ if (bus == -1 || bus == PX4_I2C_BUS_ONBOARD) {
+ if (g_dev_int != nullptr)
+ errx(0, "already started internal");
+ g_dev_int = new HMC5883(PX4_I2C_BUS_ONBOARD, HMC5883L_DEVICE_PATH_INT, rotation);
+ if (g_dev_int != nullptr && OK != g_dev_int->init()) {
+
+ /* tear down the failing onboard instance */
+ delete g_dev_int;
+ g_dev_int = nullptr;
+
+ if (bus == PX4_I2C_BUS_ONBOARD) {
+ goto fail;
+ }
+ }
+ if (g_dev_int == nullptr && bus == PX4_I2C_BUS_ONBOARD) {
goto fail;
}
}
#endif
- if (g_dev == nullptr)
+ if (g_dev_int == nullptr && g_dev_ext == nullptr)
goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
+ if (g_dev_int != nullptr) {
+ fd = open(HMC5883L_DEVICE_PATH_INT, O_RDONLY);
+ if (fd < 0)
+ goto fail;
- if (fd < 0)
- goto fail;
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ goto fail;
+ close(fd);
+ }
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
- goto fail;
+ if (g_dev_ext != nullptr) {
+ fd = open(HMC5883L_DEVICE_PATH_EXT, O_RDONLY);
+ if (fd < 0)
+ goto fail;
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ goto fail;
+ close(fd);
+ }
exit(0);
fail:
-
- if (g_dev != nullptr) {
- delete g_dev;
- g_dev = nullptr;
+ if (g_dev_int != nullptr && (bus == -1 || bus == PX4_I2C_BUS_ONBOARD)) {
+ delete g_dev_int;
+ g_dev_int = nullptr;
+ }
+ if (g_dev_ext != nullptr && (bus == -1 || bus == PX4_I2C_BUS_EXPANSION)) {
+ delete g_dev_ext;
+ g_dev_ext = nullptr;
}
errx(1, "driver start failed");
@@ -1312,16 +1443,17 @@ fail:
* and automatic modes.
*/
void
-test()
+test(int bus)
{
struct mag_report report;
ssize_t sz;
int ret;
+ const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT);
- int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
+ int fd = open(path, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", HMC5883L_DEVICE_PATH);
+ err(1, "%s open failed (try 'hmc5883 start')", path);
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
@@ -1414,14 +1546,15 @@ test()
* configuration register A back to 00 (Normal Measurement Mode), e.g. 0x10.
* Using the self test method described above, the user can scale sensor
*/
-int calibrate()
+int calibrate(int bus)
{
int ret;
+ const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT);
- int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
+ int fd = open(path, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", HMC5883L_DEVICE_PATH);
+ err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", path);
if (OK != (ret = ioctl(fd, MAGIOCCALIBRATE, fd))) {
warnx("failed to enable sensor calibration mode");
@@ -1441,9 +1574,11 @@ int calibrate()
* Reset the driver.
*/
void
-reset()
+reset(int bus)
{
- int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY);
+ const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT);
+
+ int fd = open(path, O_RDONLY);
if (fd < 0)
err(1, "failed ");
@@ -1461,8 +1596,9 @@ reset()
* Print a little info about the driver.
*/
void
-info()
+info(int bus)
{
+ HMC5883 *g_dev = (bus == PX4_I2C_BUS_ONBOARD?g_dev_int:g_dev_ext);
if (g_dev == nullptr)
errx(1, "driver not running");
@@ -1472,40 +1608,91 @@ info()
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'info', 'test', 'reset', 'info', 'calibrate'");
+ warnx("options:");
+ warnx(" -R rotation");
+ warnx(" -C calibrate on start");
+ warnx(" -X only external bus");
+#ifdef PX4_I2C_BUS_ONBOARD
+ warnx(" -I only internal bus");
+#endif
+}
+
} // namespace
int
hmc5883_main(int argc, char *argv[])
{
+ int ch;
+ int bus = -1;
+ enum Rotation rotation = ROTATION_NONE;
+ bool calibrate = false;
+
+ while ((ch = getopt(argc, argv, "XIR:C")) != EOF) {
+ switch (ch) {
+ case 'R':
+ rotation = (enum Rotation)atoi(optarg);
+ break;
+#ifdef PX4_I2C_BUS_ONBOARD
+ case 'I':
+ bus = PX4_I2C_BUS_ONBOARD;
+ break;
+#endif
+ case 'X':
+ bus = PX4_I2C_BUS_EXPANSION;
+ break;
+ case 'C':
+ calibrate = true;
+ break;
+ default:
+ hmc5883::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
- hmc5883::start();
+ if (!strcmp(verb, "start")) {
+ hmc5883::start(bus, rotation);
+ if (calibrate) {
+ if (hmc5883::calibrate(bus) == 0) {
+ errx(0, "calibration successful");
+
+ } else {
+ errx(1, "calibration failed");
+ }
+ }
+ }
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
- hmc5883::test();
+ if (!strcmp(verb, "test"))
+ hmc5883::test(bus);
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
- hmc5883::reset();
+ if (!strcmp(verb, "reset"))
+ hmc5883::reset(bus);
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
- hmc5883::info();
+ if (!strcmp(verb, "info") || !strcmp(verb, "status"))
+ hmc5883::info(bus);
/*
* Autocalibrate the scaling
*/
- if (!strcmp(argv[1], "calibrate")) {
- if (hmc5883::calibrate() == 0) {
+ if (!strcmp(verb, "calibrate")) {
+ if (hmc5883::calibrate(bus) == 0) {
errx(0, "calibration successful");
} else {
diff --git a/src/drivers/hmc5883/module.mk b/src/drivers/hmc5883/module.mk
index 07377556d..be2ee7276 100644
--- a/src/drivers/hmc5883/module.mk
+++ b/src/drivers/hmc5883/module.mk
@@ -37,7 +37,10 @@
MODULE_COMMAND = hmc5883
-# XXX seems excessive, check if 2048 is sufficient
-MODULE_STACKSIZE = 4096
-
SRCS = hmc5883.cpp
+
+MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/hott/comms.cpp b/src/drivers/hott/comms.cpp
index cb8bbba37..60a49b559 100644
--- a/src/drivers/hott/comms.cpp
+++ b/src/drivers/hott/comms.cpp
@@ -55,7 +55,7 @@ open_uart(const char *device)
const int uart = open(device, O_RDWR | O_NOCTTY);
if (uart < 0) {
- err(1, "Error opening port: %s", device);
+ err(1, "ERR: opening %s", device);
}
/* Back up the original uart configuration to restore it after exit */
@@ -63,7 +63,7 @@ open_uart(const char *device)
struct termios uart_config_original;
if ((termios_state = tcgetattr(uart, &uart_config_original)) < 0) {
close(uart);
- err(1, "Error getting baudrate / termios config for %s: %d", device, termios_state);
+ err(1, "ERR: %s: %d", device, termios_state);
}
/* Fill the struct for the new configuration */
@@ -76,13 +76,13 @@ open_uart(const char *device)
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
close(uart);
- err(1, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)",
+ err(1, "ERR: %s: %d (cfsetispeed, cfsetospeed)",
device, termios_state);
}
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
close(uart);
- err(1, "Error setting baudrate / termios config for %s (tcsetattr)", device);
+ err(1, "ERR: %s (tcsetattr)", device);
}
/* Activate single wire mode */
diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp
index a3d3a3933..8ab9d8d55 100644
--- a/src/drivers/hott/hott_sensors/hott_sensors.cpp
+++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp
@@ -204,7 +204,7 @@ hott_sensors_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- warnx("deamon already running");
+ warnx("already running");
exit(0);
}
@@ -225,10 +225,10 @@ hott_sensors_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- warnx("daemon is running");
+ warnx("is running");
} else {
- warnx("daemon not started");
+ warnx("not started");
}
exit(0);
diff --git a/src/drivers/hott/hott_sensors/module.mk b/src/drivers/hott/hott_sensors/module.mk
index b5f5762ba..47aea6caf 100644
--- a/src/drivers/hott/hott_sensors/module.mk
+++ b/src/drivers/hott/hott_sensors/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = hott_sensors
SRCS = hott_sensors.cpp \
../messages.cpp \
../comms.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
index d293f9954..edbb14172 100644
--- a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
+++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
@@ -230,7 +230,7 @@ hott_telemetry_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- warnx("deamon already running");
+ warnx("already running");
exit(0);
}
@@ -251,10 +251,10 @@ hott_telemetry_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- warnx("daemon is running");
+ warnx("is running");
} else {
- warnx("daemon not started");
+ warnx("not started");
}
exit(0);
diff --git a/src/drivers/hott/hott_telemetry/module.mk b/src/drivers/hott/hott_telemetry/module.mk
index b19cbd14c..cd7bdbc85 100644
--- a/src/drivers/hott/hott_telemetry/module.mk
+++ b/src/drivers/hott/hott_telemetry/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = hott_telemetry
SRCS = hott_telemetry.cpp \
../messages.cpp \
../comms.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
index 1e779e8dc..f1b12b067 100644
--- a/src/drivers/hott/messages.cpp
+++ b/src/drivers/hott/messages.cpp
@@ -115,9 +115,9 @@ publish_gam_message(const uint8_t *buffer)
esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
- esc.esc[0].esc_temperature = msg.temperature1 - 20;
- esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
- esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
+ esc.esc[0].esc_temperature = static_cast<float>(msg.temperature1) - 20.0F;
+ esc.esc[0].esc_voltage = static_cast<float>((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff)) * 0.1F;
+ esc.esc[0].esc_current = static_cast<float>((msg.current_H << 8) | (msg.current_L & 0xff)) * 0.1F;
/* announce the esc if needed, just publish else */
if (_esc_pub > 0) {
@@ -186,18 +186,18 @@ build_gam_response(uint8_t *buffer, size_t *size)
msg.gam_sensor_id = GAM_SENSOR_ID;
msg.sensor_text_id = GAM_SENSOR_TEXT_ID;
- msg.temperature1 = (uint8_t)(esc.esc[0].esc_temperature + 20);
+ msg.temperature1 = (uint8_t)(esc.esc[0].esc_temperature + 20.0F);
msg.temperature2 = 20; // 0 deg. C.
- uint16_t voltage = (uint16_t)(esc.esc[0].esc_voltage);
+ const uint16_t voltage = (uint16_t)(esc.esc[0].esc_voltage * 10.0F);
msg.main_voltage_L = (uint8_t)voltage & 0xff;
msg.main_voltage_H = (uint8_t)(voltage >> 8) & 0xff;
- uint16_t current = (uint16_t)(esc.esc[0].esc_current);
+ const uint16_t current = (uint16_t)(esc.esc[0].esc_current * 10.0F);
msg.current_L = (uint8_t)current & 0xff;
msg.current_H = (uint8_t)(current >> 8) & 0xff;
- uint16_t rpm = (uint16_t)(esc.esc[0].esc_rpm * 0.1f);
+ const uint16_t rpm = (uint16_t)(esc.esc[0].esc_rpm * 0.1f);
msg.rpm_L = (uint8_t)rpm & 0xff;
msg.rpm_H = (uint8_t)(rpm >> 8) & 0xff;
@@ -226,7 +226,7 @@ build_gps_response(uint8_t *buffer, size_t *size)
msg.sensor_id = GPS_SENSOR_ID;
msg.sensor_text_id = GPS_SENSOR_TEXT_ID;
- msg.gps_num_sat = gps.satellites_visible;
+ msg.gps_num_sat = gps.satellites_used;
/* The GPS fix type: 0 = none, 2 = 2D, 3 = 3D */
msg.gps_fix_char = (uint8_t)(gps.fix_type + 48);
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 37e72388b..82fa5cc6e 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -54,6 +54,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <getopt.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@@ -68,6 +69,7 @@
#include <board_config.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
+#include <lib/conversion/rotation.h>
#define L3GD20_DEVICE_PATH "/dev/l3gd20"
@@ -174,6 +176,7 @@ static const int ERROR = -1;
#define L3G4200D_DEFAULT_RATE 800
#define L3GD20_DEFAULT_RANGE_DPS 2000
#define L3GD20_DEFAULT_FILTER_FREQ 30
+#define L3GD20_TEMP_OFFSET_CELSIUS 40
#ifndef SENSOR_BOARD_ROTATION_DEFAULT
#define SENSOR_BOARD_ROTATION_DEFAULT SENSOR_BOARD_ROTATION_270_DEG
@@ -184,7 +187,7 @@ extern "C" { __EXPORT int l3gd20_main(int argc, char *argv[]); }
class L3GD20 : public device::SPI
{
public:
- L3GD20(int bus, const char* path, spi_dev_e device);
+ L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotation);
virtual ~L3GD20();
virtual int init();
@@ -211,6 +214,7 @@ private:
float _gyro_range_scale;
float _gyro_range_rad_s;
orb_advert_t _gyro_topic;
+ orb_id_t _orb_id;
int _class_instance;
unsigned _current_rate;
@@ -229,6 +233,8 @@ private:
/* true if an L3G4200D is detected */
bool _is_l3g4200d;
+ enum Rotation _rotation;
+
/**
* Start automatic measurement.
*/
@@ -326,15 +332,22 @@ private:
* @return 0 on success, 1 on failure
*/
int self_test();
+
+ /* this class does not allow copying */
+ L3GD20(const L3GD20&);
+ L3GD20 operator=(const L3GD20&);
};
-L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
+L3GD20::L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotation) :
SPI("L3GD20", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within margins for L3GD20 */),
+ _call{},
_call_interval(0),
_reports(nullptr),
+ _gyro_scale{},
_gyro_range_scale(0.0f),
_gyro_range_rad_s(0.0f),
_gyro_topic(-1),
+ _orb_id(nullptr),
_class_instance(-1),
_current_rate(0),
_orientation(SENSOR_BOARD_ROTATION_DEFAULT),
@@ -345,7 +358,8 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
_gyro_filter_x(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
_gyro_filter_y(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
_gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
- _is_l3g4200d(false)
+ _is_l3g4200d(false),
+ _rotation(rotation)
{
// enable debug() calls
_debug_enabled = true;
@@ -394,21 +408,32 @@ L3GD20::init()
_class_instance = register_class_devname(GYRO_DEVICE_PATH);
- reset();
+ switch (_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _orb_id = ORB_ID(sensor_gyro0);
+ break;
- measure();
+ case CLASS_DEVICE_SECONDARY:
+ _orb_id = ORB_ID(sensor_gyro1);
+ break;
+
+ case CLASS_DEVICE_TERTIARY:
+ _orb_id = ORB_ID(sensor_gyro2);
+ break;
+ }
- if (_class_instance == CLASS_DEVICE_PRIMARY) {
+ reset();
- /* advertise sensor topic, measure manually to initialize valid report */
- struct gyro_report grp;
- _reports->get(&grp);
+ measure();
- _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grp);
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct gyro_report grp;
+ _reports->get(&grp);
- if (_gyro_topic < 0)
- debug("failed to create sensor_gyro publication");
+ _gyro_topic = orb_advertise(_orb_id, &grp);
+ if (_gyro_topic < 0) {
+ debug("failed to create sensor_gyro publication");
}
ret = OK;
@@ -821,7 +846,7 @@ L3GD20::measure()
// if the gyro doesn't have any data ready then re-schedule
// for 100 microseconds later. This ensures we don't double
// read a value and then miss the next value
- if (stm32_gpioread(GPIO_EXTI_GYRO_DRDY) == 0) {
+ if (_bus == PX4_SPI_BUS_SENSORS && stm32_gpioread(GPIO_EXTI_GYRO_DRDY) == 0) {
perf_count(_reschedules);
hrt_call_delay(&_call, 100);
return;
@@ -832,7 +857,7 @@ L3GD20::measure()
#pragma pack(push, 1)
struct {
uint8_t cmd;
- uint8_t temp;
+ int8_t temp;
uint8_t status;
int16_t x;
int16_t y;
@@ -906,6 +931,8 @@ L3GD20::measure()
report.z_raw = raw_report.z;
+ report.temperature_raw = raw_report.temp;
+
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;
@@ -914,6 +941,11 @@ L3GD20::measure()
report.y = _gyro_filter_y.apply(report.y);
report.z = _gyro_filter_z.apply(report.z);
+ report.temperature = L3GD20_TEMP_OFFSET_CELSIUS - raw_report.temp;
+
+ // apply user specified rotation
+ rotate_3f(_rotation, report.x, report.y, report.z);
+
report.scaling = _gyro_range_scale;
report.range_rad_s = _gyro_range_rad_s;
@@ -923,9 +955,9 @@ L3GD20::measure()
poll_notify(POLLIN);
/* publish for subscribers */
- if (_gyro_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &report);
+ orb_publish(_orb_id, _gyro_topic, &report);
}
_read++;
@@ -974,16 +1006,20 @@ namespace l3gd20
L3GD20 *g_dev;
-void start();
+void usage();
+void start(bool external_bus, enum Rotation rotation);
void test();
void reset();
void info();
/**
* Start the driver.
+ *
+ * This function call only returns once the driver
+ * started or failed to detect the sensor.
*/
void
-start()
+start(bool external_bus, enum Rotation rotation)
{
int fd;
@@ -991,7 +1027,15 @@ start()
errx(0, "already started");
/* create the driver */
- g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
+ if (external_bus) {
+#ifdef PX4_SPI_BUS_EXT
+ g_dev = new L3GD20(PX4_SPI_BUS_EXT, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_EXT_GYRO, rotation);
+#else
+ errx(0, "External SPI not available");
+#endif
+ } else {
+ g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO, rotation);
+ }
if (g_dev == nullptr)
goto fail;
@@ -1052,9 +1096,11 @@ test()
warnx("gyro x: \t% 9.5f\trad/s", (double)g_report.x);
warnx("gyro y: \t% 9.5f\trad/s", (double)g_report.y);
warnx("gyro z: \t% 9.5f\trad/s", (double)g_report.z);
+ warnx("temp: \t%d\tC", (int)g_report.temperature);
warnx("gyro x: \t%d\traw", (int)g_report.x_raw);
warnx("gyro y: \t%d\traw", (int)g_report.y_raw);
warnx("gyro z: \t%d\traw", (int)g_report.z_raw);
+ warnx("temp: \t%d\traw", (int)g_report.temperature_raw);
warnx("gyro range: %8.4f rad/s (%d deg/s)", (double)g_report.range_rad_s,
(int)((g_report.range_rad_s / M_PI_F) * 180.0f + 0.5f));
@@ -1103,35 +1149,64 @@ info()
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'info', 'test', 'reset'");
+ warnx("options:");
+ warnx(" -X (external bus)");
+ warnx(" -R rotation");
+}
} // namespace
int
l3gd20_main(int argc, char *argv[])
{
+ bool external_bus = false;
+ int ch;
+ enum Rotation rotation = ROTATION_NONE;
+
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc, argv, "XR:")) != EOF) {
+ switch (ch) {
+ case 'X':
+ external_bus = true;
+ break;
+ case 'R':
+ rotation = (enum Rotation)atoi(optarg);
+ break;
+ default:
+ l3gd20::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
- l3gd20::start();
+ if (!strcmp(verb, "start"))
+ l3gd20::start(external_bus, rotation);
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
+ if (!strcmp(verb, "test"))
l3gd20::test();
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
+ if (!strcmp(verb, "reset"))
l3gd20::reset();
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info"))
+ if (!strcmp(verb, "info"))
l3gd20::info();
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
diff --git a/src/drivers/l3gd20/module.mk b/src/drivers/l3gd20/module.mk
index 23e77e871..3d64d62be 100644
--- a/src/drivers/l3gd20/module.mk
+++ b/src/drivers/l3gd20/module.mk
@@ -4,3 +4,9 @@
MODULE_COMMAND = l3gd20
SRCS = l3gd20.cpp
+
+MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/led/module.mk b/src/drivers/led/module.mk
index 777f3e442..5b7b4491b 100644
--- a/src/drivers/led/module.mk
+++ b/src/drivers/led/module.mk
@@ -36,3 +36,5 @@
#
SRCS = led.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp
new file mode 100644
index 000000000..6793acd81
--- /dev/null
+++ b/src/drivers/ll40ls/ll40ls.cpp
@@ -0,0 +1,1010 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file ll40ls.cpp
+ * @author Allyson Kreft
+ *
+ * Driver for the PulsedLight Lidar-Lite range finders connected via I2C.
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <string.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <errno.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_range_finder.h>
+#include <drivers/device/ringbuffer.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/subsystem_info.h>
+
+#include <board_config.h>
+
+/* Configuration Constants */
+#define LL40LS_BUS PX4_I2C_BUS_EXPANSION
+#define LL40LS_BASEADDR 0x62 /* 7-bit address */
+#define LL40LS_BASEADDR_OLD 0x42 /* previous 7-bit address */
+#define LL40LS_DEVICE_PATH_INT "/dev/ll40ls_int"
+#define LL40LS_DEVICE_PATH_EXT "/dev/ll40ls_ext"
+
+/* LL40LS Registers addresses */
+
+#define LL40LS_MEASURE_REG 0x00 /* Measure range register */
+#define LL40LS_MSRREG_ACQUIRE 0x04 /* Value to initiate a measurement, varies based on sensor revision */
+#define LL40LS_DISTHIGH_REG 0x8F /* High byte of distance register, auto increment */
+#define LL40LS_WHO_AM_I_REG 0x11
+#define LL40LS_WHO_AM_I_REG_VAL 0xCA
+#define LL40LS_SIGNAL_STRENGTH_REG 0x5b
+
+/* Device limits */
+#define LL40LS_MIN_DISTANCE (0.00f)
+#define LL40LS_MAX_DISTANCE (14.00f)
+
+#define LL40LS_CONVERSION_INTERVAL 100000 /* 100ms */
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error This requires CONFIG_SCHED_WORKQUEUE.
+#endif
+
+class LL40LS : public device::I2C
+{
+public:
+ LL40LS(int bus, const char *path, int address = LL40LS_BASEADDR);
+ virtual ~LL40LS();
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ /**
+ * Diagnostics - print some basic information about the driver.
+ */
+ void print_info();
+
+protected:
+ virtual int probe();
+ virtual int read_reg(uint8_t reg, uint8_t &val);
+
+private:
+ float _min_distance;
+ float _max_distance;
+ work_s _work;
+ RingBuffer *_reports;
+ bool _sensor_ok;
+ int _measure_ticks;
+ bool _collect_phase;
+ int _class_instance;
+
+ orb_advert_t _range_finder_topic;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+ perf_counter_t _buffer_overflows;
+ uint16_t _last_distance;
+
+ /**< the bus the device is connected to */
+ int _bus;
+
+ /**
+ * Test whether the device supported by the driver is present at a
+ * specific address.
+ *
+ * @param address The I2C bus address to probe.
+ * @return True if the device is present.
+ */
+ int probe_address(uint8_t address);
+
+ /**
+ * Initialise the automatic measurement state machine and start it.
+ *
+ * @note This function is called at open and error time. It might make sense
+ * to make it more aggressive about resetting the bus in case of errors.
+ */
+ void start();
+
+ /**
+ * Stop the automatic measurement state machine.
+ */
+ void stop();
+
+ /**
+ * Set the min and max distance thresholds if you want the end points of the sensors
+ * range to be brought in at all, otherwise it will use the defaults LL40LS_MIN_DISTANCE
+ * and LL40LS_MAX_DISTANCE
+ */
+ void set_minimum_distance(float min);
+ void set_maximum_distance(float max);
+ float get_minimum_distance();
+ float get_maximum_distance();
+
+ /**
+ * Perform a poll cycle; collect from the previous measurement
+ * and start a new one.
+ */
+ void cycle();
+ int measure();
+ int collect();
+ /**
+ * Static trampoline from the workq context; because we don't have a
+ * generic workq wrapper yet.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void cycle_trampoline(void *arg);
+
+
+};
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int ll40ls_main(int argc, char *argv[]);
+
+LL40LS::LL40LS(int bus, const char *path, int address) :
+ I2C("LL40LS", path, bus, address, 100000),
+ _min_distance(LL40LS_MIN_DISTANCE),
+ _max_distance(LL40LS_MAX_DISTANCE),
+ _reports(nullptr),
+ _sensor_ok(false),
+ _measure_ticks(0),
+ _collect_phase(false),
+ _class_instance(-1),
+ _range_finder_topic(-1),
+ _sample_perf(perf_alloc(PC_ELAPSED, "ll40ls_read")),
+ _comms_errors(perf_alloc(PC_COUNT, "ll40ls_comms_errors")),
+ _buffer_overflows(perf_alloc(PC_COUNT, "ll40ls_buffer_overflows")),
+ _last_distance(0),
+ _bus(bus)
+{
+ // up the retries since the device misses the first measure attempts
+ _retries = 3;
+
+ // enable debug() calls
+ _debug_enabled = false;
+
+ // work_cancel in the dtor will explode if we don't do this...
+ memset(&_work, 0, sizeof(_work));
+}
+
+LL40LS::~LL40LS()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ /* free any existing reports */
+ if (_reports != nullptr) {
+ delete _reports;
+ }
+
+ if (_class_instance != -1) {
+ unregister_class_devname(RANGE_FINDER_DEVICE_PATH, _class_instance);
+ }
+
+ // free perf counters
+ perf_free(_sample_perf);
+ perf_free(_comms_errors);
+ perf_free(_buffer_overflows);
+}
+
+int
+LL40LS::init()
+{
+ int ret = ERROR;
+
+ /* do I2C init (and probe) first */
+ if (I2C::init() != OK) {
+ goto out;
+ }
+
+ /* allocate basic report buffers */
+ _reports = new RingBuffer(2, sizeof(range_finder_report));
+
+ if (_reports == nullptr) {
+ goto out;
+ }
+
+ _class_instance = register_class_devname(RANGE_FINDER_DEVICE_PATH);
+
+ if (_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* get a publish handle on the range finder topic */
+ struct range_finder_report rf_report;
+ measure();
+ _reports->get(&rf_report);
+ _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &rf_report);
+
+ if (_range_finder_topic < 0) {
+ debug("failed to create sensor_range_finder object. Did you start uOrb?");
+ }
+ }
+
+ ret = OK;
+ /* sensor is ok, but we don't really know if it is within range */
+ _sensor_ok = true;
+out:
+ return ret;
+}
+
+int
+LL40LS::read_reg(uint8_t reg, uint8_t &val)
+{
+ return transfer(&reg, 1, &val, 1);
+}
+
+int
+LL40LS::probe()
+{
+ // cope with both old and new I2C bus address
+ const uint8_t addresses[2] = {LL40LS_BASEADDR, LL40LS_BASEADDR_OLD};
+
+ // more retries for detection
+ _retries = 10;
+
+ for (uint8_t i=0; i<sizeof(addresses); i++) {
+ uint8_t val=0, who_am_i=0;
+
+ // set the I2C bus address
+ set_address(addresses[i]);
+
+ if (read_reg(LL40LS_WHO_AM_I_REG, who_am_i) == OK && who_am_i == LL40LS_WHO_AM_I_REG_VAL) {
+ // it is responding correctly to a WHO_AM_I
+ goto ok;
+ }
+
+ if (read_reg(LL40LS_SIGNAL_STRENGTH_REG, val) == OK && val != 0) {
+ // very likely to be a ll40ls. px4flow does not
+ // respond to this
+ goto ok;
+ }
+
+ debug("WHO_AM_I byte mismatch 0x%02x should be 0x%02x val=0x%02x\n",
+ (unsigned)who_am_i,
+ LL40LS_WHO_AM_I_REG_VAL,
+ (unsigned)val);
+ }
+
+ // not found on any address
+ return -EIO;
+
+ok:
+ _retries = 3;
+
+ // start a measurement
+ return measure();
+}
+
+void
+LL40LS::set_minimum_distance(float min)
+{
+ _min_distance = min;
+}
+
+void
+LL40LS::set_maximum_distance(float max)
+{
+ _max_distance = max;
+}
+
+float
+LL40LS::get_minimum_distance()
+{
+ return _min_distance;
+}
+
+float
+LL40LS::get_maximum_distance()
+{
+ return _max_distance;
+}
+
+int
+LL40LS::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case SENSORIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _measure_ticks = 0;
+ return OK;
+
+ /* external signalling (DRDY) not supported */
+ case SENSOR_POLLRATE_EXTERNAL:
+
+ /* zero would be bad */
+ case 0:
+ return -EINVAL;
+
+ /* set default/max polling rate */
+ case SENSOR_POLLRATE_MAX:
+ case SENSOR_POLLRATE_DEFAULT: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* set interval for next measurement to minimum legal value */
+ _measure_ticks = USEC2TICK(LL40LS_CONVERSION_INTERVAL);
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start) {
+ start();
+ }
+
+ return OK;
+ }
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* convert hz to tick interval via microseconds */
+ unsigned ticks = USEC2TICK(1000000 / arg);
+
+ /* check against maximum rate */
+ if (ticks < USEC2TICK(LL40LS_CONVERSION_INTERVAL)) {
+ return -EINVAL;
+ }
+
+ /* update interval for next measurement */
+ _measure_ticks = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start) {
+ start();
+ }
+
+ return OK;
+ }
+ }
+ }
+
+ case SENSORIOCGPOLLRATE:
+ if (_measure_ticks == 0) {
+ return SENSOR_POLLRATE_MANUAL;
+ }
+
+ return (1000 / _measure_ticks);
+
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100)) {
+ return -EINVAL;
+ }
+
+ irqstate_t flags = irqsave();
+
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+
+ irqrestore(flags);
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _reports->size();
+
+ case SENSORIOCRESET:
+ /* XXX implement this */
+ return -EINVAL;
+
+ case RANGEFINDERIOCSETMINIUMDISTANCE: {
+ set_minimum_distance(*(float *)arg);
+ return 0;
+ }
+ break;
+
+ case RANGEFINDERIOCSETMAXIUMDISTANCE: {
+ set_maximum_distance(*(float *)arg);
+ return 0;
+ }
+ break;
+
+ default:
+ /* give it to the superclass */
+ return I2C::ioctl(filp, cmd, arg);
+ }
+}
+
+ssize_t
+LL40LS::read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct range_finder_report);
+ struct range_finder_report *rbuf = reinterpret_cast<struct range_finder_report *>(buffer);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1) {
+ return -ENOSPC;
+ }
+
+ /* if automatic measurement is enabled */
+ if (_measure_ticks > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ * Note that we may be pre-empted by the workq thread while we are doing this;
+ * we are careful to avoid racing with them.
+ */
+ while (count--) {
+ if (_reports->get(rbuf)) {
+ ret += sizeof(*rbuf);
+ rbuf++;
+ }
+ }
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement - run one conversion */
+ do {
+ _reports->flush();
+
+ /* trigger a measurement */
+ if (OK != measure()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* wait for it to complete */
+ usleep(LL40LS_CONVERSION_INTERVAL);
+
+ /* run the collection phase */
+ if (OK != collect()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* state machine will have generated a report, copy it out */
+ if (_reports->get(rbuf)) {
+ ret = sizeof(*rbuf);
+ }
+
+ } while (0);
+
+ return ret;
+}
+
+int
+LL40LS::measure()
+{
+ int ret;
+
+ /*
+ * Send the command to begin a measurement.
+ */
+ const uint8_t cmd[2] = { LL40LS_MEASURE_REG, LL40LS_MSRREG_ACQUIRE };
+ ret = transfer(cmd, sizeof(cmd), nullptr, 0);
+
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+ return ret;
+ }
+
+ ret = OK;
+
+ return ret;
+}
+
+int
+LL40LS::collect()
+{
+ int ret = -EIO;
+
+ /* read from the sensor */
+ uint8_t val[2] = {0, 0};
+
+ perf_begin(_sample_perf);
+
+ // read the high and low byte distance registers
+ uint8_t distance_reg = LL40LS_DISTHIGH_REG;
+ ret = transfer(&distance_reg, 1, &val[0], sizeof(val));
+
+ if (ret < 0) {
+ log("error reading from sensor: %d", ret);
+ perf_count(_comms_errors);
+ perf_end(_sample_perf);
+ return ret;
+ }
+
+ uint16_t distance = (val[0] << 8) | val[1];
+ float si_units = distance * 0.01f; /* cm to m */
+ struct range_finder_report report;
+
+ _last_distance = distance;
+
+ /* this should be fairly close to the end of the measurement, so the best approximation of the time */
+ report.timestamp = hrt_absolute_time();
+ report.error_count = perf_event_count(_comms_errors);
+ report.distance = si_units;
+ if (si_units > get_minimum_distance() && si_units < get_maximum_distance()) {
+ report.valid = 1;
+ }
+ else {
+ report.valid = 0;
+ }
+
+ /* publish it, if we are the primary */
+ if (_range_finder_topic >= 0) {
+ orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
+ }
+
+ if (_reports->force(&report)) {
+ perf_count(_buffer_overflows);
+ }
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ ret = OK;
+
+ perf_end(_sample_perf);
+ return ret;
+}
+
+void
+LL40LS::start()
+{
+ /* reset the report ring and state machine */
+ _collect_phase = false;
+ _reports->flush();
+
+ /* schedule a cycle to start things */
+ work_queue(HPWORK, &_work, (worker_t)&LL40LS::cycle_trampoline, this, 1);
+
+ /* notify about state change */
+ struct subsystem_info_s info = {
+ true,
+ true,
+ true,
+ SUBSYSTEM_TYPE_RANGEFINDER
+ };
+ static orb_advert_t pub = -1;
+
+ if (pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), pub, &info);
+
+ } else {
+ pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ }
+}
+
+void
+LL40LS::stop()
+{
+ work_cancel(HPWORK, &_work);
+}
+
+void
+LL40LS::cycle_trampoline(void *arg)
+{
+ LL40LS *dev = (LL40LS *)arg;
+
+ dev->cycle();
+}
+
+void
+LL40LS::cycle()
+{
+ /* collection phase? */
+ if (_collect_phase) {
+
+ /* perform collection */
+ if (OK != collect()) {
+ log("collection error");
+ /* restart the measurement state machine */
+ start();
+ return;
+ }
+
+ /* next phase is measurement */
+ _collect_phase = false;
+
+ /*
+ * Is there a collect->measure gap?
+ */
+ if (_measure_ticks > USEC2TICK(LL40LS_CONVERSION_INTERVAL)) {
+
+ /* schedule a fresh cycle call when we are ready to measure again */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&LL40LS::cycle_trampoline,
+ this,
+ _measure_ticks - USEC2TICK(LL40LS_CONVERSION_INTERVAL));
+
+ return;
+ }
+ }
+
+ /* measurement phase */
+ if (OK != measure()) {
+ log("measure error");
+ }
+
+ /* next phase is collection */
+ _collect_phase = true;
+
+ /* schedule a fresh cycle call when the measurement is done */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&LL40LS::cycle_trampoline,
+ this,
+ USEC2TICK(LL40LS_CONVERSION_INTERVAL));
+}
+
+void
+LL40LS::print_info()
+{
+ perf_print_counter(_sample_perf);
+ perf_print_counter(_comms_errors);
+ perf_print_counter(_buffer_overflows);
+ printf("poll interval: %u ticks\n", _measure_ticks);
+ _reports->print_info("report queue");
+ printf("distance: %ucm (0x%04x)\n",
+ (unsigned)_last_distance, (unsigned)_last_distance);
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace ll40ls
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+const int ERROR = -1;
+
+LL40LS *g_dev_int;
+LL40LS *g_dev_ext;
+
+void start(int bus);
+void stop(int bus);
+void test(int bus);
+void reset(int bus);
+void info(int bus);
+void usage();
+
+/**
+ * Start the driver.
+ */
+void
+start(int bus)
+{
+ /* create the driver, attempt expansion bus first */
+ if (bus == -1 || bus == PX4_I2C_BUS_EXPANSION) {
+ if (g_dev_ext != nullptr)
+ errx(0, "already started external");
+ g_dev_ext = new LL40LS(PX4_I2C_BUS_EXPANSION, LL40LS_DEVICE_PATH_EXT);
+ if (g_dev_ext != nullptr && OK != g_dev_ext->init()) {
+ delete g_dev_ext;
+ g_dev_ext = nullptr;
+ }
+ }
+
+#ifdef PX4_I2C_BUS_ONBOARD
+ /* if this failed, attempt onboard sensor */
+ if (bus == -1 || bus == PX4_I2C_BUS_ONBOARD) {
+ if (g_dev_int != nullptr)
+ errx(0, "already started internal");
+ g_dev_int = new LL40LS(PX4_I2C_BUS_ONBOARD, LL40LS_DEVICE_PATH_INT);
+ if (g_dev_int != nullptr && OK != g_dev_int->init()) {
+ /* tear down the failing onboard instance */
+ delete g_dev_int;
+ g_dev_int = nullptr;
+
+ if (bus == PX4_I2C_BUS_ONBOARD) {
+ goto fail;
+ }
+ }
+ if (g_dev_int == nullptr && bus == PX4_I2C_BUS_ONBOARD) {
+ goto fail;
+ }
+ }
+#endif
+
+ /* set the poll rate to default, starts automatic data collection */
+ if (g_dev_int != nullptr) {
+ int fd = open(LL40LS_DEVICE_PATH_INT, O_RDONLY);
+ if (fd == -1) {
+ goto fail;
+ }
+ int ret = ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT);
+ close(fd);
+ if (ret < 0) {
+ goto fail;
+ }
+ }
+
+ if (g_dev_ext != nullptr) {
+ int fd = open(LL40LS_DEVICE_PATH_EXT, O_RDONLY);
+ if (fd == -1) {
+ goto fail;
+ }
+ int ret = ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT);
+ close(fd);
+ if (ret < 0) {
+ goto fail;
+ }
+ }
+
+ exit(0);
+
+fail:
+ if (g_dev_int != nullptr && (bus == -1 || bus == PX4_I2C_BUS_ONBOARD)) {
+ delete g_dev_int;
+ g_dev_int = nullptr;
+ }
+ if (g_dev_ext != nullptr && (bus == -1 || bus == PX4_I2C_BUS_EXPANSION)) {
+ delete g_dev_ext;
+ g_dev_ext = nullptr;
+ }
+
+ errx(1, "driver start failed");
+}
+
+/**
+ * Stop the driver
+ */
+void stop(int bus)
+{
+ LL40LS **g_dev = (bus == PX4_I2C_BUS_ONBOARD?&g_dev_int:&g_dev_ext);
+ if (*g_dev != nullptr) {
+ delete *g_dev;
+ *g_dev = nullptr;
+
+ } else {
+ errx(1, "driver not running");
+ }
+
+ exit(0);
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ */
+void
+test(int bus)
+{
+ struct range_finder_report report;
+ ssize_t sz;
+ int ret;
+ const char *path = (bus==PX4_I2C_BUS_ONBOARD?LL40LS_DEVICE_PATH_INT:LL40LS_DEVICE_PATH_EXT);
+
+ int fd = open(path, O_RDONLY);
+
+ if (fd < 0) {
+ err(1, "%s open failed (try 'll40ls start' if the driver is not running", path);
+ }
+
+ /* do a simple demand read */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report)) {
+ err(1, "immediate read failed");
+ }
+
+ warnx("single read");
+ warnx("measurement: %0.2f m", (double)report.distance);
+ warnx("time: %lld", report.timestamp);
+
+ /* start the sensor polling at 2Hz */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
+ errx(1, "failed to set 2Hz poll rate");
+ }
+
+ /* read the sensor 5x and report each value */
+ for (unsigned i = 0; i < 5; i++) {
+ struct pollfd fds;
+
+ /* wait for data to be ready */
+ fds.fd = fd;
+ fds.events = POLLIN;
+ ret = poll(&fds, 1, 2000);
+
+ if (ret != 1) {
+ errx(1, "timed out waiting for sensor data");
+ }
+
+ /* now go get it */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report)) {
+ err(1, "periodic read failed");
+ }
+
+ warnx("periodic read %u", i);
+ warnx("measurement: %0.3f", (double)report.distance);
+ warnx("time: %lld", report.timestamp);
+ }
+
+ /* reset the sensor polling to default rate */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
+ errx(1, "failed to set default poll rate");
+ }
+
+ errx(0, "PASS");
+}
+
+/**
+ * Reset the driver.
+ */
+void
+reset(int bus)
+{
+ const char *path = (bus==PX4_I2C_BUS_ONBOARD?LL40LS_DEVICE_PATH_INT:LL40LS_DEVICE_PATH_EXT);
+ int fd = open(path, O_RDONLY);
+
+ if (fd < 0) {
+ err(1, "failed ");
+ }
+
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
+ err(1, "driver reset failed");
+ }
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
+ err(1, "driver poll restart failed");
+ }
+
+ exit(0);
+}
+
+/**
+ * Print a little info about the driver.
+ */
+void
+info(int bus)
+{
+ LL40LS *g_dev = (bus == PX4_I2C_BUS_ONBOARD?g_dev_int:g_dev_ext);
+ if (g_dev == nullptr) {
+ errx(1, "driver not running");
+ }
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ exit(0);
+}
+
+void
+usage()
+{
+ warnx("missing command: try 'start', 'stop', 'info', 'test', 'reset', 'info'");
+ warnx("options:");
+ warnx(" -X only external bus");
+#ifdef PX4_I2C_BUS_ONBOARD
+ warnx(" -I only internal bus");
+#endif
+}
+
+} // namespace
+
+int
+ll40ls_main(int argc, char *argv[])
+{
+ int ch;
+ int bus = -1;
+
+ while ((ch = getopt(argc, argv, "XI")) != EOF) {
+ switch (ch) {
+#ifdef PX4_I2C_BUS_ONBOARD
+ case 'I':
+ bus = PX4_I2C_BUS_ONBOARD;
+ break;
+#endif
+ case 'X':
+ bus = PX4_I2C_BUS_EXPANSION;
+ break;
+ default:
+ ll40ls::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
+ /*
+ * Start/load the driver.
+ */
+ if (!strcmp(verb, "start")) {
+ ll40ls::start(bus);
+ }
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(verb, "stop")) {
+ ll40ls::stop(bus);
+ }
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(verb, "test")) {
+ ll40ls::test(bus);
+ }
+
+ /*
+ * Reset the driver.
+ */
+ if (!strcmp(verb, "reset")) {
+ ll40ls::reset(bus);
+ }
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(verb, "info") || !strcmp(verb, "status")) {
+ ll40ls::info(bus);
+ }
+
+ errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
+}
diff --git a/src/drivers/ll40ls/module.mk b/src/drivers/ll40ls/module.mk
new file mode 100644
index 000000000..fb627afee
--- /dev/null
+++ b/src/drivers/ll40ls/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Makefile to build the PulsedLight Lidar-Lite driver.
+#
+
+MODULE_COMMAND = ll40ls
+
+SRCS = ll40ls.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 8bf76dcc3..01c89192a 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -52,6 +52,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <getopt.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@@ -68,6 +69,7 @@
#include <board_config.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
+#include <lib/conversion/rotation.h>
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -75,12 +77,17 @@
#endif
static const int ERROR = -1;
+// enable this to debug the buggy lsm303d sensor in very early
+// prototype pixhawk boards
+#define CHECK_EXTREMES 0
+
/* SPI protocol address bits */
#define DIR_READ (1<<7)
#define DIR_WRITE (0<<7)
#define ADDR_INCREMENT (1<<6)
#define LSM303D_DEVICE_PATH_ACCEL "/dev/lsm303d_accel"
+#define LSM303D_DEVICE_PATH_ACCEL_EXT "/dev/lsm303d_accel_ext"
#define LSM303D_DEVICE_PATH_MAG "/dev/lsm303d_mag"
/* register addresses: A: accel, M: mag, T: temp */
@@ -216,7 +223,7 @@ class LSM303D_mag;
class LSM303D : public device::SPI
{
public:
- LSM303D(int bus, const char* path, spi_dev_e device);
+ LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rotation);
virtual ~LSM303D();
virtual int init();
@@ -277,6 +284,7 @@ private:
unsigned _mag_samplerate;
orb_advert_t _accel_topic;
+ orb_id_t _accel_orb_id;
int _accel_class_instance;
unsigned _accel_read;
@@ -305,7 +313,8 @@ private:
uint64_t _last_log_us;
uint64_t _last_log_sync_us;
uint64_t _last_log_reg_us;
- uint64_t _last_log_alarm_us;
+ uint64_t _last_log_alarm_us;
+ enum Rotation _rotation;
/**
* Start automatic measurement.
@@ -453,6 +462,10 @@ private:
* @return OK if the value can be supported.
*/
int mag_set_samplerate(unsigned frequency);
+
+ /* this class cannot be copied */
+ LSM303D(const LSM303D&);
+ LSM303D operator=(const LSM303D&);
};
/**
@@ -477,29 +490,39 @@ private:
LSM303D *_parent;
orb_advert_t _mag_topic;
+ orb_id_t _mag_orb_id;
int _mag_class_instance;
void measure();
void measure_trampoline(void *arg);
+
+ /* this class does not allow copying due to ptr data members */
+ LSM303D_mag(const LSM303D_mag&);
+ LSM303D_mag operator=(const LSM303D_mag&);
};
-LSM303D::LSM303D(int bus, const char* path, spi_dev_e device) :
+LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rotation) :
SPI("LSM303D", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within safety margins for LSM303D */),
_mag(new LSM303D_mag(this)),
+ _accel_call{},
+ _mag_call{},
_call_accel_interval(0),
_call_mag_interval(0),
_accel_reports(nullptr),
_mag_reports(nullptr),
+ _accel_scale{},
_accel_range_m_s2(0.0f),
_accel_range_scale(0.0f),
_accel_samplerate(0),
_accel_onchip_filter_bandwith(0),
+ _mag_scale{},
_mag_range_ga(0.0f),
_mag_range_scale(0.0f),
_mag_samplerate(0),
_accel_topic(-1),
+ _accel_orb_id(nullptr),
_accel_class_instance(-1),
_accel_read(0),
_mag_read(0),
@@ -516,11 +539,15 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device) :
_reg7_expected(0),
_accel_log_fd(-1),
_accel_logging_enabled(false),
+ _last_extreme_us(0),
_last_log_us(0),
_last_log_sync_us(0),
_last_log_reg_us(0),
- _last_log_alarm_us(0)
+ _last_log_alarm_us(0),
+ _rotation(rotation)
{
+ _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LSM303D;
+
// enable debug() calls
_debug_enabled = true;
@@ -600,34 +627,56 @@ LSM303D::init()
/* fill report structures */
measure();
- if (_mag->_mag_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct mag_report mrp;
+ _mag_reports->get(&mrp);
+
+ /* measurement will have generated a report, publish */
+ switch (_mag->_mag_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _mag->_mag_orb_id = ORB_ID(sensor_mag0);
+ break;
- /* advertise sensor topic, measure manually to initialize valid report */
- struct mag_report mrp;
- _mag_reports->get(&mrp);
+ case CLASS_DEVICE_SECONDARY:
+ _mag->_mag_orb_id = ORB_ID(sensor_mag1);
+ break;
- /* measurement will have generated a report, publish */
- _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag), &mrp);
+ case CLASS_DEVICE_TERTIARY:
+ _mag->_mag_orb_id = ORB_ID(sensor_mag2);
+ break;
+ }
- if (_mag->_mag_topic < 0)
- debug("failed to create sensor_mag publication");
+ _mag->_mag_topic = orb_advertise(_mag->_mag_orb_id, &mrp);
+ if (_mag->_mag_topic < 0) {
+ warnx("ADVERT ERR");
}
_accel_class_instance = register_class_devname(ACCEL_DEVICE_PATH);
- if (_accel_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct accel_report arp;
+ _accel_reports->get(&arp);
- /* advertise sensor topic, measure manually to initialize valid report */
- struct accel_report arp;
- _accel_reports->get(&arp);
+ /* measurement will have generated a report, publish */
+ switch (_accel_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _accel_orb_id = ORB_ID(sensor_accel0);
+ break;
- /* measurement will have generated a report, publish */
- _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp);
+ case CLASS_DEVICE_SECONDARY:
+ _accel_orb_id = ORB_ID(sensor_accel1);
+ break;
- if (_accel_topic < 0)
- debug("failed to create sensor_accel publication");
+ case CLASS_DEVICE_TERTIARY:
+ _accel_orb_id = ORB_ID(sensor_accel2);
+ break;
+ }
+
+ _accel_topic = orb_advertise(_accel_orb_id, &arp);
+ if (_accel_topic < 0) {
+ warnx("ADVERT ERR");
}
out:
@@ -830,7 +879,9 @@ LSM303D::read(struct file *filp, char *buffer, size_t buflen)
*/
while (count--) {
if (_accel_reports->get(arb)) {
+#if CHECK_EXTREMES
check_extremes(arb);
+#endif
ret += sizeof(*arb);
arb++;
}
@@ -1468,8 +1519,10 @@ LSM303D::measure()
{
// if the accel doesn't have any data ready then re-schedule
// for 100 microseconds later. This ensures we don't double
- // read a value and then miss the next value
- if (stm32_gpioread(GPIO_EXTI_ACCEL_DRDY) == 0) {
+ // read a value and then miss the next value.
+ // Note that DRDY is not available when the lsm303d is
+ // connected on the external bus
+ if (_bus == PX4_SPI_BUS_SENSORS && stm32_gpioread(GPIO_EXTI_ACCEL_DRDY) == 0) {
perf_count(_accel_reschedules);
hrt_call_delay(&_accel_call, 100);
return;
@@ -1533,6 +1586,9 @@ LSM303D::measure()
accel_report.y = _accel_filter_y.apply(y_in_new);
accel_report.z = _accel_filter_z.apply(z_in_new);
+ // apply user specified rotation
+ rotate_3f(_rotation, accel_report.x, accel_report.y, accel_report.z);
+
accel_report.scaling = _accel_range_scale;
accel_report.range_m_s2 = _accel_range_m_s2;
@@ -1541,9 +1597,9 @@ LSM303D::measure()
/* notify anyone waiting for data */
poll_notify(POLLIN);
- if (_accel_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_accel), _accel_topic, &accel_report);
+ orb_publish(_accel_orb_id, _accel_topic, &accel_report);
}
_accel_read++;
@@ -1609,15 +1665,18 @@ LSM303D::mag_measure()
mag_report.scaling = _mag_range_scale;
mag_report.range_ga = (float)_mag_range_ga;
+ // apply user specified rotation
+ rotate_3f(_rotation, mag_report.x, mag_report.y, mag_report.z);
+
_mag_reports->force(&mag_report);
/* XXX please check this poll_notify, is it the right one? */
/* notify anyone waiting for data */
poll_notify(POLLIN);
- if (_mag->_mag_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_mag), _mag->_mag_topic, &mag_report);
+ orb_publish(_mag->_mag_orb_id, _mag->_mag_topic, &mag_report);
}
_mag_read++;
@@ -1711,6 +1770,7 @@ LSM303D_mag::LSM303D_mag(LSM303D *parent) :
CDev("LSM303D_mag", LSM303D_DEVICE_PATH_MAG),
_parent(parent),
_mag_topic(-1),
+ _mag_orb_id(nullptr),
_mag_class_instance(-1)
{
}
@@ -1774,26 +1834,37 @@ namespace lsm303d
LSM303D *g_dev;
-void start();
+void start(bool external_bus, enum Rotation rotation);
void test();
void reset();
void info();
void regdump();
void logging();
+void usage();
/**
* Start the driver.
+ *
+ * This function call only returns once the driver is
+ * up and running or failed to detect the sensor.
*/
void
-start()
+start(bool external_bus, enum Rotation rotation)
{
int fd, fd_mag;
-
if (g_dev != nullptr)
errx(0, "already started");
/* create the driver */
- g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
+ if (external_bus) {
+ #ifdef PX4_SPI_BUS_EXT
+ g_dev = new LSM303D(PX4_SPI_BUS_EXT, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_EXT_ACCEL_MAG, rotation);
+ #else
+ errx(0, "External SPI not available");
+ #endif
+ } else {
+ g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG, rotation);
+ }
if (g_dev == nullptr) {
warnx("failed instantiating LSM303D obj");
@@ -1989,47 +2060,76 @@ logging()
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'info', 'test', 'reset', 'regdump', 'logging'");
+ warnx("options:");
+ warnx(" -X (external bus)");
+ warnx(" -R rotation");
+}
} // namespace
int
lsm303d_main(int argc, char *argv[])
{
+ bool external_bus = false;
+ int ch;
+ enum Rotation rotation = ROTATION_NONE;
+
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc, argv, "XR:")) != EOF) {
+ switch (ch) {
+ case 'X':
+ external_bus = true;
+ break;
+ case 'R':
+ rotation = (enum Rotation)atoi(optarg);
+ break;
+ default:
+ lsm303d::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
- lsm303d::start();
+ if (!strcmp(verb, "start"))
+ lsm303d::start(external_bus, rotation);
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
+ if (!strcmp(verb, "test"))
lsm303d::test();
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
+ if (!strcmp(verb, "reset"))
lsm303d::reset();
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info"))
+ if (!strcmp(verb, "info"))
lsm303d::info();
/*
* dump device registers
*/
- if (!strcmp(argv[1], "regdump"))
+ if (!strcmp(verb, "regdump"))
lsm303d::regdump();
/*
* dump device registers
*/
- if (!strcmp(argv[1], "logging"))
+ if (!strcmp(verb, "logging"))
lsm303d::logging();
errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info', 'logging' or 'regdump'");
diff --git a/src/drivers/lsm303d/module.mk b/src/drivers/lsm303d/module.mk
index e40f718c5..0421eb113 100644
--- a/src/drivers/lsm303d/module.mk
+++ b/src/drivers/lsm303d/module.mk
@@ -5,4 +5,8 @@
MODULE_COMMAND = lsm303d
SRCS = lsm303d.cpp
+MODULE_STACKSIZE = 1200
+EXTRACXXFLAGS = -Weffc++
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp
index 5adb8cf69..beb6c8e35 100644
--- a/src/drivers/mb12xx/mb12xx.cpp
+++ b/src/drivers/mb12xx/mb12xx.cpp
@@ -74,6 +74,7 @@
/* Configuration Constants */
#define MB12XX_BUS PX4_I2C_BUS_EXPANSION
#define MB12XX_BASEADDR 0x70 /* 7-bit address. 8-bit address is 0xE0 */
+#define MB12XX_DEVICE_PATH "/dev/mb12xx"
/* MB12xx Registers addresses */
@@ -124,6 +125,7 @@ private:
bool _sensor_ok;
int _measure_ticks;
bool _collect_phase;
+ int _class_instance;
orb_advert_t _range_finder_topic;
@@ -187,13 +189,14 @@ private:
extern "C" __EXPORT int mb12xx_main(int argc, char *argv[]);
MB12XX::MB12XX(int bus, int address) :
- I2C("MB12xx", RANGE_FINDER_DEVICE_PATH, bus, address, 100000),
+ I2C("MB12xx", MB12XX_DEVICE_PATH, bus, address, 100000),
_min_distance(MB12XX_MIN_DISTANCE),
_max_distance(MB12XX_MAX_DISTANCE),
_reports(nullptr),
_sensor_ok(false),
_measure_ticks(0),
_collect_phase(false),
+ _class_instance(-1),
_range_finder_topic(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "mb12xx_read")),
_comms_errors(perf_alloc(PC_COUNT, "mb12xx_comms_errors")),
@@ -215,6 +218,15 @@ MB12XX::~MB12XX()
if (_reports != nullptr) {
delete _reports;
}
+
+ if (_class_instance != -1) {
+ unregister_class_devname(RANGE_FINDER_DEVICE_PATH, _class_instance);
+ }
+
+ // free perf counters
+ perf_free(_sample_perf);
+ perf_free(_comms_errors);
+ perf_free(_buffer_overflows);
}
int
@@ -234,13 +246,18 @@ MB12XX::init()
goto out;
}
- /* get a publish handle on the range finder topic */
- struct range_finder_report zero_report;
- memset(&zero_report, 0, sizeof(zero_report));
- _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &zero_report);
+ _class_instance = register_class_devname(RANGE_FINDER_DEVICE_PATH);
- if (_range_finder_topic < 0) {
- debug("failed to create sensor_range_finder object. Did you start uOrb?");
+ if (_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* get a publish handle on the range finder topic */
+ struct range_finder_report rf_report;
+ measure();
+ _reports->get(&rf_report);
+ _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &rf_report);
+
+ if (_range_finder_topic < 0) {
+ debug("failed to create sensor_range_finder object. Did you start uOrb?");
+ }
}
ret = OK;
@@ -505,8 +522,10 @@ MB12XX::collect()
report.distance = si_units;
report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
- /* publish it */
- orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
+ /* publish it, if we are the primary */
+ if (_range_finder_topic >= 0) {
+ orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
+ }
if (_reports->force(&report)) {
perf_count(_buffer_overflows);
@@ -665,7 +684,7 @@ start()
}
/* set the poll rate to default, starts automatic data collection */
- fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
+ fd = open(MB12XX_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
goto fail;
@@ -715,10 +734,10 @@ test()
ssize_t sz;
int ret;
- int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
+ int fd = open(MB12XX_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
- err(1, "%s open failed (try 'mb12xx start' if the driver is not running", RANGE_FINDER_DEVICE_PATH);
+ err(1, "%s open failed (try 'mb12xx start' if the driver is not running", MB12XX_DEVICE_PATH);
}
/* do a simple demand read */
@@ -776,7 +795,7 @@ test()
void
reset()
{
- int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
+ int fd = open(MB12XX_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
err(1, "failed ");
diff --git a/src/drivers/mb12xx/module.mk b/src/drivers/mb12xx/module.mk
index 4e00ada02..d751e93e4 100644
--- a/src/drivers/mb12xx/module.mk
+++ b/src/drivers/mb12xx/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = mb12xx
SRCS = mb12xx.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/md25/module.mk b/src/drivers/md25/module.mk
index 13821a6b5..3f9cf2d89 100644
--- a/src/drivers/md25/module.mk
+++ b/src/drivers/md25/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = md25
SRCS = md25.cpp \
md25_main.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
index c0f3c28e0..ba46de379 100644
--- a/src/drivers/meas_airspeed/meas_airspeed.cpp
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -92,7 +92,7 @@
#include <drivers/airspeed/airspeed.h>
/* I2C bus address is 1010001x */
-#define I2C_ADDRESS_MS4525DO 0x28 //0x51 /* 7-bit address. */
+#define I2C_ADDRESS_MS4525DO 0x28 /**< 7-bit address. Depends on the order code (this is for code "I") */
#define PATH_MS4525 "/dev/ms4525"
/* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */
#define I2C_ADDRESS_MS5525DSO 0x77 //0x77/* 7-bit address, addr. pin pulled low */
@@ -102,9 +102,9 @@
#define ADDR_READ_MR 0x00 /* write to this address to start conversion */
/* Measurement rate is 100Hz */
-#define MEAS_RATE 100.0f
-#define MEAS_DRIVER_FILTER_FREQ 3.0f
-#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
+#define MEAS_RATE 100
+#define MEAS_DRIVER_FILTER_FREQ 1.2f
+#define CONVERSION_INTERVAL (1000000 / MEAS_RATE) /* microseconds */
class MEASAirspeed : public Airspeed
{
@@ -140,9 +140,9 @@ extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]);
MEASAirspeed::MEASAirspeed(int bus, int address, const char *path) : Airspeed(bus, address,
CONVERSION_INTERVAL, path),
_filter(MEAS_RATE, MEAS_DRIVER_FILTER_FREQ),
- _t_system_power(-1)
+ _t_system_power(-1),
+ system_power{}
{
- memset(&system_power, 0, sizeof(system_power));
}
int
@@ -225,47 +225,28 @@ MEASAirspeed::collect()
// correct for 5V rail voltage if possible
voltage_correction(diff_press_pa_raw, temperature);
- float diff_press_pa = fabsf(diff_press_pa_raw - _diff_pres_offset);
-
- /*
- note that we return both the absolute value with offset
- applied and a raw value without the offset applied. This
- makes it possible for higher level code to detect if the
- user has the tubes connected backwards, and also makes it
- possible to correctly use offsets calculated by a higher
- level airspeed driver.
+ // the raw value still should be compensated for the known offset
+ diff_press_pa_raw -= _diff_pres_offset;
+ /*
With the above calculation the MS4525 sensor will produce a
positive number when the top port is used as a dynamic port
and bottom port is used as the static port
-
- Also note that the _diff_pres_offset is applied before the
- fabsf() not afterwards. It needs to be done this way to
- prevent a bias at low speeds, but this also means that when
- setting a offset you must set it based on the raw value, not
- the offset value
*/
-
+
struct differential_pressure_s report;
/* track maximum differential pressure measured (so we can work out top speed). */
- if (diff_press_pa > _max_differential_pressure_pa) {
- _max_differential_pressure_pa = diff_press_pa;
+ if (diff_press_pa_raw > _max_differential_pressure_pa) {
+ _max_differential_pressure_pa = diff_press_pa_raw;
}
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
report.temperature = temperature;
- report.differential_pressure_pa = diff_press_pa;
- report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa);
-
- /* the dynamics of the filter can make it overshoot into the negative range */
- if (report.differential_pressure_filtered_pa < 0.0f) {
- report.differential_pressure_filtered_pa = _filter.reset(diff_press_pa);
- }
+ report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw);
report.differential_pressure_raw_pa = diff_press_pa_raw;
- report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
if (_airspeed_pub > 0 && !(_pub_blocked)) {
@@ -343,7 +324,7 @@ MEASAirspeed::cycle()
/**
correct for 5V rail voltage if the system_power ORB topic is
available
-
+
See http://uav.tridgell.net/MS4525/MS4525-offset.png for a graph of
offset versus voltage for 3 sensors
*/
@@ -392,7 +373,7 @@ MEASAirspeed::voltage_correction(float &diff_press_pa, float &temperature)
if (voltage_diff < -1.0f) {
voltage_diff = -1.0f;
}
- temperature -= voltage_diff * temp_slope;
+ temperature -= voltage_diff * temp_slope;
#endif // CONFIG_ARCH_BOARD_PX4FMU_V2
}
@@ -418,6 +399,9 @@ void info();
/**
* Start the driver.
+ *
+ * This function call only returns once the driver is up and running
+ * or failed to detect the sensor.
*/
void
start(int i2c_bus)
@@ -518,7 +502,7 @@ test()
}
warnx("single read");
- warnx("diff pressure: %d pa", (int)report.differential_pressure_pa);
+ warnx("diff pressure: %d pa", (int)report.differential_pressure_filtered_pa);
/* start the sensor polling at 2Hz */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
@@ -535,7 +519,7 @@ test()
ret = poll(&fds, 1, 2000);
if (ret != 1) {
- errx(1, "timed out waiting for sensor data");
+ errx(1, "timed out");
}
/* now go get it */
@@ -546,7 +530,7 @@ test()
}
warnx("periodic read %u", i);
- warnx("diff pressure: %d pa", (int)report.differential_pressure_pa);
+ warnx("diff pressure: %d pa", (int)report.differential_pressure_filtered_pa);
warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature);
}
diff --git a/src/drivers/meas_airspeed/module.mk b/src/drivers/meas_airspeed/module.mk
index fed4078b6..6f5909978 100644
--- a/src/drivers/meas_airspeed/module.mk
+++ b/src/drivers/meas_airspeed/module.mk
@@ -36,6 +36,11 @@
#
MODULE_COMMAND = meas_airspeed
-MODULE_STACKSIZE = 2048
SRCS = meas_airspeed.cpp
+
+MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index 5954c40da..1055487cb 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -131,8 +131,8 @@ public:
int set_motor_count(unsigned count);
int set_motor_test(bool motortest);
int set_overrideSecurityChecks(bool overrideSecurityChecks);
- int set_px4mode(int px4mode);
- int set_frametype(int frametype);
+ void set_px4mode(int px4mode);
+ void set_frametype(int frametype);
unsigned int mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C);
private:
@@ -222,15 +222,15 @@ MK::MK(int bus, const char *_device_path) :
_task(-1),
_t_actuators(-1),
_t_actuator_armed(-1),
+ _motor(-1),
+ _px4mode(MAPPING_MK),
+ _frametype(FRAME_PLUS),
_t_outputs(0),
_t_esc_status(0),
_num_outputs(0),
+ _primary_pwm_device(false),
_motortest(false),
_overrideSecurityChecks(false),
- _motor(-1),
- _px4mode(MAPPING_MK),
- _frametype(FRAME_PLUS),
- _primary_pwm_device(false),
_task_should_exit(false),
_armed(false),
_mixers(nullptr)
@@ -330,13 +330,13 @@ MK::set_update_rate(unsigned rate)
return OK;
}
-int
+void
MK::set_px4mode(int px4mode)
{
_px4mode = px4mode;
}
-int
+void
MK::set_frametype(int frametype)
{
_frametype = frametype;
@@ -440,9 +440,6 @@ MK::scaling(float val, float inMin, float inMax, float outMin, float outMax)
void
MK::task_main()
{
- long update_rate_in_us = 0;
- float tmpVal = 0;
-
/*
* Subscribe to the appropriate PWM output topic based on whether we are the
* primary PWM output or not.
@@ -483,7 +480,6 @@ MK::task_main()
/* handle update rate changes */
if (_current_update_rate != _update_rate) {
int update_rate_in_ms = int(1000 / _update_rate);
- update_rate_in_us = long(1000000 / _update_rate);
/* reject faster than 500 Hz updates */
if (update_rate_in_ms < 2) {
@@ -604,8 +600,8 @@ MK::task_main()
esc.esc[i].esc_address = (uint8_t) BLCTRL_BASE_ADDR + i;
esc.esc[i].esc_vendor = ESC_VENDOR_MIKROKOPTER;
esc.esc[i].esc_version = (uint16_t) Motor[i].Version;
- esc.esc[i].esc_voltage = (uint16_t) 0;
- esc.esc[i].esc_current = (uint16_t) Motor[i].Current;
+ esc.esc[i].esc_voltage = 0.0F;
+ esc.esc[i].esc_current = static_cast<float>(Motor[i].Current) * 0.1F;
esc.esc[i].esc_rpm = (uint16_t) 0;
esc.esc[i].esc_setpoint = (float) Motor[i].SetPoint_PX4;
@@ -618,7 +614,7 @@ MK::task_main()
esc.esc[i].esc_setpoint_raw = (uint16_t) Motor[i].SetPoint;
}
- esc.esc[i].esc_temperature = (uint16_t) Motor[i].Temperature;
+ esc.esc[i].esc_temperature = static_cast<float>(Motor[i].Temperature);
esc.esc[i].esc_state = (uint16_t) Motor[i].State;
esc.esc[i].esc_errorcount = (uint16_t) 0;
@@ -735,7 +731,6 @@ MK::mk_servo_set(unsigned int chan, short val)
_retries = 0;
uint8_t result[3] = { 0, 0, 0 };
uint8_t msg[2] = { 0, 0 };
- uint8_t rod = 0;
uint8_t bytesToSendBL2 = 2;
tmpVal = val;
@@ -824,7 +819,7 @@ MK::mk_servo_set(unsigned int chan, short val)
if (debugCounter == 2000) {
debugCounter = 0;
- for (int i = 0; i < _num_outputs; i++) {
+ for (unsigned int i = 0; i < _num_outputs; i++) {
if (Motor[i].State & MOTOR_STATE_PRESENT_MASK) {
fprintf(stderr, "[mkblctrl] #%i:\tVer: %i\tVal: %i\tCurr: %i\tMaxPWM: %i\tTemp: %i\tState: %i\n", i, Motor[i].Version, Motor[i].SetPoint, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature, Motor[i].State);
}
@@ -1169,7 +1164,7 @@ mk_new_mode(int update_rate, int motorcount, bool motortest, int px4mode, int fr
}
int
-mk_start(unsigned motors, char *device_path)
+mk_start(unsigned motors, const char *device_path)
{
int ret;
@@ -1228,7 +1223,7 @@ mkblctrl_main(int argc, char *argv[])
bool overrideSecurityChecks = false;
bool showHelp = false;
bool newMode = false;
- char *devicepath = "";
+ const char *devicepath = "";
/*
* optional parameters
diff --git a/src/drivers/mkblctrl/module.mk b/src/drivers/mkblctrl/module.mk
index 3ac263b00..6daa14aa5 100644
--- a/src/drivers/mkblctrl/module.mk
+++ b/src/drivers/mkblctrl/module.mk
@@ -37,6 +37,8 @@
MODULE_COMMAND = mkblctrl
-SRCS = mkblctrl.cpp
+SRCS = mkblctrl.cpp
INCLUDE_DIRS += $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/mpu6000/module.mk b/src/drivers/mpu6000/module.mk
index c7d9cd3ef..da9fcc0fc 100644
--- a/src/drivers/mpu6000/module.mk
+++ b/src/drivers/mpu6000/module.mk
@@ -37,7 +37,10 @@
MODULE_COMMAND = mpu6000
-# XXX seems excessive, check if 2048 is not sufficient
-MODULE_STACKSIZE = 4096
-
SRCS = mpu6000.cpp
+
+MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 321fdd173..a95e041a1 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -55,6 +55,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <getopt.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
@@ -71,12 +72,15 @@
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
+#include <lib/conversion/rotation.h>
#define DIR_READ 0x80
#define DIR_WRITE 0x00
#define MPU_DEVICE_PATH_ACCEL "/dev/mpu6000_accel"
#define MPU_DEVICE_PATH_GYRO "/dev/mpu6000_gyro"
+#define MPU_DEVICE_PATH_ACCEL_EXT "/dev/mpu6000_accel_ext"
+#define MPU_DEVICE_PATH_GYRO_EXT "/dev/mpu6000_gyro_ext"
// MPU 6000 registers
#define MPUREG_WHOAMI 0x75
@@ -177,7 +181,7 @@ class MPU6000_gyro;
class MPU6000 : public device::SPI
{
public:
- MPU6000(int bus, spi_dev_e device);
+ MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device, enum Rotation rotation);
virtual ~MPU6000();
virtual int init();
@@ -211,6 +215,7 @@ private:
float _accel_range_scale;
float _accel_range_m_s2;
orb_advert_t _accel_topic;
+ orb_id_t _accel_orb_id;
int _accel_class_instance;
RingBuffer *_gyro_reports;
@@ -224,6 +229,7 @@ private:
perf_counter_t _gyro_reads;
perf_counter_t _sample_perf;
perf_counter_t _bad_transfers;
+ perf_counter_t _good_transfers;
math::LowPassFilter2p _accel_filter_x;
math::LowPassFilter2p _accel_filter_y;
@@ -232,6 +238,8 @@ private:
math::LowPassFilter2p _gyro_filter_y;
math::LowPassFilter2p _gyro_filter_z;
+ enum Rotation _rotation;
+
/**
* Start automatic measurement.
*/
@@ -337,6 +345,9 @@ private:
*/
void _set_sample_rate(uint16_t desired_sample_rate_hz);
+ /* do not allow to copy this class due to pointer data members */
+ MPU6000(const MPU6000&);
+ MPU6000 operator=(const MPU6000&);
};
/**
@@ -345,7 +356,7 @@ private:
class MPU6000_gyro : public device::CDev
{
public:
- MPU6000_gyro(MPU6000 *parent);
+ MPU6000_gyro(MPU6000 *parent, const char *path);
~MPU6000_gyro();
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
@@ -361,24 +372,32 @@ protected:
private:
MPU6000 *_parent;
orb_advert_t _gyro_topic;
+ orb_id_t _gyro_orb_id;
int _gyro_class_instance;
+ /* do not allow to copy this class due to pointer data members */
+ MPU6000_gyro(const MPU6000_gyro&);
+ MPU6000_gyro operator=(const MPU6000_gyro&);
};
/** driver 'main' command */
extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); }
-MPU6000::MPU6000(int bus, spi_dev_e device) :
- SPI("MPU6000", MPU_DEVICE_PATH_ACCEL, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED),
- _gyro(new MPU6000_gyro(this)),
+MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device, enum Rotation rotation) :
+ SPI("MPU6000", path_accel, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED),
+ _gyro(new MPU6000_gyro(this, path_gyro)),
_product(0),
+ _call{},
_call_interval(0),
_accel_reports(nullptr),
+ _accel_scale{},
_accel_range_scale(0.0f),
_accel_range_m_s2(0.0f),
_accel_topic(-1),
+ _accel_orb_id(nullptr),
_accel_class_instance(-1),
_gyro_reports(nullptr),
+ _gyro_scale{},
_gyro_range_scale(0.0f),
_gyro_range_rad_s(0.0f),
_sample_rate(1000),
@@ -386,12 +405,14 @@ MPU6000::MPU6000(int bus, spi_dev_e device) :
_gyro_reads(perf_alloc(PC_COUNT, "mpu6000_gyro_read")),
_sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")),
_bad_transfers(perf_alloc(PC_COUNT, "mpu6000_bad_transfers")),
+ _good_transfers(perf_alloc(PC_COUNT, "mpu6000_good_transfers")),
_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)
+ _gyro_filter_z(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ),
+ _rotation(rotation)
{
// disable debug() calls
_debug_enabled = false;
@@ -437,6 +458,7 @@ MPU6000::~MPU6000()
perf_free(_accel_reads);
perf_free(_gyro_reads);
perf_free(_bad_transfers);
+ perf_free(_good_transfers);
}
int
@@ -491,31 +513,56 @@ MPU6000::init()
measure();
- if (_accel_class_instance == CLASS_DEVICE_PRIMARY) {
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct accel_report arp;
+ _accel_reports->get(&arp);
- /* advertise sensor topic, measure manually to initialize valid report */
- struct accel_report arp;
- _accel_reports->get(&arp);
+ /* measurement will have generated a report, publish */
+ switch (_accel_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _accel_orb_id = ORB_ID(sensor_accel0);
+ break;
+
+ case CLASS_DEVICE_SECONDARY:
+ _accel_orb_id = ORB_ID(sensor_accel1);
+ break;
- /* measurement will have generated a report, publish */
- _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp);
+ case CLASS_DEVICE_TERTIARY:
+ _accel_orb_id = ORB_ID(sensor_accel2);
+ break;
- if (_accel_topic < 0)
- debug("failed to create sensor_accel publication");
+ }
+
+ _accel_topic = orb_advertise(_accel_orb_id, &arp);
+ if (_accel_topic < 0) {
+ warnx("ADVERT FAIL");
}
- if (_gyro->_gyro_class_instance == CLASS_DEVICE_PRIMARY) {
- /* advertise sensor topic, measure manually to initialize valid report */
- struct gyro_report grp;
- _gyro_reports->get(&grp);
+ /* advertise sensor topic, measure manually to initialize valid report */
+ struct gyro_report grp;
+ _gyro_reports->get(&grp);
+
+ switch (_gyro->_gyro_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _gyro->_gyro_orb_id = ORB_ID(sensor_gyro0);
+ break;
+
+ case CLASS_DEVICE_SECONDARY:
+ _gyro->_gyro_orb_id = ORB_ID(sensor_gyro1);
+ break;
- _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grp);
+ case CLASS_DEVICE_TERTIARY:
+ _gyro->_gyro_orb_id = ORB_ID(sensor_gyro2);
+ break;
+
+ }
- if (_gyro->_gyro_topic < 0)
- debug("failed to create sensor_gyro publication");
+ _gyro->_gyro_topic = orb_advertise(_gyro->_gyro_orb_id, &grp);
+ if (_gyro->_gyro_topic < 0) {
+ warnx("ADVERT FAIL");
}
out:
@@ -544,7 +591,7 @@ void MPU6000::reset()
write_reg(MPUREG_USER_CTRL, BIT_I2C_IF_DIS);
irqrestore(state);
- up_udelay(1000);
+ usleep(1000);
// SAMPLE RATE
_set_sample_rate(_sample_rate);
@@ -666,7 +713,9 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz)
/*
choose next highest filter frequency available
*/
- if (frequency_hz <= 5) {
+ if (frequency_hz == 0) {
+ filter = BITS_DLPF_CFG_2100HZ_NOLPF;
+ } else if (frequency_hz <= 5) {
filter = BITS_DLPF_CFG_5HZ;
} else if (frequency_hz <= 10) {
filter = BITS_DLPF_CFG_10HZ;
@@ -864,12 +913,14 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
// adjust filters
float cutoff_freq_hz = _accel_filter_x.get_cutoff_freq();
float sample_rate = 1.0e6f/ticks;
+ _set_dlpf_filter(cutoff_freq_hz);
_accel_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
_accel_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
_accel_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
float cutoff_freq_hz_gyro = _gyro_filter_x.get_cutoff_freq();
+ _set_dlpf_filter(cutoff_freq_hz_gyro);
_gyro_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
_gyro_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
_gyro_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
@@ -922,10 +973,9 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
return _accel_filter_x.get_cutoff_freq();
case ACCELIOCSLOWPASS:
-
- // XXX decide on relationship of both filters
- // i.e. disable the on-chip filter
- //_set_dlpf_filter((uint16_t)arg);
+ // set hardware filtering
+ _set_dlpf_filter(arg);
+ // set software filtering
_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);
@@ -1006,11 +1056,11 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
case GYROIOCGLOWPASS:
return _gyro_filter_x.get_cutoff_freq();
case GYROIOCSLOWPASS:
+ // set hardware filtering
+ _set_dlpf_filter(arg);
_gyro_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_gyro_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_gyro_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
- // XXX check relation to the internal lowpass
- //_set_dlpf_filter((uint16_t)arg);
return OK;
case GYROIOCSSCALE:
@@ -1232,8 +1282,14 @@ MPU6000::measure()
// all zero data - probably a SPI bus error
perf_count(_bad_transfers);
perf_end(_sample_perf);
+ // note that we don't call reset() here as a reset()
+ // costs 20ms with interrupts disabled. That means if
+ // the mpu6k does go bad it would cause a FMU failure,
+ // regardless of whether another sensor is available,
return;
}
+
+ perf_count(_good_transfers);
/*
@@ -1295,6 +1351,9 @@ MPU6000::measure()
arb.y = _accel_filter_y.apply(y_in_new);
arb.z = _accel_filter_z.apply(z_in_new);
+ // apply user specified rotation
+ rotate_3f(_rotation, arb.x, arb.y, arb.z);
+
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
@@ -1313,6 +1372,9 @@ MPU6000::measure()
grb.y = _gyro_filter_y.apply(y_gyro_in_new);
grb.z = _gyro_filter_z.apply(z_gyro_in_new);
+ // apply user specified rotation
+ rotate_3f(_rotation, grb.x, grb.y, grb.z);
+
grb.scaling = _gyro_range_scale;
grb.range_rad_s = _gyro_range_rad_s;
@@ -1326,14 +1388,14 @@ MPU6000::measure()
poll_notify(POLLIN);
_gyro->parent_poll_notify();
- if (_accel_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb);
+ orb_publish(_accel_orb_id, _accel_topic, &arb);
}
- if (_gyro->_gyro_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_gyro), _gyro->_gyro_topic, &grb);
+ orb_publish(_gyro->_gyro_orb_id, _gyro->_gyro_topic, &grb);
}
/* stop measuring */
@@ -1346,14 +1408,17 @@ MPU6000::print_info()
perf_print_counter(_sample_perf);
perf_print_counter(_accel_reads);
perf_print_counter(_gyro_reads);
+ perf_print_counter(_bad_transfers);
+ perf_print_counter(_good_transfers);
_accel_reports->print_info("accel queue");
_gyro_reports->print_info("gyro queue");
}
-MPU6000_gyro::MPU6000_gyro(MPU6000 *parent) :
- CDev("MPU6000_gyro", MPU_DEVICE_PATH_GYRO),
+MPU6000_gyro::MPU6000_gyro(MPU6000 *parent, const char *path) :
+ CDev("MPU6000_gyro", path),
_parent(parent),
_gyro_topic(-1),
+ _gyro_orb_id(nullptr),
_gyro_class_instance(-1)
{
}
@@ -1407,36 +1472,52 @@ MPU6000_gyro::ioctl(struct file *filp, int cmd, unsigned long arg)
namespace mpu6000
{
-MPU6000 *g_dev;
+MPU6000 *g_dev_int; // on internal bus
+MPU6000 *g_dev_ext; // on external bus
-void start();
-void test();
-void reset();
-void info();
+void start(bool, enum Rotation);
+void test(bool);
+void reset(bool);
+void info(bool);
+void usage();
/**
* Start the driver.
+ *
+ * This function only returns if the driver is up and running
+ * or failed to detect the sensor.
*/
void
-start()
+start(bool external_bus, enum Rotation rotation)
{
int fd;
+ MPU6000 **g_dev_ptr = external_bus?&g_dev_ext:&g_dev_int;
+ const char *path_accel = external_bus?MPU_DEVICE_PATH_ACCEL_EXT:MPU_DEVICE_PATH_ACCEL;
+ const char *path_gyro = external_bus?MPU_DEVICE_PATH_GYRO_EXT:MPU_DEVICE_PATH_GYRO;
- if (g_dev != nullptr)
+ if (*g_dev_ptr != nullptr)
/* if already started, the still command succeeded */
errx(0, "already started");
/* create the driver */
- g_dev = new MPU6000(1 /* XXX magic number */, (spi_dev_e)PX4_SPIDEV_MPU);
+ if (external_bus) {
+#ifdef PX4_SPI_BUS_EXT
+ *g_dev_ptr = new MPU6000(PX4_SPI_BUS_EXT, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_EXT_MPU, rotation);
+#else
+ errx(0, "External SPI not available");
+#endif
+ } else {
+ *g_dev_ptr = new MPU6000(PX4_SPI_BUS_SENSORS, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_MPU, rotation);
+ }
- if (g_dev == nullptr)
+ if (*g_dev_ptr == nullptr)
goto fail;
- if (OK != g_dev->init())
+ if (OK != (*g_dev_ptr)->init())
goto fail;
/* set the poll rate to default, starts automatic data collection */
- fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
+ fd = open(path_accel, O_RDONLY);
if (fd < 0)
goto fail;
@@ -1449,9 +1530,9 @@ start()
exit(0);
fail:
- if (g_dev != nullptr) {
- delete g_dev;
- g_dev = nullptr;
+ if (*g_dev_ptr != nullptr) {
+ delete (*g_dev_ptr);
+ *g_dev_ptr = nullptr;
}
errx(1, "driver start failed");
@@ -1463,24 +1544,26 @@ fail:
* and automatic modes.
*/
void
-test()
+test(bool external_bus)
{
+ const char *path_accel = external_bus?MPU_DEVICE_PATH_ACCEL_EXT:MPU_DEVICE_PATH_ACCEL;
+ const char *path_gyro = external_bus?MPU_DEVICE_PATH_GYRO_EXT:MPU_DEVICE_PATH_GYRO;
accel_report a_report;
gyro_report g_report;
ssize_t sz;
/* get the driver */
- int fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
+ int fd = open(path_accel, O_RDONLY);
if (fd < 0)
- err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)",
- MPU_DEVICE_PATH_ACCEL);
+ err(1, "%s open failed (try 'mpu6000 start')",
+ path_accel);
/* get the driver */
- int fd_gyro = open(MPU_DEVICE_PATH_GYRO, O_RDONLY);
+ int fd_gyro = open(path_gyro, O_RDONLY);
if (fd_gyro < 0)
- err(1, "%s open failed", MPU_DEVICE_PATH_GYRO);
+ err(1, "%s open failed", path_gyro);
/* reset to manual polling */
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0)
@@ -1528,7 +1611,7 @@ test()
/* XXX add poll-rate tests here too */
- reset();
+ reset(external_bus);
errx(0, "PASS");
}
@@ -1536,9 +1619,10 @@ test()
* Reset the driver.
*/
void
-reset()
+reset(bool external_bus)
{
- int fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY);
+ const char *path_accel = external_bus?MPU_DEVICE_PATH_ACCEL_EXT:MPU_DEVICE_PATH_ACCEL;
+ int fd = open(path_accel, O_RDONLY);
if (fd < 0)
err(1, "failed ");
@@ -1558,47 +1642,77 @@ reset()
* Print a little info about the driver.
*/
void
-info()
+info(bool external_bus)
{
- if (g_dev == nullptr)
+ MPU6000 **g_dev_ptr = external_bus?&g_dev_ext:&g_dev_int;
+ if (*g_dev_ptr == nullptr)
errx(1, "driver not running");
- printf("state @ %p\n", g_dev);
- g_dev->print_info();
+ printf("state @ %p\n", *g_dev_ptr);
+ (*g_dev_ptr)->print_info();
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'info', 'test', 'reset'");
+ warnx("options:");
+ warnx(" -X (external bus)");
+ warnx(" -R rotation");
+}
} // namespace
int
mpu6000_main(int argc, char *argv[])
{
+ bool external_bus = false;
+ int ch;
+ enum Rotation rotation = ROTATION_NONE;
+
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc, argv, "XR:")) != EOF) {
+ switch (ch) {
+ case 'X':
+ external_bus = true;
+ break;
+ case 'R':
+ rotation = (enum Rotation)atoi(optarg);
+ break;
+ default:
+ mpu6000::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
- mpu6000::start();
+ if (!strcmp(verb, "start"))
+ mpu6000::start(external_bus, rotation);
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
- mpu6000::test();
+ if (!strcmp(verb, "test"))
+ mpu6000::test(external_bus);
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
- mpu6000::reset();
+ if (!strcmp(verb, "reset"))
+ mpu6000::reset(external_bus);
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info"))
- mpu6000::info();
+ if (!strcmp(verb, "info"))
+ mpu6000::info(external_bus);
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
}
diff --git a/src/drivers/ms5611/module.mk b/src/drivers/ms5611/module.mk
index 20f8aa173..ee74058fc 100644
--- a/src/drivers/ms5611/module.mk
+++ b/src/drivers/ms5611/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = ms5611
SRCS = ms5611.cpp ms5611_spi.cpp ms5611_i2c.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 1ce93aeea..889643d0d 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -50,6 +50,7 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <getopt.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
@@ -129,7 +130,7 @@ protected:
float _T;
/* altitude conversion calibration */
- unsigned _msl_pressure; /* in kPa */
+ unsigned _msl_pressure; /* in Pa */
orb_advert_t _baro_topic;
@@ -299,12 +300,17 @@ MS5611::init()
ret = OK;
- if (_class_instance == CLASS_DEVICE_PRIMARY) {
-
- _baro_topic = orb_advertise(ORB_ID(sensor_baro), &brp);
+ switch (_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ _baro_topic = orb_advertise(ORB_ID(sensor_baro0), &brp);
+ break;
+ case CLASS_DEVICE_SECONDARY:
+ _baro_topic = orb_advertise(ORB_ID(sensor_baro1), &brp);
+ break;
+ }
- if (_baro_topic < 0)
- debug("failed to create sensor_baro publication");
+ if (_baro_topic < 0) {
+ warnx("failed to create sensor_baro publication");
}
} while (0);
@@ -460,7 +466,7 @@ MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
irqrestore(flags);
return -ENOMEM;
}
- irqrestore(flags);
+ irqrestore(flags);
return OK;
}
@@ -721,9 +727,17 @@ MS5611::collect()
report.altitude = (((pow((p / p1), (-(a * R) / g))) * T1) - T1) / a;
/* publish it */
- if (_baro_topic > 0 && !(_pub_blocked)) {
+ if (!(_pub_blocked)) {
/* publish it */
- orb_publish(ORB_ID(sensor_baro), _baro_topic, &report);
+ switch (_class_instance) {
+ case CLASS_DEVICE_PRIMARY:
+ orb_publish(ORB_ID(sensor_baro0), _baro_topic, &report);
+ break;
+
+ case CLASS_DEVICE_SECONDARY:
+ orb_publish(ORB_ID(sensor_baro1), _baro_topic, &report);
+ break;
+ }
}
if (_reports->force(&report)) {
@@ -775,11 +789,12 @@ namespace ms5611
MS5611 *g_dev;
-void start();
+void start(bool external_bus);
void test();
void reset();
void info();
void calibrate(unsigned altitude);
+void usage();
/**
* MS5611 crc4 cribbed from the datasheet
@@ -832,7 +847,7 @@ crc4(uint16_t *n_prom)
* Start the driver.
*/
void
-start()
+start(bool external_bus)
{
int fd;
prom_u prom_buf;
@@ -845,7 +860,7 @@ start()
/* create the driver, try SPI first, fall back to I2C if unsuccessful */
if (MS5611_spi_interface != nullptr)
- interface = MS5611_spi_interface(prom_buf);
+ interface = MS5611_spi_interface(prom_buf, external_bus);
if (interface == nullptr && (MS5611_i2c_interface != nullptr))
interface = MS5611_i2c_interface(prom_buf);
@@ -1056,43 +1071,68 @@ calibrate(unsigned altitude)
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'info', 'test', 'test2', 'reset', 'calibrate'");
+ warnx("options:");
+ warnx(" -X (external bus)");
+}
+
} // namespace
int
ms5611_main(int argc, char *argv[])
{
+ bool external_bus = false;
+ int ch;
+
+ /* jump over start/off/etc and look at options first */
+ while ((ch = getopt(argc, argv, "X")) != EOF) {
+ switch (ch) {
+ case 'X':
+ external_bus = true;
+ break;
+ default:
+ ms5611::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
- ms5611::start();
+ if (!strcmp(verb, "start"))
+ ms5611::start(external_bus);
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
+ if (!strcmp(verb, "test"))
ms5611::test();
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
+ if (!strcmp(verb, "reset"))
ms5611::reset();
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info"))
+ if (!strcmp(verb, "info"))
ms5611::info();
/*
* Perform MSL pressure calibration given an altitude in metres
*/
- if (!strcmp(argv[1], "calibrate")) {
+ if (!strcmp(verb, "calibrate")) {
if (argc < 2)
errx(1, "missing altitude");
- long altitude = strtol(argv[2], nullptr, 10);
+ long altitude = strtol(argv[optind+1], nullptr, 10);
ms5611::calibrate(altitude);
}
diff --git a/src/drivers/ms5611/ms5611.h b/src/drivers/ms5611/ms5611.h
index 76fb84de8..f0b3fd61d 100644
--- a/src/drivers/ms5611/ms5611.h
+++ b/src/drivers/ms5611/ms5611.h
@@ -80,6 +80,6 @@ extern bool crc4(uint16_t *n_prom);
} /* namespace */
/* interface factories */
-extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf) weak_function;
+extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus) weak_function;
extern device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf) weak_function;
diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp
index 8759d16a1..5234ce8d6 100644
--- a/src/drivers/ms5611/ms5611_spi.cpp
+++ b/src/drivers/ms5611/ms5611_spi.cpp
@@ -62,7 +62,7 @@
#ifdef PX4_SPIDEV_BARO
-device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf);
+device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus);
class MS5611_SPI : public device::SPI
{
@@ -115,9 +115,17 @@ private:
};
device::Device *
-MS5611_spi_interface(ms5611::prom_u &prom_buf)
+MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus)
{
- return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
+ if (external_bus) {
+ #ifdef PX4_SPI_BUS_EXT
+ return new MS5611_SPI(PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_BARO, prom_buf);
+ #else
+ return nullptr;
+ #endif
+ } else {
+ return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
+ }
}
MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) :
diff --git a/src/drivers/pca8574/module.mk b/src/drivers/pca8574/module.mk
index 825ee9bb7..c53ed9ab2 100644
--- a/src/drivers/pca8574/module.mk
+++ b/src/drivers/pca8574/module.mk
@@ -4,3 +4,5 @@
MODULE_COMMAND = pca8574
SRCS = pca8574.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/pca9685/arduino_Adafruit_PWM_Servo_Driver_Library_license.txt b/src/drivers/pca9685/arduino_Adafruit_PWM_Servo_Driver_Library_license.txt
new file mode 100644
index 000000000..9c5eb42eb
--- /dev/null
+++ b/src/drivers/pca9685/arduino_Adafruit_PWM_Servo_Driver_Library_license.txt
@@ -0,0 +1,29 @@
+The following license agreement covers re-used code from the arduino driver
+for the Adafruit I2C to PWM converter.
+
+Software License Agreement (BSD License)
+
+Copyright (c) 2012, Adafruit Industries
+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 of the copyright holders 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 ''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 HOLDER 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.
diff --git a/src/drivers/pca9685/module.mk b/src/drivers/pca9685/module.mk
new file mode 100644
index 000000000..7a5c7996e
--- /dev/null
+++ b/src/drivers/pca9685/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# 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.
+#
+############################################################################
+
+#
+# Driver for the PCA9685 I2C PWM controller
+# The chip is used on the adafruit I2C PWM converter,
+# which allows to control servos via I2C.
+# https://www.adafruit.com/product/815
+
+MODULE_COMMAND = pca9685
+
+SRCS = pca9685.cpp
diff --git a/src/drivers/pca9685/pca9685.cpp b/src/drivers/pca9685/pca9685.cpp
new file mode 100644
index 000000000..6f69ce8a1
--- /dev/null
+++ b/src/drivers/pca9685/pca9685.cpp
@@ -0,0 +1,651 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 pca9685.cpp
+ *
+ * Driver for the PCA9685 I2C PWM module
+ * The chip is used on the Adafruit I2C/PWM converter https://www.adafruit.com/product/815
+ *
+ * Parts of the code are adapted from the arduino library for the board
+ * https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Library
+ * for the license of these parts see the
+ * arduino_Adafruit_PWM_Servo_Driver_Library_license.txt file
+ * see https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Library for contributors
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#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 <math.h>
+
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/actuator_controls.h>
+
+#include <board_config.h>
+#include <drivers/drv_io_expander.h>
+
+#define PCA9685_SUBADR1 0x2
+#define PCA9685_SUBADR2 0x3
+#define PCA9685_SUBADR3 0x4
+
+#define PCA9685_MODE1 0x0
+#define PCA9685_PRESCALE 0xFE
+
+#define LED0_ON_L 0x6
+#define LED0_ON_H 0x7
+#define LED0_OFF_L 0x8
+#define LED0_OFF_H 0x9
+
+#define ALLLED_ON_L 0xFA
+#define ALLLED_ON_H 0xFB
+#define ALLLED_OFF_L 0xFC
+#define ALLLED_OF
+
+#define ADDR 0x40 // I2C adress
+
+#define PCA9685_DEVICE_PATH "/dev/pca9685"
+#define PCA9685_BUS PX4_I2C_BUS_EXPANSION
+#define PCA9685_PWMFREQ 60.0f
+#define PCA9685_NCHANS 16 // total amount of pwm outputs
+
+#define PCA9685_PWMMIN 150 // this is the 'minimum' pulse length count (out of 4096)
+#define PCA9685_PWMMAX 600 // this is the 'maximum' pulse length count (out of 4096)_PWMFREQ 60.0f
+
+#define PCA9685_PWMCENTER ((PCA9685_PWMMAX + PCA9685_PWMMIN)/2)
+#define PCA9685_MAXSERVODEG 90.0f /* maximal servo deflection in degrees
+ PCA9685_PWMMIN <--> -PCA9685_MAXSERVODEG
+ PCA9685_PWMMAX <--> PCA9685_MAXSERVODEG
+ */
+#define PCA9685_SCALE ((PCA9685_PWMMAX - PCA9685_PWMCENTER)/(M_DEG_TO_RAD_F * PCA9685_MAXSERVODEG)) // scales from rad to PWM
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+class PCA9685 : public device::I2C
+{
+public:
+ PCA9685(int bus=PCA9685_BUS, uint8_t address=ADDR);
+ virtual ~PCA9685();
+
+
+ virtual int init();
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+ virtual int info();
+ virtual int reset();
+ bool is_running() { return _running; }
+
+private:
+ work_s _work;
+
+
+ enum IOX_MODE _mode;
+ bool _running;
+ int _i2cpwm_interval;
+ bool _should_run;
+ perf_counter_t _comms_errors;
+
+ uint8_t _msg[6];
+
+ int _actuator_controls_sub;
+ struct actuator_controls_s _actuator_controls;
+ uint16_t _current_values[NUM_ACTUATOR_CONTROLS]; /**< stores the current pwm output
+ values as sent to the setPin() */
+
+ bool _mode_on_initialized; /** Set to true after the first call of i2cpwm in mode IOX_MODE_ON */
+
+ static void i2cpwm_trampoline(void *arg);
+ void i2cpwm();
+
+ /**
+ * Helper function to set the pwm frequency
+ */
+ int setPWMFreq(float freq);
+
+ /**
+ * Helper function to set the demanded pwm value
+ * @param num pwm output number
+ */
+ int setPWM(uint8_t num, uint16_t on, uint16_t off);
+
+ /**
+ * Sets pin without having to deal with on/off tick placement and properly handles
+ * a zero value as completely off. Optional invert parameter supports inverting
+ * the pulse for sinking to ground.
+ * @param num pwm output number
+ * @param val should be a value from 0 to 4095 inclusive.
+ */
+ int setPin(uint8_t num, uint16_t val, bool invert = false);
+
+
+ /* Wrapper to read a byte from addr */
+ int read8(uint8_t addr, uint8_t &value);
+
+ /* Wrapper to wite a byte to addr */
+ int write8(uint8_t addr, uint8_t value);
+
+};
+
+/* for now, we only support one board */
+namespace
+{
+PCA9685 *g_pca9685;
+}
+
+void pca9685_usage();
+
+extern "C" __EXPORT int pca9685_main(int argc, char *argv[]);
+
+PCA9685::PCA9685(int bus, uint8_t address) :
+ I2C("pca9685", PCA9685_DEVICE_PATH, bus, address, 100000),
+ _mode(IOX_MODE_OFF),
+ _running(false),
+ _i2cpwm_interval(SEC2TICK(1.0f/60.0f)),
+ _should_run(false),
+ _comms_errors(perf_alloc(PC_COUNT, "actuator_controls_2_comms_errors")),
+ _actuator_controls_sub(-1),
+ _actuator_controls(),
+ _mode_on_initialized(false)
+{
+ memset(&_work, 0, sizeof(_work));
+ memset(_msg, 0, sizeof(_msg));
+ memset(_current_values, 0, sizeof(_current_values));
+}
+
+PCA9685::~PCA9685()
+{
+}
+
+int
+PCA9685::init()
+{
+ int ret;
+ ret = I2C::init();
+ if (ret != OK) {
+ return ret;
+ }
+
+ ret = reset();
+ if (ret != OK) {
+ return ret;
+ }
+
+ ret = setPWMFreq(PCA9685_PWMFREQ);
+
+ return ret;
+}
+
+int
+PCA9685::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int ret = -EINVAL;
+ switch (cmd) {
+
+ case IOX_SET_MODE:
+
+ if (_mode != (IOX_MODE)arg) {
+
+ switch ((IOX_MODE)arg) {
+ case IOX_MODE_OFF:
+ warnx("shutting down");
+ break;
+ case IOX_MODE_ON:
+ warnx("starting");
+ break;
+ case IOX_MODE_TEST_OUT:
+ warnx("test starting");
+ break;
+
+ default:
+ return -1;
+ }
+
+ _mode = (IOX_MODE)arg;
+ }
+
+ // if not active, kick it
+ if (!_running) {
+ _running = true;
+ work_queue(LPWORK, &_work, (worker_t)&PCA9685::i2cpwm_trampoline, this, 1);
+ }
+
+
+ return OK;
+
+ default:
+ // see if the parent class can make any use of it
+ ret = CDev::ioctl(filp, cmd, arg);
+ break;
+ }
+
+ return ret;
+}
+
+int
+PCA9685::info()
+{
+ int ret = OK;
+
+ if (is_running()) {
+ warnx("Driver is running, mode: %u", _mode);
+ } else {
+ warnx("Driver started but not running");
+ }
+
+ return ret;
+}
+
+void
+PCA9685::i2cpwm_trampoline(void *arg)
+{
+ PCA9685 *i2cpwm = reinterpret_cast<PCA9685 *>(arg);
+
+ i2cpwm->i2cpwm();
+}
+
+/**
+ * Main loop function
+ */
+void
+PCA9685::i2cpwm()
+{
+ if (_mode == IOX_MODE_TEST_OUT) {
+ setPin(0, PCA9685_PWMCENTER);
+ _should_run = true;
+ } else if (_mode == IOX_MODE_OFF) {
+ _should_run = false;
+ } else {
+ if (!_mode_on_initialized) {
+ /* Subscribe to actuator control 2 (payload group for gimbal) */
+ _actuator_controls_sub = orb_subscribe(ORB_ID(actuator_controls_2));
+ /* set the uorb update interval lower than the driver pwm interval */
+ orb_set_interval(_actuator_controls_sub, 1000.0f / PCA9685_PWMFREQ - 5);
+
+ _mode_on_initialized = true;
+ }
+
+ /* Read the servo setpoints from the actuator control topics (gimbal) */
+ bool updated;
+ orb_check(_actuator_controls_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(actuator_controls_2), _actuator_controls_sub, &_actuator_controls);
+ for (int i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
+ /* Scale the controls to PWM, first multiply by pi to get rad,
+ * the control[i] values are on the range -1 ... 1 */
+ uint16_t new_value = PCA9685_PWMCENTER +
+ (_actuator_controls.control[i] * M_PI_F * PCA9685_SCALE);
+ debug("%d: current: %u, new %u, control %.2f", i, _current_values[i], new_value,
+ (double)_actuator_controls.control[i]);
+ if (new_value != _current_values[i] &&
+ isfinite(new_value) &&
+ new_value >= PCA9685_PWMMIN &&
+ new_value <= PCA9685_PWMMAX) {
+ /* This value was updated, send the command to adjust the PWM value */
+ setPin(i, new_value);
+ _current_values[i] = new_value;
+ }
+ }
+ }
+ _should_run = true;
+ }
+
+ // check if any activity remains, else stop
+ if (!_should_run) {
+ _running = false;
+ return;
+ }
+
+ // re-queue ourselves to run again later
+ _running = true;
+ work_queue(LPWORK, &_work, (worker_t)&PCA9685::i2cpwm_trampoline, this, _i2cpwm_interval);
+}
+
+int
+PCA9685::setPWM(uint8_t num, uint16_t on, uint16_t off)
+{
+ int ret;
+ /* convert to correct message */
+ _msg[0] = LED0_ON_L + 4 * num;
+ _msg[1] = on;
+ _msg[2] = on >> 8;
+ _msg[3] = off;
+ _msg[4] = off >> 8;
+
+ /* try i2c transfer */
+ ret = transfer(_msg, 5, nullptr, 0);
+
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+ }
+
+ return ret;
+}
+
+int
+PCA9685::setPin(uint8_t num, uint16_t val, bool invert)
+{
+ // Clamp value between 0 and 4095 inclusive.
+ if (val > 4095) {
+ val = 4095;
+ }
+ if (invert) {
+ if (val == 0) {
+ // Special value for signal fully on.
+ return setPWM(num, 4096, 0);
+ } else if (val == 4095) {
+ // Special value for signal fully off.
+ return setPWM(num, 0, 4096);
+ } else {
+ return setPWM(num, 0, 4095-val);
+ }
+ } else {
+ if (val == 4095) {
+ // Special value for signal fully on.
+ return setPWM(num, 4096, 0);
+ } else if (val == 0) {
+ // Special value for signal fully off.
+ return setPWM(num, 0, 4096);
+ } else {
+ return setPWM(num, 0, val);
+ }
+ }
+
+ return ERROR;
+}
+
+int
+PCA9685::setPWMFreq(float freq)
+{
+ int ret = OK;
+ freq *= 0.9f; /* Correct for overshoot in the frequency setting (see issue
+ https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Library/issues/11). */
+ float prescaleval = 25000000;
+ prescaleval /= 4096;
+ prescaleval /= freq;
+ prescaleval -= 1;
+ uint8_t prescale = uint8_t(prescaleval + 0.5f); //implicit floor()
+ uint8_t oldmode;
+ ret = read8(PCA9685_MODE1, oldmode);
+ if (ret != OK) {
+ return ret;
+ }
+ uint8_t newmode = (oldmode&0x7F) | 0x10; // sleep
+
+ ret = write8(PCA9685_MODE1, newmode); // go to sleep
+ if (ret != OK) {
+ return ret;
+ }
+ ret = write8(PCA9685_PRESCALE, prescale); // set the prescaler
+ if (ret != OK) {
+ return ret;
+ }
+ ret = write8(PCA9685_MODE1, oldmode);
+ if (ret != OK) {
+ return ret;
+ }
+
+ usleep(5000); //5ms delay (from arduino driver)
+
+ ret = write8(PCA9685_MODE1, oldmode | 0xa1); // This sets the MODE1 register to turn on auto increment.
+ if (ret != OK) {
+ return ret;
+ }
+
+ return ret;
+}
+
+/* Wrapper to read a byte from addr */
+int
+PCA9685::read8(uint8_t addr, uint8_t &value)
+{
+ int ret = OK;
+
+ /* send addr */
+ ret = transfer(&addr, sizeof(addr), nullptr, 0);
+ if (ret != OK) {
+ goto fail_read;
+ }
+
+ /* get value */
+ ret = transfer(nullptr, 0, &value, 1);
+ if (ret != OK) {
+ goto fail_read;
+ }
+
+ return ret;
+
+fail_read:
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+
+ return ret;
+}
+
+int PCA9685::reset(void) {
+ warnx("resetting");
+ return write8(PCA9685_MODE1, 0x0);
+}
+
+/* Wrapper to wite a byte to addr */
+int
+PCA9685::write8(uint8_t addr, uint8_t value) {
+ int ret = OK;
+ _msg[0] = addr;
+ _msg[1] = value;
+ /* send addr and value */
+ ret = transfer(_msg, 2, nullptr, 0);
+ if (ret != OK) {
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+ }
+ return ret;
+}
+
+void
+pca9685_usage()
+{
+ warnx("missing command: try 'start', 'test', 'stop', 'info'");
+ warnx("options:");
+ warnx(" -b i2cbus (%d)", PX4_I2C_BUS_EXPANSION);
+ warnx(" -a addr (0x%x)", ADDR);
+}
+
+int
+pca9685_main(int argc, char *argv[])
+{
+ int i2cdevice = -1;
+ int i2caddr = ADDR; // 7bit
+
+ int ch;
+
+ // jump over start/off/etc and look at options first
+ while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
+ switch (ch) {
+ case 'a':
+ i2caddr = strtol(optarg, NULL, 0);
+ break;
+
+ case 'b':
+ i2cdevice = strtol(optarg, NULL, 0);
+ break;
+
+ default:
+ pca9685_usage();
+ exit(0);
+ }
+ }
+
+ if (optind >= argc) {
+ pca9685_usage();
+ exit(1);
+ }
+
+ const char *verb = argv[optind];
+
+ int fd;
+ int ret;
+
+ if (!strcmp(verb, "start")) {
+ if (g_pca9685 != nullptr) {
+ errx(1, "already started");
+ }
+
+ if (i2cdevice == -1) {
+ // try the external bus first
+ i2cdevice = PX4_I2C_BUS_EXPANSION;
+ g_pca9685 = new PCA9685(PX4_I2C_BUS_EXPANSION, i2caddr);
+
+ if (g_pca9685 != nullptr && OK != g_pca9685->init()) {
+ delete g_pca9685;
+ g_pca9685 = nullptr;
+ }
+
+ if (g_pca9685 == nullptr) {
+ errx(1, "init failed");
+ }
+ }
+
+ if (g_pca9685 == nullptr) {
+ g_pca9685 = new PCA9685(i2cdevice, i2caddr);
+
+ if (g_pca9685 == nullptr) {
+ errx(1, "new failed");
+ }
+
+ if (OK != g_pca9685->init()) {
+ delete g_pca9685;
+ g_pca9685 = nullptr;
+ errx(1, "init failed");
+ }
+ }
+ fd = open(PCA9685_DEVICE_PATH, 0);
+ if (fd == -1) {
+ errx(1, "Unable to open " PCA9685_DEVICE_PATH);
+ }
+ ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_ON);
+ close(fd);
+
+
+ exit(0);
+ }
+
+ // need the driver past this point
+ if (g_pca9685 == nullptr) {
+ warnx("not started, run pca9685 start");
+ exit(1);
+ }
+
+ if (!strcmp(verb, "info")) {
+ g_pca9685->info();
+ exit(0);
+ }
+
+ if (!strcmp(verb, "reset")) {
+ g_pca9685->reset();
+ exit(0);
+ }
+
+
+ if (!strcmp(verb, "test")) {
+ fd = open(PCA9685_DEVICE_PATH, 0);
+
+ if (fd == -1) {
+ errx(1, "Unable to open " PCA9685_DEVICE_PATH);
+ }
+
+ ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_TEST_OUT);
+
+ close(fd);
+ exit(ret);
+ }
+
+ if (!strcmp(verb, "stop")) {
+ fd = open(PCA9685_DEVICE_PATH, 0);
+
+ if (fd == -1) {
+ errx(1, "Unable to open " PCA9685_DEVICE_PATH);
+ }
+
+ ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_OFF);
+ close(fd);
+
+ // wait until we're not running any more
+ for (unsigned i = 0; i < 15; i++) {
+ if (!g_pca9685->is_running()) {
+ break;
+ }
+
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+ }
+ printf("\n");
+ fflush(stdout);
+
+ if (!g_pca9685->is_running()) {
+ delete g_pca9685;
+ g_pca9685= nullptr;
+ warnx("stopped, exiting");
+ exit(0);
+ } else {
+ warnx("stop failed.");
+ exit(1);
+ }
+ }
+
+ pca9685_usage();
+ exit(0);
+}
diff --git a/src/drivers/px4flow/module.mk b/src/drivers/px4flow/module.mk
index d3062e457..460bec7b9 100644
--- a/src/drivers/px4flow/module.mk
+++ b/src/drivers/px4flow/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = px4flow
SRCS = px4flow.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp
index f214b5964..804027b05 100644
--- a/src/drivers/px4flow/px4flow.cpp
+++ b/src/drivers/px4flow/px4flow.cpp
@@ -37,7 +37,7 @@
*
* Driver for the PX4FLOW module connected via I2C.
*/
-
+
#include <nuttx/config.h>
#include <drivers/device/i2c.h>
@@ -68,7 +68,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/subsystem_info.h>
-//#include <uORB/topics/optical_flow.h>
+#include <uORB/topics/optical_flow.h>
#include <board_config.h>
@@ -80,7 +80,7 @@
/* PX4FLOW Registers addresses */
#define PX4FLOW_REG 0x00 /* Measure Register */
-#define PX4FLOW_CONVERSION_INTERVAL 8000 /* 8ms 125Hz
+#define PX4FLOW_CONVERSION_INTERVAL 8000 /* 8ms 125Hz */
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -115,17 +115,17 @@ class PX4FLOW : public device::I2C
public:
PX4FLOW(int bus = PX4FLOW_BUS, int address = I2C_FLOW_ADDRESS);
virtual ~PX4FLOW();
-
+
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();
@@ -136,13 +136,13 @@ private:
bool _sensor_ok;
int _measure_ticks;
bool _collect_phase;
-
+
orb_advert_t _px4flow_topic;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
-
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -151,7 +151,7 @@ private:
* @return True if the device is present.
*/
int probe_address(uint8_t address);
-
+
/**
* Initialise the automatic measurement state machine and start it.
*
@@ -159,12 +159,12 @@ private:
* to make it more aggressive about resetting the bus in case of errors.
*/
void start();
-
+
/**
* Stop the automatic measurement state machine.
*/
void stop();
-
+
/**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
@@ -179,8 +179,8 @@ private:
* @param arg Instance pointer for the driver that is polling.
*/
static void cycle_trampoline(void *arg);
-
-
+
+
};
/*
@@ -200,8 +200,8 @@ PX4FLOW::PX4FLOW(int bus, int address) :
_buffer_overflows(perf_alloc(PC_COUNT, "px4flow_buffer_overflows"))
{
// enable debug() calls
- _debug_enabled = true;
-
+ _debug_enabled = false;
+
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
}
@@ -212,8 +212,9 @@ PX4FLOW::~PX4FLOW()
stop();
/* free any existing reports */
- if (_reports != nullptr)
+ if (_reports != nullptr) {
delete _reports;
+ }
}
int
@@ -222,22 +223,25 @@ PX4FLOW::init()
int ret = ERROR;
/* do I2C init (and probe) first */
- if (I2C::init() != OK)
+ if (I2C::init() != OK) {
goto out;
+ }
/* allocate basic report buffers */
- _reports = new RingBuffer(2, sizeof(px4flow_report));
+ _reports = new RingBuffer(2, sizeof(struct optical_flow_s));
- if (_reports == nullptr)
+ if (_reports == nullptr) {
goto out;
+ }
/* get a publish handle on the px4flow topic */
- struct px4flow_report zero_report;
+ struct optical_flow_s zero_report;
memset(&zero_report, 0, sizeof(zero_report));
_px4flow_topic = orb_advertise(ORB_ID(optical_flow), &zero_report);
- if (_px4flow_topic < 0)
- debug("failed to create px4flow object. Did you start uOrb?");
+ if (_px4flow_topic < 0) {
+ warnx("failed to create px4flow object. Did you start uOrb?");
+ }
ret = OK;
/* sensor is ok, but we don't really know if it is within range */
@@ -249,6 +253,17 @@ out:
int
PX4FLOW::probe()
{
+ uint8_t val[22];
+
+ // to be sure this is not a ll40ls Lidar (which can also be on
+ // 0x42) we check if a 22 byte transfer works from address
+ // 0. The ll40ls gives an error for that, whereas the flow
+ // happily returns some data
+ if (transfer(nullptr, 0, &val[0], 22) != OK) {
+ return -EIO;
+ }
+
+ // that worked, so start a measurement cycle
return measure();
}
@@ -260,20 +275,20 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSORIOCSPOLLRATE: {
switch (arg) {
- /* switching to manual polling */
+ /* switching to manual polling */
case SENSOR_POLLRATE_MANUAL:
stop();
_measure_ticks = 0;
return OK;
- /* external signalling (DRDY) not supported */
+ /* external signalling (DRDY) not supported */
case SENSOR_POLLRATE_EXTERNAL:
- /* zero would be bad */
+ /* zero would be bad */
case 0:
return -EINVAL;
- /* set default/max polling rate */
+ /* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT: {
/* do we need to start internal polling? */
@@ -283,13 +298,14 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
_measure_ticks = USEC2TICK(PX4FLOW_CONVERSION_INTERVAL);
/* if we need to start the poll state machine, do it */
- if (want_start)
+ if (want_start) {
start();
+ }
return OK;
}
- /* adjust to a legal polling interval in Hz */
+ /* adjust to a legal polling interval in Hz */
default: {
/* do we need to start internal polling? */
bool want_start = (_measure_ticks == 0);
@@ -298,15 +314,17 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
unsigned ticks = USEC2TICK(1000000 / arg);
/* check against maximum rate */
- if (ticks < USEC2TICK(PX4FLOW_CONVERSION_INTERVAL))
+ if (ticks < USEC2TICK(PX4FLOW_CONVERSION_INTERVAL)) {
return -EINVAL;
+ }
/* update interval for next measurement */
_measure_ticks = ticks;
/* if we need to start the poll state machine, do it */
- if (want_start)
+ if (want_start) {
start();
+ }
return OK;
}
@@ -314,33 +332,37 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
}
case SENSORIOCGPOLLRATE:
- if (_measure_ticks == 0)
+ if (_measure_ticks == 0) {
return SENSOR_POLLRATE_MANUAL;
+ }
return (1000 / _measure_ticks);
case SENSORIOCSQUEUEDEPTH: {
- /* lower bound is mandatory, upper bound is a sanity check */
- if ((arg < 1) || (arg > 100))
- return -EINVAL;
-
- irqstate_t flags = irqsave();
- if (!_reports->resize(arg)) {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100)) {
+ return -EINVAL;
+ }
+
+ irqstate_t flags = irqsave();
+
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+
irqrestore(flags);
- return -ENOMEM;
+
+ return OK;
}
- irqrestore(flags);
-
- return OK;
- }
case SENSORIOCGQUEUEDEPTH:
return _reports->size();
-
+
case SENSORIOCRESET:
/* XXX implement this */
return -EINVAL;
-
+
default:
/* give it to the superclass */
return I2C::ioctl(filp, cmd, arg);
@@ -350,13 +372,14 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
ssize_t
PX4FLOW::read(struct file *filp, char *buffer, size_t buflen)
{
- unsigned count = buflen / sizeof(struct px4flow_report);
- struct px4flow_report *rbuf = reinterpret_cast<struct px4flow_report *>(buffer);
+ unsigned count = buflen / sizeof(struct optical_flow_s);
+ struct optical_flow_s *rbuf = reinterpret_cast<struct optical_flow_s *>(buffer);
int ret = 0;
/* buffer must be large enough */
- if (count < 1)
+ if (count < 1) {
return -ENOSPC;
+ }
/* if automatic measurement is enabled */
if (_measure_ticks > 0) {
@@ -417,15 +440,13 @@ PX4FLOW::measure()
uint8_t cmd = PX4FLOW_REG;
ret = transfer(&cmd, 1, nullptr, 0);
- if (OK != ret)
- {
+ if (OK != ret) {
perf_count(_comms_errors);
- log("i2c::transfer returned %d", ret);
- printf("i2c::transfer flow returned %d");
return ret;
}
+
ret = OK;
-
+
return ret;
}
@@ -433,22 +454,21 @@ int
PX4FLOW::collect()
{
int ret = -EIO;
-
+
/* read from the sensor */
- uint8_t val[22] = {0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0};
-
+ uint8_t val[22] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
+
perf_begin(_sample_perf);
-
+
ret = transfer(nullptr, 0, &val[0], 22);
-
- if (ret < 0)
- {
- log("error reading from sensor: %d", ret);
+
+ if (ret < 0) {
+ debug("error reading from sensor: %d", ret);
perf_count(_comms_errors);
perf_end(_sample_perf);
return ret;
}
-
+
// f.frame_count = val[1] << 8 | val[0];
// f.pixel_flow_x_sum= val[3] << 8 | val[2];
// f.pixel_flow_y_sum= val[5] << 8 | val[4];
@@ -466,13 +486,13 @@ PX4FLOW::collect()
int16_t flowcy = val[9] << 8 | val[8];
int16_t gdist = val[21] << 8 | val[20];
- struct px4flow_report report;
- report.flow_comp_x_m = float(flowcx)/1000.0f;
- report.flow_comp_y_m = float(flowcy)/1000.0f;
- report.flow_raw_x= val[3] << 8 | val[2];
- report.flow_raw_y= val[5] << 8 | val[4];
- report.ground_distance_m =float(gdist)/1000.0f;
- report.quality= val[10];
+ struct optical_flow_s report;
+ report.flow_comp_x_m = float(flowcx) / 1000.0f;
+ report.flow_comp_y_m = float(flowcy) / 1000.0f;
+ report.flow_raw_x = val[3] << 8 | val[2];
+ report.flow_raw_y = val[5] << 8 | val[4];
+ report.ground_distance_m = float(gdist) / 1000.0f;
+ report.quality = val[10];
report.sensor_id = 0;
report.timestamp = hrt_absolute_time();
@@ -503,17 +523,19 @@ PX4FLOW::start()
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&PX4FLOW::cycle_trampoline, this, 1);
-
+
/* notify about state change */
struct subsystem_info_s info = {
true,
true,
true,
- SUBSYSTEM_TYPE_OPTICALFLOW};
+ SUBSYSTEM_TYPE_OPTICALFLOW
+ };
static orb_advert_t pub = -1;
if (pub > 0) {
orb_publish(ORB_ID(subsystem_info), pub, &info);
+
} else {
pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
@@ -541,7 +563,7 @@ PX4FLOW::cycle()
/* perform collection */
if (OK != collect()) {
- log("collection error");
+ debug("collection error");
/* restart the measurement state machine */
start();
return;
@@ -567,8 +589,9 @@ PX4FLOW::cycle()
}
/* measurement phase */
- if (OK != measure())
- log("measure error");
+ if (OK != measure()) {
+ debug("measure error");
+ }
/* next phase is collection */
_collect_phase = true;
@@ -619,33 +642,37 @@ start()
{
int fd;
- if (g_dev != nullptr)
+ if (g_dev != nullptr) {
errx(1, "already started");
+ }
/* create the driver */
g_dev = new PX4FLOW(PX4FLOW_BUS);
- if (g_dev == nullptr)
+ if (g_dev == nullptr) {
goto fail;
+ }
- if (OK != g_dev->init())
+ if (OK != g_dev->init()) {
goto fail;
+ }
/* set the poll rate to default, starts automatic data collection */
fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
goto fail;
+ }
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX) < 0)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX) < 0) {
goto fail;
+ }
exit(0);
fail:
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
}
@@ -658,15 +685,14 @@ fail:
*/
void stop()
{
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
- }
- else
- {
+
+ } else {
errx(1, "driver not running");
}
+
exit(0);
}
@@ -678,20 +704,23 @@ void stop()
void
test()
{
- struct px4flow_report report;
+ struct optical_flow_s report;
ssize_t sz;
int ret;
int fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
err(1, "%s open failed (try 'px4flow start' if the driver is not running", PX4FLOW_DEVICE_PATH);
+ }
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
if (sz != sizeof(report))
- // err(1, "immediate read failed");
+ {
+ warnx("immediate read failed");
+ }
warnx("single read");
warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
@@ -700,8 +729,9 @@ test()
/* start the sensor polling at 2Hz */
- if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
errx(1, "failed to set 2Hz poll rate");
+ }
/* read the sensor 5x and report each value */
for (unsigned i = 0; i < 5; i++) {
@@ -712,14 +742,16 @@ test()
fds.events = POLLIN;
ret = poll(&fds, 1, 2000);
- if (ret != 1)
+ if (ret != 1) {
errx(1, "timed out waiting for sensor data");
+ }
/* now go get it */
sz = read(fd, &report, sizeof(report));
- if (sz != sizeof(report))
+ if (sz != sizeof(report)) {
err(1, "periodic read failed");
+ }
warnx("periodic read %u", i);
warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
@@ -740,14 +772,17 @@ reset()
{
int fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
err(1, "failed ");
+ }
- if (ioctl(fd, SENSORIOCRESET, 0) < 0)
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
err(1, "driver reset failed");
+ }
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
err(1, "driver poll restart failed");
+ }
exit(0);
}
@@ -758,8 +793,9 @@ reset()
void
info()
{
- if (g_dev == nullptr)
+ if (g_dev == nullptr) {
errx(1, "driver not running");
+ }
printf("state @ %p\n", g_dev);
g_dev->print_info();
@@ -775,32 +811,37 @@ px4flow_main(int argc, char *argv[])
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
+ if (!strcmp(argv[1], "start")) {
px4flow::start();
-
- /*
- * Stop the driver
- */
- if (!strcmp(argv[1], "stop"))
- px4flow::stop();
+ }
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop")) {
+ px4flow::stop();
+ }
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
+ if (!strcmp(argv[1], "test")) {
px4flow::test();
+ }
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
+ if (!strcmp(argv[1], "reset")) {
px4flow::reset();
+ }
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
+ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
px4flow::info();
+ }
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
}
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 8a4bfa18c..3d3e1b0eb 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -179,6 +179,9 @@ private:
uint32_t gpio_read(void);
int gpio_ioctl(file *filp, int cmd, unsigned long arg);
+ /* do not allow to copy due to ptr data members */
+ PX4FMU(const PX4FMU&);
+ PX4FMU operator=(const PX4FMU&);
};
const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
@@ -240,10 +243,9 @@ PX4FMU::PX4FMU() :
_pwm_alt_rate_channels(0),
_current_update_rate(0),
_task(-1),
- _control_subs({-1}),
- _poll_fds_num(0),
_armed_sub(-1),
_outputs_pub(-1),
+ _armed{},
_num_outputs(0),
_primary_pwm_device(false),
_task_should_exit(false),
@@ -252,10 +254,13 @@ PX4FMU::PX4FMU() :
_mixers(nullptr),
_groups_required(0),
_groups_subscribed(0),
- _failsafe_pwm({0}),
- _disarmed_pwm({0}),
- _num_failsafe_set(0),
- _num_disarmed_set(0)
+ _control_subs{-1},
+ _poll_fds_num(0),
+ _pwm_limit{},
+ _failsafe_pwm{0},
+ _disarmed_pwm{0},
+ _num_failsafe_set(0),
+ _num_disarmed_set(0)
{
for (unsigned i = 0; i < _max_actuators; i++) {
_min_pwm[i] = PWM_DEFAULT_MIN;
@@ -329,7 +334,7 @@ PX4FMU::init()
_task = task_spawn_cmd("fmuservo",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 1600,
(main_t)&PX4FMU::task_main_trampoline,
nullptr);
@@ -741,7 +746,7 @@ PX4FMU::task_main()
}
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
- if (_control_subs > 0) {
+ if (_control_subs[i] > 0) {
::close(_control_subs[i]);
_control_subs[i] = -1;
}
@@ -824,6 +829,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_SET_ARM_OK:
case PWM_SERVO_CLEAR_ARM_OK:
case PWM_SERVO_SET_FORCE_SAFETY_OFF:
+ case PWM_SERVO_SET_FORCE_SAFETY_ON:
// these are no-ops, as no safety switch
break;
@@ -1267,7 +1273,9 @@ PX4FMU::write(file *filp, const char *buffer, size_t len)
memcpy(values, buffer, count * 2);
for (uint8_t i = 0; i < count; i++) {
- up_pwm_servo_set(i, values[i]);
+ if (values[i] != PWM_IGNORE_THIS_CHANNEL) {
+ up_pwm_servo_set(i, values[i]);
+ }
}
return count * 2;
@@ -1784,7 +1792,7 @@ fmu_main(int argc, char *argv[])
}
if (!strcmp(verb, "id")) {
- char id[12];
+ uint8_t id[12];
(void)get_board_serial(id);
errx(0, "Board serial:\n %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X",
diff --git a/src/drivers/px4fmu/module.mk b/src/drivers/px4fmu/module.mk
index eeb59e1a1..a06323a52 100644
--- a/src/drivers/px4fmu/module.mk
+++ b/src/drivers/px4fmu/module.mk
@@ -6,3 +6,7 @@ MODULE_COMMAND = fmu
SRCS = fmu.cpp
MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/px4io/module.mk b/src/drivers/px4io/module.mk
index c14f1f783..924283356 100644
--- a/src/drivers/px4io/module.mk
+++ b/src/drivers/px4io/module.mk
@@ -46,3 +46,7 @@ SRCS = px4io.cpp \
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Weffc++
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 992ab9623..519ba663a 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -72,6 +72,7 @@
#include <systemlib/systemlib.h>
#include <systemlib/scheduling_priorities.h>
#include <systemlib/param/param.h>
+#include <systemlib/circuit_breaker.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
@@ -135,6 +136,15 @@ public:
virtual int init();
/**
+ * Initialize the PX4IO class.
+ *
+ * Retrieve relevant initial system parameters. Initialize PX4IO registers.
+ *
+ * @param disable_rc_handling set to true to forbid override / RC handling on IO
+ */
+ int init(bool disable_rc_handling);
+
+ /**
* Detect if a PX4IO is connected.
*
* Only validate if there is a PX4IO to talk to.
@@ -285,6 +295,7 @@ private:
float _battery_amp_bias; ///< current sensor bias
float _battery_mamphour_total;///< amp hours consumed so far
uint64_t _battery_last_timestamp;///< last amp hour calculation timestamp
+ bool _cb_flighttermination; ///< true if the flight termination circuit breaker is enabled
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
bool _dsm_vcc_ctl; ///< true if relay 1 controls DSM satellite RX power
@@ -452,6 +463,9 @@ private:
*/
void io_handle_vservo(uint16_t vservo, uint16_t vrssi);
+ /* do not allow to copy this class due to ptr data members */
+ PX4IO(const PX4IO&);
+ PX4IO operator=(const PX4IO&);
};
namespace
@@ -495,12 +509,15 @@ PX4IO::PX4IO(device::Device *interface) :
_to_battery(0),
_to_servorail(0),
_to_safety(0),
+ _outputs{},
+ _servorail_status{},
_primary_pwm_device(false),
_lockdown_override(false),
_battery_amp_per_volt(90.0f / 5.0f), // this matches the 3DR current sensor
_battery_amp_bias(0),
_battery_mamphour_total(0),
- _battery_last_timestamp(0)
+ _battery_last_timestamp(0),
+ _cb_flighttermination(true)
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
, _dsm_vcc_ctl(false)
#endif
@@ -574,6 +591,12 @@ PX4IO::detect()
}
int
+PX4IO::init(bool rc_handling_disabled) {
+ _rc_handling_disabled = rc_handling_disabled;
+ return init();
+}
+
+int
PX4IO::init()
{
int ret;
@@ -772,6 +795,11 @@ PX4IO::init()
if (_rc_handling_disabled) {
ret = io_disable_rc_handling();
+ if (ret != OK) {
+ log("failed disabling RC handling");
+ return ret;
+ }
+
} else {
/* publish RC config to IO */
ret = io_set_rc_config();
@@ -1012,6 +1040,22 @@ PX4IO::task_main()
}
}
+ int32_t safety_param_val;
+ param_t safety_param = param_find("RC_FAILS_THR");
+
+ if (safety_param != PARAM_INVALID) {
+
+ param_get(safety_param, &safety_param_val);
+
+ if (safety_param_val == PX4IO_FORCE_SAFETY_MAGIC) {
+ /* disable IO safety if circuit breaker asked for it */
+ (void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, safety_param_val);
+ }
+ }
+
+ /* Update Circuit breakers */
+ _cb_flighttermination = circuit_breaker_enabled("CBRK_FLIGHTTERM", CBRK_FLIGHTTERM_KEY);
+
}
}
@@ -1130,6 +1174,21 @@ PX4IO::io_set_arming_state()
clear |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
}
+ /* Do not set failsafe if circuit breaker is enabled */
+ if (armed.force_failsafe && !_cb_flighttermination) {
+ set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
+ } else {
+ clear |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
+ }
+
+ // XXX this is for future support in the commander
+ // but can be removed if unneeded
+ // if (armed.termination_failsafe) {
+ // set |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
+ // } else {
+ // clear |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
+ // }
+
if (armed.ready_to_arm) {
set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
@@ -1150,6 +1209,7 @@ PX4IO::io_set_arming_state()
int
PX4IO::disable_rc_handling()
{
+ _rc_handling_disabled = true;
return io_disable_rc_handling();
}
@@ -1185,30 +1245,43 @@ PX4IO::io_set_rc_config()
* for compatibility reasons with existing
* autopilots / GCS'.
*/
- param_get(param_find("RC_MAP_ROLL"), &ichan);
- if ((ichan >= 0) && (ichan < (int)_max_rc_input))
+ /* ROLL */
+ param_get(param_find("RC_MAP_ROLL"), &ichan);
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
input_map[ichan - 1] = 0;
+ }
+ /* PITCH */
param_get(param_find("RC_MAP_PITCH"), &ichan);
-
- if ((ichan >= 0) && (ichan < (int)_max_rc_input))
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
input_map[ichan - 1] = 1;
+ }
+ /* YAW */
param_get(param_find("RC_MAP_YAW"), &ichan);
-
- if ((ichan >= 0) && (ichan < (int)_max_rc_input))
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
input_map[ichan - 1] = 2;
+ }
+ /* THROTTLE */
param_get(param_find("RC_MAP_THROTTLE"), &ichan);
-
- if ((ichan >= 0) && (ichan < (int)_max_rc_input))
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
input_map[ichan - 1] = 3;
+ }
- param_get(param_find("RC_MAP_MODE_SW"), &ichan);
-
- if ((ichan >= 0) && (ichan < (int)_max_rc_input))
+ /* FLAPS */
+ param_get(param_find("RC_MAP_FLAPS"), &ichan);
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
input_map[ichan - 1] = 4;
+ }
+
+ /* MAIN MODE SWITCH */
+ param_get(param_find("RC_MAP_MODE_SW"), &ichan);
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
+ /* use out of normal bounds index to indicate special channel */
+ input_map[ichan - 1] = PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH;
+ }
/*
* Iterate all possible RC inputs.
@@ -1369,7 +1442,7 @@ void
PX4IO::io_handle_battery(uint16_t vbatt, uint16_t ibatt)
{
/* only publish if battery has a valid minimum voltage */
- if (vbatt <= 3300) {
+ if (vbatt <= 4900) {
return;
}
@@ -1557,6 +1630,9 @@ PX4IO::io_publish_raw_rc()
} else if (_status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
rc_val.input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
+ } else if (_status & PX4IO_P_STATUS_FLAGS_RC_ST24) {
+ rc_val.input_source = RC_INPUT_SOURCE_PX4IO_ST24;
+
} else {
rc_val.input_source = RC_INPUT_SOURCE_UNKNOWN;
@@ -1581,10 +1657,6 @@ PX4IO::io_publish_raw_rc()
int
PX4IO::io_publish_pwm_outputs()
{
- /* if no FMU comms(!) just don't publish */
- if (!(_status & PX4IO_P_STATUS_FLAGS_FMU_OK))
- return OK;
-
/* data we are going to fetch */
actuator_outputs_s outputs;
outputs.timestamp = hrt_absolute_time();
@@ -1874,13 +1946,15 @@ PX4IO::print_status(bool extended_status)
io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FREEMEM));
uint16_t flags = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS);
uint16_t io_status_flags = flags;
- printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s\n",
+ printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s%s%s\n",
flags,
((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" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) ? " DSM" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_RC_ST24) ? " ST24" : ""),
((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_PWM_PASSTHROUGH" : ""),
@@ -1922,7 +1996,7 @@ PX4IO::print_status(bool extended_status)
printf("actuators");
for (unsigned i = 0; i < _max_actuators; i++)
- printf(" %u", io_reg_get(PX4IO_PAGE_ACTUATORS, i));
+ printf(" %hi", int16_t(io_reg_get(PX4IO_PAGE_ACTUATORS, i)));
printf("\n");
printf("servos");
@@ -1983,7 +2057,7 @@ PX4IO::print_status(bool extended_status)
((features & PX4IO_P_SETUP_FEATURES_ADC_RSSI) ? " RSSI_ADC" : "")
);
uint16_t arming = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING);
- printf("arming 0x%04x%s%s%s%s%s%s%s\n",
+ printf("arming 0x%04x%s%s%s%s%s%s%s%s%s%s\n",
arming,
((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"),
@@ -1991,7 +2065,11 @@ PX4IO::print_status(bool extended_status)
((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" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) ? " LOCKDOWN" : ""));
+ ((arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) ? " LOCKDOWN" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) ? " FORCE_FAILSAFE" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) ? " TERM_FAILSAFE" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE) ? " OVERRIDE_IMMEDIATE" : "")
+ );
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
printf("rates 0x%04x default %u alt %u relays 0x%04x\n",
io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES),
@@ -2203,6 +2281,46 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC);
break;
+ case PWM_SERVO_SET_FORCE_SAFETY_ON:
+ /* force safety switch on */
+ ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_ON, PX4IO_FORCE_SAFETY_MAGIC);
+ break;
+
+ case PWM_SERVO_SET_FORCE_FAILSAFE:
+ /* force failsafe mode instantly */
+ if (arg == 0) {
+ /* clear force failsafe flag */
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE, 0);
+ } else {
+ /* set force failsafe flag */
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE);
+ }
+ break;
+
+ case PWM_SERVO_SET_TERMINATION_FAILSAFE:
+ /* if failsafe occurs, do not allow the system to recover */
+ if (arg == 0) {
+ /* clear termination failsafe flag */
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE, 0);
+ } else {
+ /* set termination failsafe flag */
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE);
+ }
+ break;
+
+ case PWM_SERVO_SET_OVERRIDE_IMMEDIATE:
+ /* control whether override on FMU failure is
+ immediate or waits for override threshold on mode
+ switch */
+ if (arg == 0) {
+ /* clear override immediate flag */
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE, 0);
+ } else {
+ /* set override immediate flag */
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE);
+ }
+ break;
+
case DSM_BIND_START:
/* only allow DSM2, DSM-X and DSM-X with more than 7 channels */
@@ -2380,6 +2498,9 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
} else if (status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
+ } else if (status & PX4IO_P_STATUS_FLAGS_RC_ST24) {
+ rc_val->input_source = RC_INPUT_SOURCE_PX4IO_ST24;
+
} else {
rc_val->input_source = RC_INPUT_SOURCE_UNKNOWN;
}
@@ -2405,7 +2526,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
break;
case PX4IO_CHECK_CRC: {
- /* check IO firmware CRC against passed value */
+ /* check IO firmware CRC against passed value */
uint32_t io_crc = 0;
ret = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_CRC, (uint16_t *)&io_crc, 2);
if (ret != OK)
@@ -2461,6 +2582,42 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
break;
+ case PWM_SERVO_SET_RC_CONFIG: {
+ /* enable setting of RC configuration without relying
+ on param_get()
+ */
+ struct pwm_output_rc_config* config = (struct pwm_output_rc_config*)arg;
+ if (config->channel >= _max_actuators) {
+ /* fail with error */
+ return E2BIG;
+ }
+
+ /* copy values to registers in IO */
+ uint16_t regs[PX4IO_P_RC_CONFIG_STRIDE];
+ uint16_t offset = config->channel * PX4IO_P_RC_CONFIG_STRIDE;
+ regs[PX4IO_P_RC_CONFIG_MIN] = config->rc_min;
+ regs[PX4IO_P_RC_CONFIG_CENTER] = config->rc_trim;
+ regs[PX4IO_P_RC_CONFIG_MAX] = config->rc_max;
+ regs[PX4IO_P_RC_CONFIG_DEADZONE] = config->rc_dz;
+ regs[PX4IO_P_RC_CONFIG_ASSIGNMENT] = config->rc_assignment;
+ regs[PX4IO_P_RC_CONFIG_OPTIONS] = PX4IO_P_RC_CONFIG_OPTIONS_ENABLED;
+ if (config->rc_reverse) {
+ regs[PX4IO_P_RC_CONFIG_OPTIONS] |= PX4IO_P_RC_CONFIG_OPTIONS_REVERSE;
+ }
+ ret = io_reg_set(PX4IO_PAGE_RC_CONFIG, offset, regs, PX4IO_P_RC_CONFIG_STRIDE);
+ break;
+ }
+
+ case PWM_SERVO_SET_OVERRIDE_OK:
+ /* set the 'OVERRIDE OK' bit */
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK);
+ break;
+
+ case PWM_SERVO_CLEAR_OVERRIDE_OK:
+ /* clear the 'OVERRIDE OK' bit */
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK, 0);
+ break;
+
default:
/* see if the parent class can make any use of it */
ret = CDev::ioctl(filep, cmd, arg);
@@ -2575,24 +2732,25 @@ start(int argc, char *argv[])
errx(1, "driver alloc failed");
}
- if (OK != g_dev->init()) {
- delete g_dev;
- g_dev = nullptr;
- errx(1, "driver init failed");
- }
+ bool rc_handling_disabled = false;
/* disable RC handling on request */
if (argc > 1) {
if (!strcmp(argv[1], "norc")) {
- if (g_dev->disable_rc_handling())
- warnx("Failed disabling RC handling");
+ rc_handling_disabled = true;
} else {
warnx("unknown argument: %s", argv[1]);
}
}
+ if (OK != g_dev->init(rc_handling_disabled)) {
+ delete g_dev;
+ g_dev = nullptr;
+ errx(1, "driver init failed");
+ }
+
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
int dsm_vcc_ctl;
@@ -2665,7 +2823,7 @@ checkcrc(int argc, char *argv[])
int fd = open(argv[1], O_RDONLY);
if (fd == -1) {
printf("open of %s failed - %d\n", argv[1], errno);
- exit(1);
+ exit(1);
}
const uint32_t app_size_max = 0xf000;
uint32_t fw_crc = 0;
@@ -2680,7 +2838,7 @@ checkcrc(int argc, char *argv[])
close(fd);
while (nbytes < app_size_max) {
uint8_t b = 0xff;
- fw_crc = crc32part(&b, 1, fw_crc);
+ fw_crc = crc32part(&b, 1, fw_crc);
nbytes++;
}
@@ -2693,7 +2851,7 @@ checkcrc(int argc, char *argv[])
if (ret != OK) {
printf("check CRC failed - %d\n", ret);
- exit(1);
+ exit(1);
}
printf("CRCs match\n");
exit(0);
@@ -2723,12 +2881,12 @@ bind(int argc, char *argv[])
pulses = DSMX_BIND_PULSES;
else if (!strcmp(argv[2], "dsmx8"))
pulses = DSMX8_BIND_PULSES;
- else
+ else
errx(1, "unknown parameter %s, use dsm2, dsmx or dsmx8", argv[2]);
// Test for custom pulse parameter
if (argc > 3)
pulses = atoi(argv[3]);
- if (g_dev->system_status() & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
+ if (g_dev->system_status() & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
errx(1, "system must not be armed");
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
@@ -2930,7 +3088,7 @@ lockdown(int argc, char *argv[])
(void)g_dev->ioctl(0, PWM_SERVO_SET_DISABLE_LOCKDOWN, 0);
warnx("ACTUATORS ARE NOW SAFE IN HIL.");
}
-
+
} else {
errx(1, "driver not loaded, exiting");
}
diff --git a/src/drivers/px4io/px4io_i2c.cpp b/src/drivers/px4io/px4io_i2c.cpp
index 19776c40a..c57ddf65b 100644..100755
--- a/src/drivers/px4io/px4io_i2c.cpp
+++ b/src/drivers/px4io/px4io_i2c.cpp
@@ -79,7 +79,7 @@ device::Device
}
PX4IO_I2C::PX4IO_I2C(int bus, uint8_t address) :
- I2C("PX4IO_i2c", nullptr, bus, address, 320000)
+ I2C("PX4IO_i2c", nullptr, bus, address, 400000)
{
_retries = 3;
}
diff --git a/src/drivers/px4io/px4io_serial.cpp b/src/drivers/px4io/px4io_serial.cpp
index 3b210ac59..d227e15d5 100644
--- a/src/drivers/px4io/px4io_serial.cpp
+++ b/src/drivers/px4io/px4io_serial.cpp
@@ -157,6 +157,10 @@ private:
perf_counter_t _pc_idle;
perf_counter_t _pc_badidle;
+ /* do not allow top copying this class */
+ PX4IO_serial(PX4IO_serial &);
+ PX4IO_serial& operator = (const PX4IO_serial &);
+
};
IOPacket PX4IO_serial::_dma_buffer;
@@ -173,7 +177,9 @@ PX4IO_serial::PX4IO_serial() :
_tx_dma(nullptr),
_rx_dma(nullptr),
_rx_dma_status(_dma_status_inactive),
- _pc_txns(perf_alloc(PC_ELAPSED, "io_txns ")),
+ _bus_semaphore(SEM_INITIALIZER(0)),
+ _completion_semaphore(SEM_INITIALIZER(0)),
+ _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 ")),
@@ -639,7 +645,7 @@ PX4IO_serial::_do_interrupt()
if (_rx_dma_status == _dma_status_waiting) {
/* verify that the received packet is complete */
- int length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
+ size_t length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
if ((length < 1) || (length < PKT_SIZE(_dma_buffer))) {
perf_count(_pc_badidle);
diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp
index 7b6361a7c..fb16f891f 100644
--- a/src/drivers/px4io/px4io_uploader.cpp
+++ b/src/drivers/px4io/px4io_uploader.cpp
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
#include <assert.h>
@@ -64,7 +65,8 @@
PX4IO_Uploader::PX4IO_Uploader() :
_io_fd(-1),
- _fw_fd(-1)
+ _fw_fd(-1),
+ bl_rev(0)
{
}
@@ -203,12 +205,8 @@ PX4IO_Uploader::upload(const char *filenames[])
if (bl_rev <= 2) {
ret = verify_rev2(fw_size);
- } else if(bl_rev == 3) {
- ret = verify_rev3(fw_size);
} else {
- /* verify rev 4 and higher still uses the same approach and
- * every version *needs* to be verified.
- */
+ /* verify rev 3 and higher. Every version *needs* to be verified. */
ret = verify_rev3(fw_size);
}
@@ -248,7 +246,7 @@ PX4IO_Uploader::upload(const char *filenames[])
}
int
-PX4IO_Uploader::recv(uint8_t &c, unsigned timeout)
+PX4IO_Uploader::recv_byte_with_timeout(uint8_t *c, unsigned timeout)
{
struct pollfd fds[1];
@@ -265,24 +263,24 @@ PX4IO_Uploader::recv(uint8_t &c, unsigned timeout)
return -ETIMEDOUT;
}
- read(_io_fd, &c, 1);
+ read(_io_fd, c, 1);
#ifdef UDEBUG
- log("recv 0x%02x", c);
+ log("recv_bytes 0x%02x", c);
#endif
return OK;
}
int
-PX4IO_Uploader::recv(uint8_t *p, unsigned count)
+PX4IO_Uploader::recv_bytes(uint8_t *p, unsigned count)
{
+ int ret = OK;
while (count--) {
- int ret = recv(*p++, 5000);
+ ret = recv_byte_with_timeout(p++, 5000);
if (ret != OK)
- return ret;
+ break;
}
-
- return OK;
+ return ret;
}
void
@@ -292,10 +290,10 @@ PX4IO_Uploader::drain()
int ret;
do {
- // the small recv timeout here is to allow for fast
+ // the small recv_bytes timeout here is to allow for fast
// drain when rebooting the io board for a forced
// update of the fw without using the safety switch
- ret = recv(c, 40);
+ ret = recv_byte_with_timeout(&c, 40);
#ifdef UDEBUG
if (ret == OK) {
@@ -313,21 +311,19 @@ PX4IO_Uploader::send(uint8_t c)
#endif
if (write(_io_fd, &c, 1) != 1)
return -errno;
-
return OK;
}
int
PX4IO_Uploader::send(uint8_t *p, unsigned count)
{
+ int ret;
while (count--) {
- int ret = send(*p++);
-
+ ret = send(*p++);
if (ret != OK)
- return ret;
+ break;
}
-
- return OK;
+ return ret;
}
int
@@ -336,12 +332,12 @@ PX4IO_Uploader::get_sync(unsigned timeout)
uint8_t c[2];
int ret;
- ret = recv(c[0], timeout);
+ ret = recv_byte_with_timeout(c, timeout);
if (ret != OK)
return ret;
- ret = recv(c[1], timeout);
+ ret = recv_byte_with_timeout(c + 1, timeout);
if (ret != OK)
return ret;
@@ -377,7 +373,7 @@ PX4IO_Uploader::get_info(int param, uint32_t &val)
send(param);
send(PROTO_EOC);
- ret = recv((uint8_t *)&val, sizeof(val));
+ ret = recv_bytes((uint8_t *)&val, sizeof(val));
if (ret != OK)
return ret;
@@ -413,11 +409,20 @@ static int read_with_retry(int fd, void *buf, size_t n)
int
PX4IO_Uploader::program(size_t fw_size)
{
- uint8_t file_buf[PROG_MULTI_MAX];
+ uint8_t *file_buf;
ssize_t count;
int ret;
size_t sent = 0;
+ file_buf = new uint8_t[PROG_MULTI_MAX];
+ if (!file_buf) {
+ log("Can't allocate program buffer");
+ return -ENOMEM;
+ }
+
+ ASSERT((fw_size & 3) == 0);
+ ASSERT((PROG_MULTI_MAX & 3) == 0);
+
log("programming %u bytes...", (unsigned)fw_size);
ret = lseek(_fw_fd, 0, SEEK_SET);
@@ -425,8 +430,8 @@ PX4IO_Uploader::program(size_t fw_size)
while (sent < fw_size) {
/* get more bytes to program */
size_t n = fw_size - sent;
- if (n > sizeof(file_buf)) {
- n = sizeof(file_buf);
+ if (n > PROG_MULTI_MAX) {
+ n = PROG_MULTI_MAX;
}
count = read_with_retry(_fw_fd, file_buf, n);
@@ -436,29 +441,26 @@ PX4IO_Uploader::program(size_t fw_size)
(unsigned)sent,
(int)count,
(int)errno);
+ ret = -errno;
+ break;
}
- if (count == 0)
- return OK;
-
sent += count;
- if (count < 0)
- return -errno;
-
- ASSERT((count % 4) == 0);
-
send(PROTO_PROG_MULTI);
send(count);
- send(&file_buf[0], count);
+ send(file_buf, count);
send(PROTO_EOC);
ret = get_sync(1000);
- if (ret != OK)
- return ret;
+ if (ret != OK) {
+ break;
+ }
}
- return OK;
+
+ delete [] file_buf;
+ return ret;
}
int
@@ -512,7 +514,7 @@ PX4IO_Uploader::verify_rev2(size_t fw_size)
for (ssize_t i = 0; i < count; i++) {
uint8_t c;
- ret = recv(c, 5000);
+ ret = recv_byte_with_timeout(&c, 5000);
if (ret != OK) {
log("%d: got %d waiting for bytes", sent + i, ret);
@@ -599,7 +601,7 @@ PX4IO_Uploader::verify_rev3(size_t fw_size_local)
send(PROTO_GET_CRC);
send(PROTO_EOC);
- ret = recv((uint8_t*)(&crc), sizeof(crc));
+ ret = recv_bytes((uint8_t*)(&crc), sizeof(crc));
if (ret != OK) {
log("did not receive CRC checksum");
diff --git a/src/drivers/px4io/uploader.h b/src/drivers/px4io/uploader.h
index 55f63eef9..e17523413 100644
--- a/src/drivers/px4io/uploader.h
+++ b/src/drivers/px4io/uploader.h
@@ -74,20 +74,19 @@ private:
INFO_BOARD_REV = 3, /**< board revision */
INFO_FLASH_SIZE = 4, /**< max firmware size in bytes */
- PROG_MULTI_MAX = 60, /**< protocol max is 255, must be multiple of 4 */
- READ_MULTI_MAX = 60, /**< protocol max is 255, something overflows with >= 64 */
+ PROG_MULTI_MAX = 248, /**< protocol max is 255, must be multiple of 4 */
};
int _io_fd;
int _fw_fd;
- uint32_t bl_rev; /**< bootloader revision */
+ uint32_t bl_rev; /**< bootloader revision */
void log(const char *fmt, ...);
- int recv(uint8_t &c, unsigned timeout);
- int recv(uint8_t *p, unsigned count);
+ int recv_byte_with_timeout(uint8_t *c, unsigned timeout);
+ int recv_bytes(uint8_t *p, unsigned count);
void drain();
int send(uint8_t c);
int send(uint8_t *p, unsigned count);
diff --git a/src/drivers/rgbled/module.mk b/src/drivers/rgbled/module.mk
index 39b53ec9e..c287e35f3 100644
--- a/src/drivers/rgbled/module.mk
+++ b/src/drivers/rgbled/module.mk
@@ -4,3 +4,5 @@
MODULE_COMMAND = rgbled
SRCS = rgbled.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/roboclaw/RoboClaw.cpp b/src/drivers/roboclaw/RoboClaw.cpp
index 280f6c831..eb9453b50 100644
--- a/src/drivers/roboclaw/RoboClaw.cpp
+++ b/src/drivers/roboclaw/RoboClaw.cpp
@@ -182,7 +182,10 @@ float RoboClaw::getMotorPosition(e_motor motor)
return _motor1Position;
} else if (motor == MOTOR_2) {
return _motor2Position;
- }
+ } else {
+ warnx("Unknown motor value passed to RoboClaw::getMotorPosition");
+ return NAN;
+ }
}
float RoboClaw::getMotorSpeed(e_motor motor)
@@ -191,7 +194,10 @@ float RoboClaw::getMotorSpeed(e_motor motor)
return _motor1Speed;
} else if (motor == MOTOR_2) {
return _motor2Speed;
- }
+ } else {
+ warnx("Unknown motor value passed to RoboClaw::getMotorPosition");
+ return NAN;
+ }
}
int RoboClaw::setMotorSpeed(e_motor motor, float value)
diff --git a/src/drivers/roboclaw/module.mk b/src/drivers/roboclaw/module.mk
index 1abecf198..c5e55bdc3 100644
--- a/src/drivers/roboclaw/module.mk
+++ b/src/drivers/roboclaw/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = roboclaw
SRCS = roboclaw_main.cpp \
RoboClaw.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/sf0x/module.mk b/src/drivers/sf0x/module.mk
index dc93a90e7..26e77d1cc 100644
--- a/src/drivers/sf0x/module.mk
+++ b/src/drivers/sf0x/module.mk
@@ -37,4 +37,7 @@
MODULE_COMMAND = sf0x
-SRCS = sf0x.cpp
+SRCS = sf0x.cpp \
+ sf0x_parser.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp
index 9109af14f..fdd524189 100644
--- a/src/drivers/sf0x/sf0x.cpp
+++ b/src/drivers/sf0x/sf0x.cpp
@@ -72,6 +72,8 @@
#include <board_config.h>
+#include "sf0x_parser.h"
+
/* Configuration Constants */
/* oddly, ERROR is not defined for c++ */
@@ -120,6 +122,7 @@ private:
int _fd;
char _linebuf[10];
unsigned _linebuf_index;
+ enum SF0X_PARSE_STATE _parse_state;
hrt_abstime _last_read;
orb_advert_t _range_finder_topic;
@@ -186,6 +189,7 @@ SF0X::SF0X(const char *port) :
_collect_phase(false),
_fd(-1),
_linebuf_index(0),
+ _parse_state(SF0X_PARSE_STATE0_UNSYNC),
_last_read(0),
_range_finder_topic(-1),
_consecutive_fail_count(0),
@@ -200,12 +204,6 @@ SF0X::SF0X(const char *port) :
warnx("FAIL: laser fd");
}
- /* tell it to stop auto-triggering */
- char stop_auto = ' ';
- (void)::write(_fd, &stop_auto, 1);
- usleep(100);
- (void)::write(_fd, &stop_auto, 1);
-
struct termios uart_config;
int termios_state;
@@ -520,22 +518,15 @@ SF0X::collect()
/* clear buffer if last read was too long ago */
uint64_t read_elapsed = hrt_elapsed_time(&_last_read);
- if (read_elapsed > (SF0X_CONVERSION_INTERVAL * 2)) {
- _linebuf_index = 0;
- } else if (_linebuf_index > 0) {
- /* increment to next read position */
- _linebuf_index++;
- }
-
/* the buffer for read chars is buflen minus null termination */
- unsigned readlen = sizeof(_linebuf) - 1;
+ char readbuf[sizeof(_linebuf)];
+ unsigned readlen = sizeof(readbuf) - 1;
/* read from the sensor (uart buffer) */
- ret = ::read(_fd, &_linebuf[_linebuf_index], readlen - _linebuf_index);
+ ret = ::read(_fd, &readbuf[0], readlen);
if (ret < 0) {
- _linebuf[sizeof(_linebuf) - 1] = '\0';
- debug("read err: %d lbi: %d buf: %s", ret, (int)_linebuf_index, _linebuf);
+ debug("read err: %d", ret);
perf_count(_comms_errors);
perf_end(_sample_perf);
@@ -550,83 +541,23 @@ SF0X::collect()
return -EAGAIN;
}
- /* we did increment the index to the next position already, so just add the additional fields */
- _linebuf_index += (ret - 1);
-
_last_read = hrt_absolute_time();
- if (_linebuf_index < 1) {
- /* we need at least the two end bytes to make sense of this string */
- return -EAGAIN;
-
- } else if (_linebuf[_linebuf_index - 1] != '\r' || _linebuf[_linebuf_index] != '\n') {
-
- if (_linebuf_index >= readlen - 1) {
- /* we have a full buffer, but no line ending - abort */
- _linebuf_index = 0;
- perf_count(_comms_errors);
- return -ENOMEM;
- } else {
- /* incomplete read, reschedule ourselves */
- return -EAGAIN;
- }
- }
-
- char *end;
float si_units;
- bool valid;
-
- /* enforce line ending */
- unsigned lend = (_linebuf_index < (sizeof(_linebuf) - 1)) ? _linebuf_index : (sizeof(_linebuf) - 1);
-
- _linebuf[lend] = '\0';
-
- if (_linebuf[0] == '-' && _linebuf[1] == '-' && _linebuf[2] == '.') {
- si_units = -1.0f;
- valid = false;
-
- } else {
-
- /* we need to find a dot in the string, as we're missing the meters part else */
- valid = false;
-
- /* wipe out partially read content from last cycle(s), check for dot */
- for (unsigned i = 0; i < (lend - 2); i++) {
- if (_linebuf[i] == '\n') {
- char buf[sizeof(_linebuf)];
- memcpy(buf, &_linebuf[i+1], (lend + 1) - (i + 1));
- memcpy(_linebuf, buf, (lend + 1) - (i + 1));
- }
-
- if (_linebuf[i] == '.') {
- valid = true;
- }
- }
-
- if (valid) {
- si_units = strtod(_linebuf, &end);
-
- /* we require at least 3 characters for a valid number */
- if (end > _linebuf + 3) {
- valid = true;
- } else {
- si_units = -1.0f;
- valid = false;
- }
+ bool valid = false;
+
+ for (int i = 0; i < ret; i++) {
+ if (OK == sf0x_parser(readbuf[i], _linebuf, &_linebuf_index, &_parse_state, &si_units)) {
+ valid = true;
}
}
- debug("val (float): %8.4f, raw: %s, valid: %s\n", si_units, _linebuf, ((valid) ? "OK" : "NO"));
-
- /* done with this chunk, resetting - even if invalid */
- _linebuf_index = 0;
-
- /* if its invalid, there is no reason to forward the value */
if (!valid) {
- perf_count(_comms_errors);
- return -EINVAL;
+ return -EAGAIN;
}
+ debug("val (float): %8.4f, raw: %s, valid: %s", (double)si_units, _linebuf, ((valid) ? "OK" : "NO"));
+
struct range_finder_report report;
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
@@ -708,12 +639,12 @@ SF0X::cycle()
int collect_ret = collect();
if (collect_ret == -EAGAIN) {
- /* reschedule to grab the missing bits, time to transmit 10 bytes @9600 bps */
+ /* reschedule to grab the missing bits, time to transmit 8 bytes @ 9600 bps */
work_queue(HPWORK,
&_work,
(worker_t)&SF0X::cycle_trampoline,
this,
- USEC2TICK(1100));
+ USEC2TICK(1042 * 8));
return;
}
diff --git a/src/drivers/sf0x/sf0x_parser.cpp b/src/drivers/sf0x/sf0x_parser.cpp
new file mode 100644
index 000000000..8e73b0ad3
--- /dev/null
+++ b/src/drivers/sf0x/sf0x_parser.cpp
@@ -0,0 +1,155 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 sf0x_parser.cpp
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Driver for the Lightware SF0x laser rangefinder series
+ */
+
+#include "sf0x_parser.h"
+#include <string.h>
+#include <stdlib.h>
+
+//#define SF0X_DEBUG
+
+#ifdef SF0X_DEBUG
+#include <stdio.h>
+
+const char *parser_state[] = {
+ "0_UNSYNC",
+ "1_SYNC",
+ "2_GOT_DIGIT0",
+ "3_GOT_DOT",
+ "4_GOT_DIGIT1",
+ "5_GOT_DIGIT2",
+ "6_GOT_CARRIAGE_RETURN"
+};
+#endif
+
+int sf0x_parser(char c, char *parserbuf, unsigned *parserbuf_index, enum SF0X_PARSE_STATE *state, float *dist)
+{
+ int ret = -1;
+ char *end;
+
+ switch (*state) {
+ case SF0X_PARSE_STATE0_UNSYNC:
+ if (c == '\n') {
+ *state = SF0X_PARSE_STATE1_SYNC;
+ (*parserbuf_index) = 0;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE1_SYNC:
+ if (c >= '0' && c <= '9') {
+ *state = SF0X_PARSE_STATE2_GOT_DIGIT0;
+ parserbuf[*parserbuf_index] = c;
+ (*parserbuf_index)++;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE2_GOT_DIGIT0:
+ if (c >= '0' && c <= '9') {
+ *state = SF0X_PARSE_STATE2_GOT_DIGIT0;
+ parserbuf[*parserbuf_index] = c;
+ (*parserbuf_index)++;
+
+ } else if (c == '.') {
+ *state = SF0X_PARSE_STATE3_GOT_DOT;
+ parserbuf[*parserbuf_index] = c;
+ (*parserbuf_index)++;
+
+ } else {
+ *state = SF0X_PARSE_STATE0_UNSYNC;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE3_GOT_DOT:
+ if (c >= '0' && c <= '9') {
+ *state = SF0X_PARSE_STATE4_GOT_DIGIT1;
+ parserbuf[*parserbuf_index] = c;
+ (*parserbuf_index)++;
+
+ } else {
+ *state = SF0X_PARSE_STATE0_UNSYNC;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE4_GOT_DIGIT1:
+ if (c >= '0' && c <= '9') {
+ *state = SF0X_PARSE_STATE5_GOT_DIGIT2;
+ parserbuf[*parserbuf_index] = c;
+ (*parserbuf_index)++;
+
+ } else {
+ *state = SF0X_PARSE_STATE0_UNSYNC;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE5_GOT_DIGIT2:
+ if (c == '\r') {
+ *state = SF0X_PARSE_STATE6_GOT_CARRIAGE_RETURN;
+
+ } else {
+ *state = SF0X_PARSE_STATE0_UNSYNC;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE6_GOT_CARRIAGE_RETURN:
+ if (c == '\n') {
+ parserbuf[*parserbuf_index] = '\0';
+ *dist = strtod(parserbuf, &end);
+ *state = SF0X_PARSE_STATE1_SYNC;
+ *parserbuf_index = 0;
+ ret = 0;
+
+ } else {
+ *state = SF0X_PARSE_STATE0_UNSYNC;
+ }
+
+ break;
+ }
+
+#ifdef SF0X_DEBUG
+ printf("state: SF0X_PARSE_STATE%s\n", parser_state[*state]);
+#endif
+
+ return ret;
+} \ No newline at end of file
diff --git a/src/drivers/sf0x/sf0x_parser.h b/src/drivers/sf0x/sf0x_parser.h
new file mode 100644
index 000000000..20892d50e
--- /dev/null
+++ b/src/drivers/sf0x/sf0x_parser.h
@@ -0,0 +1,51 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 sf0x_parser.cpp
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Declarations of parser for the Lightware SF0x laser rangefinder series
+ */
+
+enum SF0X_PARSE_STATE {
+ SF0X_PARSE_STATE0_UNSYNC = 0,
+ SF0X_PARSE_STATE1_SYNC,
+ SF0X_PARSE_STATE2_GOT_DIGIT0,
+ SF0X_PARSE_STATE3_GOT_DOT,
+ SF0X_PARSE_STATE4_GOT_DIGIT1,
+ SF0X_PARSE_STATE5_GOT_DIGIT2,
+ SF0X_PARSE_STATE6_GOT_CARRIAGE_RETURN
+};
+
+int sf0x_parser(char c, char *parserbuf, unsigned *parserbuf_index, enum SF0X_PARSE_STATE *state, float *dist); \ No newline at end of file
diff --git a/src/drivers/stm32/adc/module.mk b/src/drivers/stm32/adc/module.mk
index 48620feea..38ea490a0 100644
--- a/src/drivers/stm32/adc/module.mk
+++ b/src/drivers/stm32/adc/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = adc
SRCS = adc.cpp
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/stm32/module.mk b/src/drivers/stm32/module.mk
index bb751c7f6..54428e270 100644
--- a/src/drivers/stm32/module.mk
+++ b/src/drivers/stm32/module.mk
@@ -41,3 +41,5 @@ SRCS = drv_hrt.c \
drv_pwm_servo.c
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/stm32/tone_alarm/module.mk b/src/drivers/stm32/tone_alarm/module.mk
index 827cf30b2..25a194ef6 100644
--- a/src/drivers/stm32/tone_alarm/module.mk
+++ b/src/drivers/stm32/tone_alarm/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = tone_alarm
SRCS = tone_alarm.cpp
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index 810f4aacc..8f523b390 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -336,6 +336,8 @@ ToneAlarm::ToneAlarm() :
_default_tunes[TONE_GPS_WARNING_TUNE] = "MFT255L4AAAL1F#"; //gps warning slow
_default_tunes[TONE_ARMING_FAILURE_TUNE] = "MFT255L4<<<BAP";
_default_tunes[TONE_PARACHUTE_RELEASE_TUNE] = "MFT255L16agagagag"; // parachute release
+ _default_tunes[TONE_EKF_WARNING_TUNE] = "MFT255L8ddd#d#eeff"; // ekf warning
+ _default_tunes[TONE_BARO_WARNING_TUNE] = "MFT255L4gf#fed#d"; // baro warning
_tune_names[TONE_STARTUP_TUNE] = "startup"; // startup tune
_tune_names[TONE_ERROR_TUNE] = "error"; // ERROR tone
@@ -348,6 +350,8 @@ ToneAlarm::ToneAlarm() :
_tune_names[TONE_GPS_WARNING_TUNE] = "gps_warning"; // gps warning
_tune_names[TONE_ARMING_FAILURE_TUNE] = "arming_failure"; //fail to arm
_tune_names[TONE_PARACHUTE_RELEASE_TUNE] = "parachute_release"; // parachute release
+ _tune_names[TONE_EKF_WARNING_TUNE] = "ekf_warning"; // ekf warning
+ _tune_names[TONE_BARO_WARNING_TUNE] = "baro_warning"; // baro warning
}
ToneAlarm::~ToneAlarm()