aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/drivers/hmc5883/hmc5883.cpp11
-rw-r--r--apps/drivers/ms5611/ms5611.cpp6
-rw-r--r--apps/drivers/stm32/tone_alarm/tone_alarm.cpp2
-rwxr-xr-xnuttx/configs/px4fmu/include/board.h44
4 files changed, 14 insertions, 49 deletions
diff --git a/apps/drivers/hmc5883/hmc5883.cpp b/apps/drivers/hmc5883/hmc5883.cpp
index 7943012cc..f9079c3ff 100644
--- a/apps/drivers/hmc5883/hmc5883.cpp
+++ b/apps/drivers/hmc5883/hmc5883.cpp
@@ -58,17 +58,21 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
-#include <drivers/drv_hrt.h>
+#include <arch/board/board.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
#include <drivers/drv_mag.h>
+#include <drivers/drv_hrt.h>
/*
* HMC5883 internal constants and data structures.
*/
+#define HMC5883L_BUS PX4_I2C_BUS_ONBOARD
+#define HMC5883L_ADDRESS PX4_I2C_OBDEV_HMC5883
+
/* Max measurement rate is 160Hz */
#define HMC5883_CONVERSION_INTERVAL (1000000 / 160) /* microseconds */
@@ -86,8 +90,6 @@
#define ADDR_ID_B 0x0b
#define ADDR_ID_C 0x0c
-#define HMC5883L_ADDRESS 0x1E
-
/* modes not changeable outside of driver */
#define HMC5883L_MODE_NORMAL (0 << 0) /* default */
#define HMC5883L_MODE_POSITIVE_BIAS (1 << 0) /* positive bias */
@@ -1100,8 +1102,7 @@ start()
errx(1, "already started");
/* create the driver */
- /* XXX HORRIBLE hack - the bus number should not come from here */
- g_dev = new HMC5883(2);
+ g_dev = new HMC5883(HMC5883L_BUS);
if (g_dev == nullptr)
goto fail;
diff --git a/apps/drivers/ms5611/ms5611.cpp b/apps/drivers/ms5611/ms5611.cpp
index 699cd36d2..211c07728 100644
--- a/apps/drivers/ms5611/ms5611.cpp
+++ b/apps/drivers/ms5611/ms5611.cpp
@@ -240,7 +240,8 @@ private:
#define MS5611_CONVERSION_INTERVAL 10000 /* microseconds */
#define MS5611_MEASUREMENT_RATIO 3 /* pressure measurements per temperature measurement */
-#define MS5611_ADDRESS_1 0x76 /* address select pins pulled high (PX4FMU series v1.6+) */
+#define MS5611_BUS PX4_I2C_BUS_ONBOARD
+#define MS5611_ADDRESS_1 PX4_I2C_OBDEV_MS5611 /* address select pins pulled high (PX4FMU series v1.6+) */
#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
@@ -937,8 +938,7 @@ start()
errx(1, "already started");
/* create the driver */
- /* XXX HORRIBLE hack - the bus number should not come from here */
- g_dev = new MS5611(2);
+ g_dev = new MS5611(MS5611_BUS);
if (g_dev == nullptr)
goto fail;
diff --git a/apps/drivers/stm32/tone_alarm/tone_alarm.cpp b/apps/drivers/stm32/tone_alarm/tone_alarm.cpp
index 03cf3ee5d..cb1d567d1 100644
--- a/apps/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/apps/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -84,7 +84,7 @@
#include <systemlib/err.h>
#ifndef CONFIG_HRT_TIMER
-# error CONFIG_TONE_ALARM requires CONFIG_HRT_TIMER
+# error This driver requires CONFIG_HRT_TIMER
#endif
/* Tone alarm configuration */
diff --git a/nuttx/configs/px4fmu/include/board.h b/nuttx/configs/px4fmu/include/board.h
index a7dae6552..3f0f26ba1 100755
--- a/nuttx/configs/px4fmu/include/board.h
+++ b/nuttx/configs/px4fmu/include/board.h
@@ -45,9 +45,6 @@
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
-//#include "stm32_rcc.h"
-//#include "stm32_sdio.h"
-//#include "stm32_internal.h"
/************************************************************************************
* Definitions
@@ -298,7 +295,7 @@
* Note that these are unshifted addresses.
*/
#define PX4_I2C_OBDEV_HMC5883 0x1e
-#define PX4_I2C_OBDEV_MS5611 NOTDEFINED
+#define PX4_I2C_OBDEV_MS5611 0x76
#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
#define PX4_I2C_OBDEV_PX4IO_BL 0x18
@@ -327,11 +324,9 @@
/*
* Tone alarm output
*/
-#ifdef CONFIG_TONE_ALARM
-# define TONE_ALARM_TIMER 3 /* timer 3 */
-# define TONE_ALARM_CHANNEL 3 /* channel 3 */
-# define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
-#endif
+#define TONE_ALARM_TIMER 3 /* timer 3 */
+#define TONE_ALARM_CHANNEL 3 /* channel 3 */
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
/************************************************************************************
* Public Data
@@ -362,37 +357,6 @@ extern "C" {
EXTERN void stm32_boardinitialize(void);
-/************************************************************************************
- * Button support.
- *
- * Description:
- * up_buttoninit() must be called to initialize button resources. After
- * that, up_buttons() may be called to collect the current state of all
- * buttons or up_irqbutton() may be called to register button interrupt
- * handlers.
- *
- * After up_buttoninit() has been called, up_buttons() may be called to
- * collect the state of all buttons. up_buttons() returns an 8-bit bit set
- * with each bit associated with a button. See the BUTTON_*_BIT
- * definitions in board.h for the meaning of each bit.
- *
- * up_irqbutton() may be called to register an interrupt handler that will
- * be called when a button is depressed or released. The ID value is a
- * button enumeration value that uniquely identifies a button resource. See the
- * BUTTON_* definitions in board.h for the meaning of enumeration
- * value. The previous interrupt handler address is returned (so that it may
- * restored, if so desired).
- *
- ************************************************************************************/
-
-#ifdef CONFIG_ARCH_BUTTONS
-EXTERN void up_buttoninit(void);
-EXTERN uint8_t up_buttons(void);
-#ifdef CONFIG_ARCH_IRQBUTTONS
-EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
-#endif
-#endif
-
#undef EXTERN
#if defined(__cplusplus)
}