From ed0722e298f9b86d8eecf5c7df280b0b34561251 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Mon, 31 Oct 2011 13:18:48 -0400 Subject: [PATCH] ArduPlane cmake build working. --- .project | 1 - CMakeLists.txt | 8 ++++---- libraries/AP_GPS/AP_GPS_IMU.cpp | 2 +- 3 files changed, 5 insertions(+), 6 deletions(-) diff --git a/.project b/.project index db4ffb2294..e6215fa3bb 100644 --- a/.project +++ b/.project @@ -3,7 +3,6 @@ ArduPilotMega-Source@ardupilotone - ArduPilotMega@ardupilotone-unix diff --git a/CMakeLists.txt b/CMakeLists.txt index 58ec82bb9f..4c54fc7836 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -124,16 +124,16 @@ macro(add_sketch SKETCH_NAME BOARD PORT) foreach(PDE ${PDE_SOURCES}) message(STATUS "pde: ${PDE}") file(READ ${PDE} FILE) - string(REGEX MATCHALL "([a-zA-Z]+[ ]+)*[ ]*[a-zA-Z0-9]+[ ]+[_a-zA-Z0-9]+[(][^)]*[)]" PROTOTYPES ${FILE}) + string(REGEX MATCHALL "[\n]([a-zA-Z]+[ ])*[_a-zA-Z0-9]+([ ]*[\n][\t]*|[ ])[_a-zA-Z0-9]+[ ]?[\n]?[\t]*[ ]*[(]([\t]*[ ]*[*]?[ ]?[a-zA-Z0-9_][,]?[ ]*[\n]?)*[)]" PROTOTYPES ${FILE}) foreach(PROTOTYPE ${PROTOTYPES}) message(STATUS "\tprototype: ${PROTOTYPE};") - file(APPEND ${SKETCH_CPP} "${PROTOTYPE};\n") + file(APPEND ${SKETCH_CPP} "${PROTOTYPE};") endforeach() endforeach() # write source - file(APPEND ${SKETCH_CPP} "${FILE_BODY}") + file(APPEND ${SKETCH_CPP} "\n${FILE_BODY}") list(REMOVE_ITEM PDE_SOURCES ${SKETCH_PDE}) list(SORT PDE_SOURCES) foreach (PDE ${PDE_SOURCES}) @@ -157,5 +157,5 @@ endmacro() add_sketch(apo ${BOARD} ${PORT}) add_sketch(ArduRover ${BOARD} ${PORT}) add_sketch(ArduBoat ${BOARD} ${PORT}) -#add_sketch(ArduPlane ${BOARD} ${PORT}) +add_sketch(ArduPlane ${BOARD} ${PORT}) #add_sketch(ArduCopter ${BOARD} ${PORT}) diff --git a/libraries/AP_GPS/AP_GPS_IMU.cpp b/libraries/AP_GPS/AP_GPS_IMU.cpp index 71fc6f2e23..8e5da67ae9 100644 --- a/libraries/AP_GPS/AP_GPS_IMU.cpp +++ b/libraries/AP_GPS/AP_GPS_IMU.cpp @@ -220,7 +220,7 @@ void AP_GPS_IMU::GPS_join_data(void) * ****************************************************************/ // checksum algorithm -void AP_GPS_IMU::checksum(byte data) +void AP_GPS_IMU::checksum(unsigned char data) { ck_a += data; ck_b += ck_a;