aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/drivers/blinkm/blinkm.cpp3
-rw-r--r--apps/drivers/stm32/drv_hrt.c2
-rw-r--r--apps/drivers/stm32/tone_alarm/tone_alarm.cpp8
-rwxr-xr-xnuttx/configs/px4fmu/include/board.h1
4 files changed, 8 insertions, 6 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/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
diff --git a/nuttx/configs/px4fmu/include/board.h b/nuttx/configs/px4fmu/include/board.h
index 8ad56a4c6..0bc0b3021 100755
--- a/nuttx/configs/px4fmu/include/board.h
+++ b/nuttx/configs/px4fmu/include/board.h
@@ -326,6 +326,7 @@
*/
#define TONE_ALARM_TIMER 3 /* timer 3 */
#define TONE_ALARM_CHANNEL 3 /* channel 3 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
/************************************************************************************