aboutsummaryrefslogtreecommitdiff
path: root/apps/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'apps/drivers')
-rw-r--r--apps/drivers/blinkm/blinkm.cpp3
-rw-r--r--apps/drivers/gps/ubx.cpp24
-rw-r--r--apps/drivers/stm32/drv_hrt.c2
-rw-r--r--apps/drivers/stm32/tone_alarm/tone_alarm.cpp8
4 files changed, 24 insertions, 13 deletions
diff --git a/apps/drivers/blinkm/blinkm.cpp b/apps/drivers/blinkm/blinkm.cpp
index 56265995f..3fabfd9a5 100644
--- a/apps/drivers/blinkm/blinkm.cpp
+++ b/apps/drivers/blinkm/blinkm.cpp
@@ -92,6 +92,7 @@
#include <nuttx/config.h>
+#include <arch/board/board.h>
#include <drivers/device/i2c.h>
#include <sys/types.h>
@@ -841,7 +842,7 @@ int
blinkm_main(int argc, char *argv[])
{
- int i2cdevice = 3;
+ int i2cdevice = PX4_I2C_BUS_EXPANSION;
int blinkmadr = 9;
int x;
diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp
index 74cbc5aaf..c150f5271 100644
--- a/apps/drivers/gps/ubx.cpp
+++ b/apps/drivers/gps/ubx.cpp
@@ -33,7 +33,14 @@
*
****************************************************************************/
-/* @file U-Blox protocol implementation */
+/**
+ * @file ubx.cpp
+ *
+ * U-Blox protocol implementation. Following u-blox 6/7 Receiver Description
+ * including Prototol Specification.
+ *
+ * @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
+ */
#include <unistd.h>
#include <stdio.h>
@@ -113,13 +120,15 @@ UBX::configure(unsigned &baudrate)
cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
send_config_packet(_fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet));
+
+ /* no ACK is expected here, but read the buffer anyway in case we actually get an ACK */
+ receive(UBX_CONFIG_TIMEOUT);
+
if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) {
set_baudrate(_fd, UBX_CFG_PRT_PAYLOAD_BAUDRATE);
baudrate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
}
- /* no ack is ecpected here, keep going configuring */
-
/* send a CFT-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));
@@ -631,16 +640,17 @@ UBX::handle_message()
}
case NAV_VELNED: {
-// printf("GOT NAV_VELNED MESSAGE\n");
if (!_waiting_for_ack) {
+ /* 35.15 NAV-VELNED (0x01 0x12) message (page 181 / 210 of reference manual */
gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer;
_gps_position->vel_m_s = (float)packet->speed * 1e-2f;
- _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f;
- _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f;
- _gps_position->vel_d_m_s = (float)packet->velD * 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();
}
diff --git a/apps/drivers/stm32/drv_hrt.c b/apps/drivers/stm32/drv_hrt.c
index bb67d5e6d..cec0c49ff 100644
--- a/apps/drivers/stm32/drv_hrt.c
+++ b/apps/drivers/stm32/drv_hrt.c
@@ -125,7 +125,7 @@
# define HRT_TIMER_VECTOR STM32_IRQ_TIM8CC
# define HRT_TIMER_CLOCK STM32_APB2_TIM8_CLKIN
# if CONFIG_STM32_TIM8
-# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=6
+# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=8
# endif
#elif HRT_TIMER == 9
# define HRT_TIMER_BASE STM32_TIM9_BASE
diff --git a/apps/drivers/stm32/tone_alarm/tone_alarm.cpp b/apps/drivers/stm32/tone_alarm/tone_alarm.cpp
index baa652d8a..ac5511e60 100644
--- a/apps/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/apps/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -494,7 +494,7 @@ ToneAlarm::init()
return ret;
/* configure the GPIO to the idle state */
- stm32_configgpio(GPIO_TONE_ALARM);
+ stm32_configgpio(GPIO_TONE_ALARM_IDLE);
/* clock/power on our timer */
modifyreg32(STM32_RCC_APB1ENR, 0, TONE_ALARM_CLOCK_ENABLE);
@@ -606,6 +606,8 @@ ToneAlarm::start_note(unsigned note)
rEGR = GTIM_EGR_UG; // force a reload of the period
rCCER |= TONE_CCER; // enable the output
+ // configure the GPIO to enable timer output
+ stm32_configgpio(GPIO_TONE_ALARM);
}
void
@@ -616,10 +618,8 @@ ToneAlarm::stop_note()
/*
* Make sure the GPIO is not driving the speaker.
- *
- * XXX this presumes PX4FMU and the onboard speaker driver FET.
*/
- stm32_gpiowrite(GPIO_TONE_ALARM, 0);
+ stm32_configgpio(GPIO_TONE_ALARM_IDLE);
}
void