aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-12-28 21:09:58 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-12-28 21:09:58 +0100
commit6b2f3f9b07cdf01ad6b11c8bab9723bfbac97c92 (patch)
tree9503a0a82e1f7ca09dbfac9f4cc81f695e28637b /src/drivers
parent784888e1757661a267978c25a00d03c1a348db21 (diff)
parentc29972424f6d7b99633c8497f0c25ab7cda4d2ca (diff)
downloadpx4-firmware-6b2f3f9b07cdf01ad6b11c8bab9723bfbac97c92.tar.gz
px4-firmware-6b2f3f9b07cdf01ad6b11c8bab9723bfbac97c92.tar.bz2
px4-firmware-6b2f3f9b07cdf01ad6b11c8bab9723bfbac97c92.zip
Merged master into nuttx_bringup / nuttx_noappconfig
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c2
-rw-r--r--src/drivers/boards/aerocore/aerocore_led.c3
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h2
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_spi.c15
-rw-r--r--src/drivers/frsky_telemetry/frsky_telemetry.c2
-rw-r--r--src/drivers/hott/comms.h2
-rw-r--r--src/drivers/hott/hott_sensors/hott_sensors.cpp2
-rw-r--r--src/drivers/hott/hott_sensors/module.mk4
-rw-r--r--src/drivers/hott/hott_telemetry/hott_telemetry.cpp2
-rw-r--r--src/drivers/hott/hott_telemetry/module.mk4
-rw-r--r--src/drivers/hott/messages.h18
-rw-r--r--src/drivers/hott/module.mk41
-rw-r--r--src/drivers/px4flow/module.mk2
-rw-r--r--src/drivers/px4flow/px4flow.cpp2
-rw-r--r--src/drivers/roboclaw/roboclaw_main.cpp2
-rw-r--r--src/drivers/sf0x/sf0x.cpp4
-rw-r--r--src/drivers/stm32/drv_hrt.c8
-rw-r--r--src/drivers/trone/trone.cpp2
18 files changed, 89 insertions, 28 deletions
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index 9d2c1441d..7f1b21a95 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -121,7 +121,7 @@ int ardrone_interface_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 15,
1100,
ardrone_interface_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/drivers/boards/aerocore/aerocore_led.c b/src/drivers/boards/aerocore/aerocore_led.c
index e40d1730c..94a716029 100644
--- a/src/drivers/boards/aerocore/aerocore_led.c
+++ b/src/drivers/boards/aerocore/aerocore_led.c
@@ -45,6 +45,7 @@
#include "board_config.h"
#include <arch/board/board.h>
+#include <systemlib/err.h>
/*
* Ideally we'd be able to get these from up_internal.h,
@@ -54,7 +55,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/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index ee365e47c..2fd8bc724 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -105,6 +105,7 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
+#define GPIO_SPI_CS_HMC (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN1)
#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)
@@ -119,6 +120,7 @@ __BEGIN_DECLS
#define PX4_SPIDEV_ACCEL_MAG 2
#define PX4_SPIDEV_BARO 3
#define PX4_SPIDEV_MPU 4
+#define PX4_SPIDEV_HMC 5
/* External bus */
#define PX4_SPIDEV_EXT0 1
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
index 297ff406e..b98cd999b 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
@@ -73,6 +73,7 @@ __EXPORT void weak_function stm32_spiinitialize(void)
stm32_configgpio(GPIO_SPI_CS_GYRO);
stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
stm32_configgpio(GPIO_SPI_CS_BARO);
+ stm32_configgpio(GPIO_SPI_CS_HMC);
stm32_configgpio(GPIO_SPI_CS_MPU);
/* De-activate all peripherals,
@@ -82,6 +83,7 @@ __EXPORT void weak_function stm32_spiinitialize(void)
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
stm32_configgpio(GPIO_EXTI_GYRO_DRDY);
@@ -117,6 +119,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
@@ -125,6 +128,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
@@ -133,6 +137,16 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
+ break;
+
+ case PX4_SPIDEV_HMC:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, !selected);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
@@ -141,6 +155,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected);
break;
diff --git a/src/drivers/frsky_telemetry/frsky_telemetry.c b/src/drivers/frsky_telemetry/frsky_telemetry.c
index bccdf1190..5035600ef 100644
--- a/src/drivers/frsky_telemetry/frsky_telemetry.c
+++ b/src/drivers/frsky_telemetry/frsky_telemetry.c
@@ -221,7 +221,7 @@ int frsky_telemetry_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2000,
frsky_telemetry_thread_main,
- (const char **)argv);
+ (char * const *)argv);
while (!thread_running) {
usleep(200);
diff --git a/src/drivers/hott/comms.h b/src/drivers/hott/comms.h
index f5608122f..0a586a8fd 100644
--- a/src/drivers/hott/comms.h
+++ b/src/drivers/hott/comms.h
@@ -41,6 +41,6 @@
#ifndef COMMS_H_
#define COMMS_H
-int open_uart(const char *device);
+__EXPORT int open_uart(const char *device);
#endif /* COMMS_H_ */
diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp
index 8ab9d8d55..4b8e0c0b0 100644
--- a/src/drivers/hott/hott_sensors/hott_sensors.cpp
+++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp
@@ -214,7 +214,7 @@ hott_sensors_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
1024,
hott_sensors_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/drivers/hott/hott_sensors/module.mk b/src/drivers/hott/hott_sensors/module.mk
index 47aea6caf..25a6f0ac0 100644
--- a/src/drivers/hott/hott_sensors/module.mk
+++ b/src/drivers/hott/hott_sensors/module.mk
@@ -37,8 +37,6 @@
MODULE_COMMAND = hott_sensors
-SRCS = hott_sensors.cpp \
- ../messages.cpp \
- ../comms.cpp
+SRCS = hott_sensors.cpp
MAXOPTIMIZATION = -Os
diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
index edbb14172..17a24d104 100644
--- a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
+++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp
@@ -240,7 +240,7 @@ hott_telemetry_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2048,
hott_telemetry_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/drivers/hott/hott_telemetry/module.mk b/src/drivers/hott/hott_telemetry/module.mk
index cd7bdbc85..9de47b356 100644
--- a/src/drivers/hott/hott_telemetry/module.mk
+++ b/src/drivers/hott/hott_telemetry/module.mk
@@ -37,8 +37,6 @@
MODULE_COMMAND = hott_telemetry
-SRCS = hott_telemetry.cpp \
- ../messages.cpp \
- ../comms.cpp
+SRCS = hott_telemetry.cpp
MAXOPTIMIZATION = -Os
diff --git a/src/drivers/hott/messages.h b/src/drivers/hott/messages.h
index 224f8fc56..a116a50dd 100644
--- a/src/drivers/hott/messages.h
+++ b/src/drivers/hott/messages.h
@@ -235,15 +235,15 @@ struct gps_module_msg {
// The maximum size of a message.
#define MAX_MESSAGE_BUFFER_SIZE 45
-void init_sub_messages(void);
-void init_pub_messages(void);
-void build_gam_request(uint8_t *buffer, size_t *size);
-void publish_gam_message(const uint8_t *buffer);
-void build_eam_response(uint8_t *buffer, size_t *size);
-void build_gam_response(uint8_t *buffer, size_t *size);
-void build_gps_response(uint8_t *buffer, size_t *size);
-float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
-void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec);
+__EXPORT void init_sub_messages(void);
+__EXPORT void init_pub_messages(void);
+__EXPORT void build_gam_request(uint8_t *buffer, size_t *size);
+__EXPORT void publish_gam_message(const uint8_t *buffer);
+__EXPORT void build_eam_response(uint8_t *buffer, size_t *size);
+__EXPORT void build_gam_response(uint8_t *buffer, size_t *size);
+__EXPORT void build_gps_response(uint8_t *buffer, size_t *size);
+__EXPORT float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
+__EXPORT void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec);
#endif /* MESSAGES_H_ */
diff --git a/src/drivers/hott/module.mk b/src/drivers/hott/module.mk
new file mode 100644
index 000000000..31a66d491
--- /dev/null
+++ b/src/drivers/hott/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2012, 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.
+#
+############################################################################
+
+#
+# Graupner HoTT Sensors messages.
+#
+
+SRCS = messages.cpp \
+ comms.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/px4flow/module.mk b/src/drivers/px4flow/module.mk
index 460bec7b9..ecd3e804a 100644
--- a/src/drivers/px4flow/module.mk
+++ b/src/drivers/px4flow/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = px4flow
SRCS = px4flow.cpp
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wno-attributes
diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp
index 09ec4bf96..62308fc65 100644
--- a/src/drivers/px4flow/px4flow.cpp
+++ b/src/drivers/px4flow/px4flow.cpp
@@ -106,7 +106,7 @@ struct i2c_frame {
};
struct i2c_frame f;
-typedef struct i2c_integral_frame {
+struct i2c_integral_frame {
uint16_t frame_count_since_last_readout;
int16_t pixel_flow_x_integral;
int16_t pixel_flow_y_integral;
diff --git a/src/drivers/roboclaw/roboclaw_main.cpp b/src/drivers/roboclaw/roboclaw_main.cpp
index 44ed03254..83086fd7c 100644
--- a/src/drivers/roboclaw/roboclaw_main.cpp
+++ b/src/drivers/roboclaw/roboclaw_main.cpp
@@ -109,7 +109,7 @@ int roboclaw_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 10,
2048,
roboclaw_thread_main,
- (const char **)argv);
+ (char * const *)argv);
exit(0);
} else if (!strcmp(argv[1], "test")) {
diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp
index 4301750f0..8e62e0d4b 100644
--- a/src/drivers/sf0x/sf0x.cpp
+++ b/src/drivers/sf0x/sf0x.cpp
@@ -90,7 +90,9 @@ static const int ERROR = -1;
#define SF0X_TAKE_RANGE_REG 'd'
#define SF02F_MIN_DISTANCE 0.0f
#define SF02F_MAX_DISTANCE 40.0f
-#define SF0X_DEFAULT_PORT "/dev/ttyS2"
+
+// designated SERIAL4/5 on Pixhawk
+#define SF0X_DEFAULT_PORT "/dev/ttyS6"
class SF0X : public device::CDev
{
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index 281f918d7..603c2eb9d 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -253,9 +253,11 @@ static uint16_t latency_baseline;
static uint16_t latency_actual;
/* latency histogram */
-#define LATENCY_BUCKET_COUNT 8
-static const uint16_t latency_buckets[LATENCY_BUCKET_COUNT] = { 1, 2, 5, 10, 20, 50, 100, 1000 };
-static uint32_t latency_counters[LATENCY_BUCKET_COUNT + 1];
+#define LATENCY_BUCKET_COUNT 8
+__EXPORT const uint16_t latency_bucket_count = LATENCY_BUCKET_COUNT;
+__EXPORT const uint16_t latency_buckets[LATENCY_BUCKET_COUNT] = { 1, 2, 5, 10, 20, 50, 100, 1000 };
+__EXPORT uint32_t latency_counters[LATENCY_BUCKET_COUNT + 1];
+
/* timer-specific functions */
static void hrt_tim_init(void);
diff --git a/src/drivers/trone/trone.cpp b/src/drivers/trone/trone.cpp
index 83b5c987e..cf3546669 100644
--- a/src/drivers/trone/trone.cpp
+++ b/src/drivers/trone/trone.cpp
@@ -206,7 +206,7 @@ static const uint8_t crc_table[] = {
0xfa, 0xfd, 0xf4, 0xf3
};
-uint8_t crc8(uint8_t *p, uint8_t len){
+static uint8_t crc8(uint8_t *p, uint8_t len) {
uint16_t i;
uint16_t crc = 0x0;