This is an automated email from the ASF dual-hosted git repository.

jerpelea pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit edafeccc9f0e0db4da3111a6489e149b8cb667e8
Author: Matias Nitsche <mnits...@dc.uba.ar>
AuthorDate: Fri May 8 11:55:38 2020 -0300

    stm32: make BMP180 initialization part of stm32 board-common logic
---
 boards/.gitignore                                  |   1 +
 boards/arm/stm32/common/Makefile                   |  34 +++++++
 boards/arm/stm32/common/include/stm32_bmp180.h     |  84 ++++++++++++++++
 boards/arm/stm32/common/src/Make.defs              |  27 ++++++
 boards/arm/stm32/common/src/stm32_bmp180.c         | 106 +++++++++++++++++++++
 .../olimex-stm32-e407/src/{Makefile => Make.defs}  |   8 +-
 .../olimex-stm32-e407/src/olimex-stm32-e407.h      |  18 ----
 .../arm/stm32/olimex-stm32-e407/src/stm32_bmp180.c | 106 ---------------------
 .../stm32/olimex-stm32-e407/src/stm32_bringup.c    |   8 +-
 .../stm32f103-minimum/src/{Makefile => Make.defs}  |   8 +-
 .../arm/stm32/stm32f103-minimum/src/stm32_bmp180.c | 103 --------------------
 .../stm32/stm32f103-minimum/src/stm32_bringup.c    |  10 +-
 .../stm32f103-minimum/src/stm32f103_minimum.h      |  13 ---
 .../stm32f4discovery/src/{Makefile => Make.defs}   |   8 +-
 .../arm/stm32/stm32f4discovery/src/stm32_bmp180.c  | 103 --------------------
 .../arm/stm32/stm32f4discovery/src/stm32_bringup.c |  15 ++-
 .../stm32/stm32f4discovery/src/stm32f4discovery.h  |  13 ---
 17 files changed, 291 insertions(+), 374 deletions(-)

diff --git a/boards/.gitignore b/boards/.gitignore
index 4a88090..de8f114 100644
--- a/boards/.gitignore
+++ b/boards/.gitignore
@@ -22,3 +22,4 @@ cscope.out
 /*.adb
 /*.lib
 /*.src
+/*/*/common/board
diff --git a/boards/arm/stm32/common/Makefile b/boards/arm/stm32/common/Makefile
new file mode 100644
index 0000000..c2531d0
--- /dev/null
+++ b/boards/arm/stm32/common/Makefile
@@ -0,0 +1,34 @@
+#############################################################################
+# boards/arm/stm32/common/Makefile
+#
+# Licensed to the Apache Software Foundation (ASF) under one or more
+# contributor license agreements.  See the NOTICE file distributed with
+# this work for additional information regarding copyright ownership.  The
+# ASF licenses this file to you under the Apache License, Version 2.0 (the
+# "License"); you may not use this file except in compliance with the
+# License.  You may obtain a copy of the License at
+#
+#   http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+# License for the specific language governing permissions and limitations
+# under the License.
+#
+#############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+include board$(DELIM)Make.defs
+include src$(DELIM)Make.defs
+
+DEPPATH += --dep-path board
+DEPPATH += --dep-path src
+
+include $(TOPDIR)/boards/Board.mk
+
+ARCHSRCDIR = $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src
+BOARDDIR = $(ARCHSRCDIR)$(DELIM)board
+CFLAGS += $(shell $(INCDIR) $(INCDIROPT) "$(CC)" $(BOARDDIR)$(DELIM)include)
+
diff --git a/boards/arm/stm32/common/include/stm32_bmp180.h 
b/boards/arm/stm32/common/include/stm32_bmp180.h
new file mode 100644
index 0000000..ee41069
--- /dev/null
+++ b/boards/arm/stm32/common/include/stm32_bmp180.h
@@ -0,0 +1,84 @@
+/****************************************************************************
+ * boards/arm/stm32/common/src/stm32_bmp180.h
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+#ifndef __STM32_BMP180_H
+#define __STM32_BMP180_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Inline Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_bmp180_initialize
+ *
+ * Description:
+ *   Initialize and register the BMP180 Pressure Sensor driver.
+ *
+ * Input Parameters:
+ *   devno - The device number, used to build the device path as /dev/pressN
+ *   busno - The I2C bus number
+ *
+ * Returned Value:
+ *   Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int board_bmp180_initialize(int devno, int busno);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif // __STM32_BMP180_H
diff --git a/boards/arm/stm32/common/src/Make.defs 
b/boards/arm/stm32/common/src/Make.defs
new file mode 100644
index 0000000..592055b
--- /dev/null
+++ b/boards/arm/stm32/common/src/Make.defs
@@ -0,0 +1,27 @@
+#############################################################################
+# boards/arm/stm32/common/src/Make.defs
+#
+# Licensed to the Apache Software Foundation (ASF) under one or more
+# contributor license agreements.  See the NOTICE file distributed with
+# this work for additional information regarding copyright ownership.  The
+# ASF licenses this file to you under the Apache License, Version 2.0 (the
+# "License"); you may not use this file except in compliance with the
+# License.  You may obtain a copy of the License at
+#
+#   http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+# License for the specific language governing permissions and limitations
+# under the License.
+#
+#############################################################################
+
+ifeq ($(CONFIG_SENSORS_BMP180),y)
+  CSRCS += stm32_bmp180.c
+endif
+
+DEPPATH += --dep-path src
+VPATH += :src
+CFLAGS += $(shell $(INCDIR) $(INCDIROPT) "$(CC)" 
$(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)src)
diff --git a/boards/arm/stm32/common/src/stm32_bmp180.c 
b/boards/arm/stm32/common/src/stm32_bmp180.c
new file mode 100644
index 0000000..1be621c
--- /dev/null
+++ b/boards/arm/stm32/common/src/stm32_bmp180.c
@@ -0,0 +1,106 @@
+/****************************************************************************
+ * boards/arm/stm32/common/src/stm32_bmp180.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+#include <nuttx/sensors/bmp180.h>
+#include <nuttx/i2c/i2c_master.h>
+#include <stdio.h>
+#include "stm32_i2c.h"
+
+#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BMP180)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_bmp180_initialize
+ *
+ * Description:
+ *   Initialize and register the BMP180 Pressure Sensor driver.
+ *
+ * Input Parameters:
+ *   devno - The device number, used to build the device path as /dev/pressN
+ *   busno - The I2C bus number
+ *
+ * Returned Value:
+ *   Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int board_bmp180_initialize(int devno, int busno)
+{
+  FAR struct i2c_master_s *i2c;
+  char devpath[12];
+  int ret;
+
+  sninfo("Initializing BMP180!\n");
+
+  /* Initialize I2C */
+
+  i2c = stm32_i2cbus_initialize(busno);
+
+  if (!i2c)
+    {
+      return -ENODEV;
+    }
+
+  /* Then register the barometer sensor */
+
+  snprintf(devpath, 12, "/dev/press%d", devno);
+  ret = bmp180_register(devpath, i2c);
+  if (ret < 0)
+    {
+      snerr("ERROR: Error registering BM180\n");
+    }
+
+  return ret;
+}
+
+#endif
diff --git a/boards/arm/stm32/olimex-stm32-e407/src/Makefile 
b/boards/arm/stm32/olimex-stm32-e407/src/Make.defs
similarity index 94%
rename from boards/arm/stm32/olimex-stm32-e407/src/Makefile
rename to boards/arm/stm32/olimex-stm32-e407/src/Make.defs
index b09192a..e6d7c94 100644
--- a/boards/arm/stm32/olimex-stm32-e407/src/Makefile
+++ b/boards/arm/stm32/olimex-stm32-e407/src/Make.defs
@@ -80,10 +80,6 @@ ifeq ($(CONFIG_ARCH_FPU),y)
 CSRCS += stm32_ostest.c
 endif
 
-ifeq ($(CONFIG_SENSORS_BMP180),y)
-CSRCS += stm32_bmp180.c
-endif
-
 ifeq ($(CONFIG_DAC),y)
 CSRCS += stm32_dac.c
 endif
@@ -100,4 +96,6 @@ ifeq ($(CONFIG_IEEE802154_MRF24J40),y)
 CSRCS += stm32_mrf24j40.c
 endif
 
-include $(TOPDIR)/boards/Board.mk
+DEPPATH += --dep-path board
+VPATH += :board
+CFLAGS += $(shell $(INCDIR) $(INCDIROPT) "$(CC)" 
$(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)board)
diff --git a/boards/arm/stm32/olimex-stm32-e407/src/olimex-stm32-e407.h 
b/boards/arm/stm32/olimex-stm32-e407/src/olimex-stm32-e407.h
index 2148b8f..d6b84e2 100644
--- a/boards/arm/stm32/olimex-stm32-e407/src/olimex-stm32-e407.h
+++ b/boards/arm/stm32/olimex-stm32-e407/src/olimex-stm32-e407.h
@@ -290,24 +290,6 @@ int stm32_can_setup(void);
 #endif
 
 /****************************************************************************
- * Name: stm32_bmp180initialize
- *
- * Description:
- *   Initialize and register the BMP180 Pressure Sensor driver.
- *
- * Input parameters:
- *   devpath - The full path to the driver to register. E.g., "/dev/press0"
- *
- * Returned Value:
- *   Zero (OK) on success; a negated errno value on failure.
- *
- ****************************************************************************/
-
-#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BMP180)
-int stm32_bmp180initialize(FAR const char *devpath);
-#endif
-
-/****************************************************************************
  * Name: stm32_dac_setup
  *
  * Description:
diff --git a/boards/arm/stm32/olimex-stm32-e407/src/stm32_bmp180.c 
b/boards/arm/stm32/olimex-stm32-e407/src/stm32_bmp180.c
deleted file mode 100644
index 6bdaa70..0000000
--- a/boards/arm/stm32/olimex-stm32-e407/src/stm32_bmp180.c
+++ /dev/null
@@ -1,106 +0,0 @@
-/****************************************************************************
- * boards/arm/stm32/olimex-stm32-e407/src/stm32_bmp180.c
- *
- *   Copyright (C) 2019 Acutronics Robotics. All rights reserved.
- *   Author: Acutronics Robotics (Juan Flores) <j...@erlerobotics.com>
- *   Base on the implementation of: Alan Carvalho de Assis <acas...@gmail.com>
- *
- * 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 NuttX 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/spi/spi.h>
-#include <nuttx/sensors/bmp180.h>
-
-#include "stm32.h"
-#include "stm32_i2c.h"
-#include "olimex-stm32-e407.h"
-
-#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BMP180)
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define BMP180_I2C_PORTNO 1   /* On I2C1 */
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: stm32_bmp180initialize
- *
- * Description:
- *   Initialize and register the BMP180 Pressure Sensor driver.
- *
- * Input parameters:
- *   devpath - The full path to the driver to register. E.g., "/dev/press0"
- *
- * Returned Value:
- *   Zero (OK) on success; a negated errno value on failure.
- *
- ****************************************************************************/
-
-int stm32_bmp180initialize(FAR const char *devpath)
-{
-  FAR struct i2c_master_s *i2c;
-  int ret;
-
-  sninfo("Initializing BMP180!\n");
-
-  /* Initialize I2C */
-
-  i2c = stm32_i2cbus_initialize(BMP180_I2C_PORTNO);
-
-  if (!i2c)
-    {
-      return -ENODEV;
-    }
-
-  /* Then register the barometer sensor */
-
-  ret = bmp180_register(devpath, i2c);
-  if (ret < 0)
-    {
-      snerr("ERROR: Error registering BMP180\n");
-    }
-
-  return ret;
-}
-
-#endif /* CONFIG_I2C && CONFIG_SENSORS_BMP180 && CONFIG_STM32_I2C1 */
diff --git a/boards/arm/stm32/olimex-stm32-e407/src/stm32_bringup.c 
b/boards/arm/stm32/olimex-stm32-e407/src/stm32_bringup.c
index 99295d3..8dde27f 100644
--- a/boards/arm/stm32/olimex-stm32-e407/src/stm32_bringup.c
+++ b/boards/arm/stm32/olimex-stm32-e407/src/stm32_bringup.c
@@ -57,6 +57,12 @@
 #include "stm32.h"
 #include "olimex-stm32-e407.h"
 
+/* The following are includes from board-common logic */
+
+#ifdef CONFIG_SENSORS_BMP180
+#include "stm32_bmp180.h"
+#endif
+
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
@@ -221,7 +227,7 @@ int stm32_bringup(void)
 #ifdef CONFIG_SENSORS_BMP180
   /* Initialize the BMP180 pressure sensor. */
 
-  ret = stm32_bmp180initialize("/dev/press0");
+  ret = board_bmp180_initialize(0, 1);
   if (ret < 0)
     {
       syslog(LOG_ERR, "Failed to initialize BMP180, error %d\n", ret);
diff --git a/boards/arm/stm32/stm32f103-minimum/src/Makefile 
b/boards/arm/stm32/stm32f103-minimum/src/Make.defs
similarity index 95%
rename from boards/arm/stm32/stm32f103-minimum/src/Makefile
rename to boards/arm/stm32/stm32f103-minimum/src/Make.defs
index 515ca99..c4bb6df 100644
--- a/boards/arm/stm32/stm32f103-minimum/src/Makefile
+++ b/boards/arm/stm32/stm32f103-minimum/src/Make.defs
@@ -77,10 +77,6 @@ ifeq ($(CONFIG_LEDS_APA102),y)
   CSRCS += stm32_apa102.c
 endif
 
-ifeq ($(CONFIG_SENSORS_BMP180),y)
-  CSRCS += stm32_bmp180.c
-endif
-
 ifeq ($(CONFIG_LM75_I2C),y)
   CSRCS += stm32_lm75.c
 endif
@@ -167,4 +163,6 @@ ifeq ($(CONFIG_USBMSC),y)
 CSRCS += stm32_usbmsc.c
 endif
 
-include $(TOPDIR)/boards/Board.mk
+DEPPATH += --dep-path board
+VPATH += :board
+CFLAGS += $(shell $(INCDIR) $(INCDIROPT) "$(CC)" 
$(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)board)
diff --git a/boards/arm/stm32/stm32f103-minimum/src/stm32_bmp180.c 
b/boards/arm/stm32/stm32f103-minimum/src/stm32_bmp180.c
deleted file mode 100644
index 167d8d1..0000000
--- a/boards/arm/stm32/stm32f103-minimum/src/stm32_bmp180.c
+++ /dev/null
@@ -1,103 +0,0 @@
-/****************************************************************************
- * boards/arm/stm32/stm32f103-minimum/src/stm32_bmp180.c
- *
- *   Copyright (C) 2018 Alan Carvalho de Assis. All rights reserved.
- *   Author: Alan Carvalho de Assis <acas...@gmail.com>
- *
- * 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 NuttX 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/spi/spi.h>
-#include <nuttx/sensors/bmp180.h>
-
-#include "stm32.h"
-#include "stm32_i2c.h"
-#include "stm32f103_minimum.h"
-
-#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BMP180)
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: stm32_bmp180initialize
- *
- * Description:
- *   Initialize and register the MPL115A Pressure Sensor driver.
- *
- * Input parameters:
- *   devpath - The full path to the driver to register. E.g., "/dev/press0"
- *
- * Returned Value:
- *   Zero (OK) on success; a negated errno value on failure.
- *
- ****************************************************************************/
-
-int stm32_bmp180initialize(FAR const char *devpath)
-{
-  FAR struct i2c_master_s *i2c;
-  int ret;
-
-  sninfo("Initializing BMP180!\n");
-
-  /* Initialize I2C */
-
-  i2c = stm32_i2cbus_initialize(BMP180_I2C_PORTNO);
-
-  if (!i2c)
-    {
-      return -ENODEV;
-    }
-
-  /* Then register the barometer sensor */
-
-  ret = bmp180_register(devpath, i2c);
-  if (ret < 0)
-    {
-      snerr("ERROR: Error registering BM180\n");
-    }
-
-  return ret;
-}
-
-#endif /* CONFIG_I2C && CONFIG_SENSORS_MPL115A && CONFIG_STM32_I2C1 */
diff --git a/boards/arm/stm32/stm32f103-minimum/src/stm32_bringup.c 
b/boards/arm/stm32/stm32f103-minimum/src/stm32_bringup.c
index ea66125..a3ee67d 100644
--- a/boards/arm/stm32/stm32f103-minimum/src/stm32_bringup.c
+++ b/boards/arm/stm32/stm32f103-minimum/src/stm32_bringup.c
@@ -83,6 +83,12 @@
 #  include "stm32_rtc.h"
 #endif
 
+/* The following are includes from board-common logic */
+
+#ifdef CONFIG_SENSORS_BMP180
+#include "stm32_bmp180.h"
+#endif
+
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
@@ -191,7 +197,9 @@ int stm32_bringup(void)
 #endif
 
 #ifdef CONFIG_SENSORS_BMP180
-  ret = stm32_bmp180initialize("/dev/press0");
+  /* Initialize the BMP180 pressure sensor. */
+
+  ret = board_bmp180_initialize(0, 1);
   if (ret < 0)
     {
       syslog(LOG_ERR, "Failed to initialize BMP180, error %d\n", ret);
diff --git a/boards/arm/stm32/stm32f103-minimum/src/stm32f103_minimum.h 
b/boards/arm/stm32/stm32f103-minimum/src/stm32f103_minimum.h
index 87a483e..2490703 100644
--- a/boards/arm/stm32/stm32f103-minimum/src/stm32f103_minimum.h
+++ b/boards/arm/stm32/stm32f103-minimum/src/stm32f103_minimum.h
@@ -294,19 +294,6 @@ int stm32_apds9960initialize(FAR const char *devpath);
 #endif
 
 /****************************************************************************
- * Name: stm32_bmp180initialize
- *
- * Description:
- *   Called to configure an I2C and to register BMP180 for the stm32f4discovery
- *   board.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_SENSORS_BMP180
-int stm32_bmp180initialize(FAR const char *devpath);
-#endif
-
-/****************************************************************************
  * Name: stm32_spidev_initialize
  *
  * Description:
diff --git a/boards/arm/stm32/stm32f4discovery/src/Makefile 
b/boards/arm/stm32/stm32f4discovery/src/Make.defs
similarity index 96%
rename from boards/arm/stm32/stm32f4discovery/src/Makefile
rename to boards/arm/stm32/stm32f4discovery/src/Make.defs
index 8684021..eefa4a4 100644
--- a/boards/arm/stm32/stm32f4discovery/src/Makefile
+++ b/boards/arm/stm32/stm32f4discovery/src/Make.defs
@@ -69,10 +69,6 @@ ifeq ($(CONFIG_SENSORS_BH1750FVI),y)
 CSRCS += stm32_bh1750fvi.c
 endif
 
-ifeq ($(CONFIG_SENSORS_BMP180),y)
-CSRCS += stm32_bmp180.c
-endif
-
 ifeq ($(CONFIG_SENSORS_MLX90614),y)
 CSRCS += stm32_mlx90614.c
 endif
@@ -232,4 +228,6 @@ ifeq ($(CONFIG_WL_GS2200M),y)
 CSRCS += stm32_gs2200m.c
 endif
 
-include $(TOPDIR)/boards/Board.mk
+DEPPATH += --dep-path board
+VPATH += :board
+CFLAGS += $(shell $(INCDIR) $(INCDIROPT) "$(CC)" 
$(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)board)
diff --git a/boards/arm/stm32/stm32f4discovery/src/stm32_bmp180.c 
b/boards/arm/stm32/stm32f4discovery/src/stm32_bmp180.c
deleted file mode 100644
index 9ca9604..0000000
--- a/boards/arm/stm32/stm32f4discovery/src/stm32_bmp180.c
+++ /dev/null
@@ -1,103 +0,0 @@
-/****************************************************************************
- * boards/arm/stm32/stm32f4discovery/src/stm32_bmp180.c
- *
- *   Copyright (C) 2015 Alan Carvalho de Assis. All rights reserved.
- *   Author: Alan Carvalho de Assis <acas...@gmail.com>
- *
- * 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 NuttX 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/spi/spi.h>
-#include <nuttx/sensors/bmp180.h>
-
-#include "stm32.h"
-#include "stm32_i2c.h"
-#include "stm32f4discovery.h"
-
-#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BMP180)
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: stm32_bmp180initialize
- *
- * Description:
- *   Initialize and register the MPL115A Pressure Sensor driver.
- *
- * Input Parameters:
- *   devpath - The full path to the driver to register. E.g., "/dev/press0"
- *
- * Returned Value:
- *   Zero (OK) on success; a negated errno value on failure.
- *
- ****************************************************************************/
-
-int stm32_bmp180initialize(FAR const char *devpath)
-{
-  FAR struct i2c_master_s *i2c;
-  int ret;
-
-  sninfo("Initializing BMP180!\n");
-
-  /* Initialize I2C */
-
-  i2c = stm32_i2cbus_initialize(BMP180_I2C_PORTNO);
-
-  if (!i2c)
-    {
-      return -ENODEV;
-    }
-
-  /* Then register the barometer sensor */
-
-  ret = bmp180_register(devpath, i2c);
-  if (ret < 0)
-    {
-      snerr("ERROR: Error registering BM180\n");
-    }
-
-  return ret;
-}
-
-#endif /* CONFIG_I2C && CONFIG_STM32_I2C1 */
diff --git a/boards/arm/stm32/stm32f4discovery/src/stm32_bringup.c 
b/boards/arm/stm32/stm32f4discovery/src/stm32_bringup.c
index dc29faf..aa4b324 100644
--- a/boards/arm/stm32/stm32f4discovery/src/stm32_bringup.c
+++ b/boards/arm/stm32/stm32f4discovery/src/stm32_bringup.c
@@ -80,6 +80,12 @@
 #  include "stm32_rtc.h"
 #endif
 
+/* The following are includes from board-common logic */
+
+#ifdef CONFIG_SENSORS_BMP180
+#include "stm32_bmp180.h"
+#endif
+
 /****************************************************************************
  * Public Functions
  ****************************************************************************/
@@ -163,7 +169,14 @@ int stm32_bringup(void)
 #endif
 
 #ifdef CONFIG_SENSORS_BMP180
-  stm32_bmp180initialize("/dev/press0");
+  /* Initialize the BMP180 pressure sensor. */
+
+  ret = board_bmp180_initialize(0, 1);
+  if (ret < 0)
+    {
+      syslog(LOG_ERR, "Failed to initialize BMP180, error %d\n", ret);
+      return ret;
+    }
 #endif
 
 #ifdef CONFIG_SENSORS_BH1750FVI
diff --git a/boards/arm/stm32/stm32f4discovery/src/stm32f4discovery.h 
b/boards/arm/stm32/stm32f4discovery/src/stm32f4discovery.h
index ba30fc0..6204e62 100644
--- a/boards/arm/stm32/stm32f4discovery/src/stm32f4discovery.h
+++ b/boards/arm/stm32/stm32f4discovery/src/stm32f4discovery.h
@@ -471,19 +471,6 @@ int stm32_bh1750initialize(FAR const char *devpath);
 #endif
 
 /****************************************************************************
- * Name: stm32_bmp180initialize
- *
- * Description:
- *   Called to configure an I2C and to register BMP180 for the
- *   stm32f4discovery board.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_SENSORS_BMP180
-int stm32_bmp180initialize(FAR const char *devpath);
-#endif
-
-/****************************************************************************
  * Name: stm32_lis3dshinitialize
  *
  * Description:

Reply via email to