aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-12-26 20:25:31 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-12-26 20:25:31 +0100
commite952324fbf08405fe555be7169ef0a53a12487f8 (patch)
treebfb9fae7837db492e0f5e69d0e8a544713c50e74
parent0e84f60826a5f640233a3e265da2079f89e422c0 (diff)
downloadpx4-firmware-e952324fbf08405fe555be7169ef0a53a12487f8.tar.gz
px4-firmware-e952324fbf08405fe555be7169ef0a53a12487f8.tar.bz2
px4-firmware-e952324fbf08405fe555be7169ef0a53a12487f8.zip
Rework HoTT into a proper library, which fixes parallel build breakage
-rw-r--r--makefiles/config_px4fmu-v2_default.mk1
-rw-r--r--src/drivers/hott/comms.h2
-rw-r--r--src/drivers/hott/hott_sensors/module.mk4
-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
6 files changed, 54 insertions, 16 deletions
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index 335055cb1..fa5dff93c 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -32,6 +32,7 @@ MODULES += drivers/ll40ls
# MODULES += drivers/trone
MODULES += drivers/gps
MODULES += drivers/hil
+MODULES += drivers/hott
MODULES += drivers/hott/hott_telemetry
MODULES += drivers/hott/hott_sensors
# MODULES += drivers/blinkm
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/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/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