Browse Source

Rework HoTT into a proper library, which fixes parallel build breakage

sbg
Lorenz Meier 10 years ago
parent
commit
e952324fbf
  1. 1
      makefiles/config_px4fmu-v2_default.mk
  2. 2
      src/drivers/hott/comms.h
  3. 4
      src/drivers/hott/hott_sensors/module.mk
  4. 4
      src/drivers/hott/hott_telemetry/module.mk
  5. 18
      src/drivers/hott/messages.h
  6. 41
      src/drivers/hott/module.mk

1
makefiles/config_px4fmu-v2_default.mk

@ -32,6 +32,7 @@ MODULES += drivers/ll40ls @@ -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

2
src/drivers/hott/comms.h

@ -41,6 +41,6 @@ @@ -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_ */

4
src/drivers/hott/hott_sensors/module.mk

@ -37,8 +37,6 @@ @@ -37,8 +37,6 @@
MODULE_COMMAND = hott_sensors
SRCS = hott_sensors.cpp \
../messages.cpp \
../comms.cpp
SRCS = hott_sensors.cpp
MAXOPTIMIZATION = -Os

4
src/drivers/hott/hott_telemetry/module.mk

@ -37,8 +37,6 @@ @@ -37,8 +37,6 @@
MODULE_COMMAND = hott_telemetry
SRCS = hott_telemetry.cpp \
../messages.cpp \
../comms.cpp
SRCS = hott_telemetry.cpp
MAXOPTIMIZATION = -Os

18
src/drivers/hott/messages.h

@ -235,15 +235,15 @@ struct gps_module_msg { @@ -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_ */

41
src/drivers/hott/module.mk

@ -0,0 +1,41 @@ @@ -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
Loading…
Cancel
Save