Making cmake local to projects.

This commit is contained in:
James Goppert 2012-04-17 21:31:10 -04:00
parent bce4410419
commit fb07cddd6f
5 changed files with 380 additions and 45 deletions

73
ArduPlane/CMakeLists.txt Normal file
View File

@ -0,0 +1,73 @@
set(CMAKE_TOOLCHAIN_FILE cmake/ArduinoToolchain.cmake) # Arduino Toolchain
cmake_minimum_required(VERSION 2.8)
project(ArduPilotMega C CXX)
# set these for release
set(PROJECT_VERSION_MAJOR "2")
set(PROJECT_VERSION_MINOR "3")
set(PROJECT_VERSION_PATCH "3")
set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}")
# macro path
list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/../cmake/modules")
# disallow in-source build
include(MacroEnsureOutOfSourceBuild)
macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build.
Please create a separate build directory and run 'cmake /path/to/${PROJECT_NAME} [options]' there.")
# macros
include(CMakeParseArguments)
include(APMOption)
# options
apm_option("APM_PROGRAMMING_PORT" TYPE STRING
DESCRIPTION "Programming upload port?"
DEFAULT "/dev/ttyUSB0")
apm_option("APM_BOARD" TYPE STRING
DESCRIPTION "ArduPilotMega board?"
DEFAULT "mega2560"
OPTIONS "mega" "mega2560")
apm_option("APM_PROJECT" TYPE STRING
DESCRIPTION "ArduPilotMega project to build?"
DEFAULT "ArduPlane"
OPTIONS "ArduPlane" "ArduCopter")
include(options.cmake)
# modify flags from default toolchain flags
set(APM_OPT_FLAGS "-Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${APM_OPT_FLAGS}")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${APM_OPT_FLAGS} -Wno-reorder")
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${APM_OPT_FLAGS} -Wl,--relax")
# build apm project
set(${APM_PROJECT}_SKETCH ${CMAKE_SOURCE_DIR}/${APM_PROJECT})
set(${APM_PROJECT}_BOARD ${APM_BOARD})
set(${APM_PROJECT}_PORT ${APM_PROGRAMMING_PORT})
generate_arduino_firmware(${APM_PROJECT})
# packaging settings
set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "A universal autopilot system for the ArduPilotMega board.")
set(CPACK_PACKAGE_VENDOR "DIYDRONES")
set(CPACK_DEBIAN_PACKAGE_MAINTAINER "james.goppert@gmail.com")
set(CPACK_PACKAGE_CONTACT "james.goppert@gmail.com")
set(CPACK_PACKAGE_DESCRIPTION_FILE "${CMAKE_SOURCE_DIR}/README.txt")
set(CPACK_RESOURCE_FILE_LICENSE "${CMAKE_SOURCE_DIR}/COPYING.txt")
set(CPACK_RESOURCE_FILE_README "${CMAKE_SOURCE_DIR}/README.txt")
set(CPACK_PACKAGE_VERSION_MAJOR "${APPLICATION_VERSION_MAJOR}")
set(CPACK_PACKAGE_VERSION_MINOR "${APPLICATION_VERSION_MINOR}")
set(CPACK_PACKAGE_VERSION_PATCH "${APPLICATION_VERSION_PATCH}")
set(CPACK_PACKAGE_INSTALL_DIRECTORY "CMake ${CMake_VERSION_MAJOR}.${CMake_VERSION_MINOR}")
set(CPACK_SET_DESTDIR TRUE)
set(CPACK_SOURCE_IGNORE_FILES ${CPACK_SOURCE_IGNORE_FILES}
/.git/;/build/;~$;.*\\\\.bin$;.*\\\\.swp$)
set(CPACK_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
set(CPACK_SOURCE_GENERATOR "ZIP")
set(CPACK_GENERATOR "ZIP")
set(CPACK_PACKAGE_NAME "${APM_PROJECT}_${BOARD}_${HIL_MODE}")
include(CPack)

View File

@ -4,12 +4,31 @@
#option(CLI_SLIDER "Command-line-interface slider support?" OFF) #option(CLI_SLIDER "Command-line-interface slider support?" OFF)
#option(APM2 "Build for APM 2.0" OFF) #option(APM2 "Build for APM 2.0" OFF)
apm_option("APM_FRAME" TYPE "COMBO" # set booleans for project
foreach(PROJECT_NAME "ArduPlane;ArduCopter")
if ("${APM_PROJECT}" STREQUAL "${PROJECT_NAME}")
set(IS_${PROJECT_NAME} true)
else()
set(IS_${PROJECT_NAME} false)
endif()
endforeach()
if (IS_ARDUCOPTER)
endif()
apm_option("APM_FRAME" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "Vehicle type?" DESCRIPTION "Vehicle type?"
DEFAULT "PLANE_FRAME" DEFAULT "PLANE_FRAME"
OPTIONS "HELI_FRAME" "HEXA_FRAME" "OCTA_FRAME" "Y6_FRAME") OPTIONS
"PLANE FRAME"
"HELI_FRAME"
"HEXA_FRAME"
"OCTA_FRAME"
"Y6_FRAME"
)
apm_option("GPS_PROTOCOL" TYPE "COMBO" apm_option("GPS_PROTOCOL" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "GPS protocol?" DESCRIPTION "GPS protocol?"
DEFAULT "GPS_PROTOCOL_AUTO" DEFAULT "GPS_PROTOCOL_AUTO"
OPTIONS OPTIONS
@ -23,19 +42,23 @@ apm_option("GPS_PROTOCOL" TYPE "COMBO"
"GPS_PROTOCOL_SIRF" "GPS_PROTOCOL_SIRF"
"GPS_PROTOCOL_NMEA") "GPS_PROTOCOL_NMEA")
apm_option("AIRSPEED_SENSOR" TYPE "BOOL" apm_option("AIRSPEED_SENSOR" TYPE BOOL
DEPENDS IS_ARDUPLANE
DESCRIPTION "Enable airspeed sensor?" DESCRIPTION "Enable airspeed sensor?"
DEFAULT OFF) DEFAULT OFF)
apm_option("AIRSPEED_RATIO" TYPE "STRING" ADVANCED apm_option("AIRSPEED_RATIO" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Airspeed ratio?" DESCRIPTION "Airspeed ratio?"
DEFAULT "1.9936") DEFAULT "1.9936")
apm_option("MAGNETOMETER" TYPE "BOOL" apm_option("MAGNETOMETER" TYPE BOOL
DEPENDS IS_ARDUPLANE
DESCRIPTION "Enable airspeed sensor?" DESCRIPTION "Enable airspeed sensor?"
DEFAULT OFF) DEFAULT OFF)
apm_option("MAG_ORIENTATION" TYPE "COMBO" ADVANCED apm_option("MAG_ORIENTATION" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Magnetometer orientation?" DESCRIPTION "Magnetometer orientation?"
DEFAULT "AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD" DEFAULT "AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD"
OPTIONS OPTIONS
@ -44,7 +67,8 @@ apm_option("MAG_ORIENTATION" TYPE "COMBO" ADVANCED
"AP_COMPASS_COMPONENTS_UP_PINS_FORWARD" "AP_COMPASS_COMPONENTS_UP_PINS_FORWARD"
"AP_COMPASS_COMPONENTS_UP_PINS_BACK") "AP_COMPASS_COMPONENTS_UP_PINS_BACK")
apm_option("HIL_MODE" TYPE "COMBO" apm_option("HIL_MODE" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "Hardware-in-the-loop- mode?" DESCRIPTION "Hardware-in-the-loop- mode?"
DEFAULT "HIL_MODE_DISABLED" DEFAULT "HIL_MODE_DISABLED"
OPTIONS OPTIONS
@ -52,59 +76,77 @@ apm_option("HIL_MODE" TYPE "COMBO"
"HIL_MODE_ATTITUDE" "HIL_MODE_ATTITUDE"
"HIL_MODE_SENSORS") "HIL_MODE_SENSORS")
apm_option("HIL_PORT" TYPE "COMBO" apm_option("HIL_PORT" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "Port for Hardware-in-the-loop communication" DESCRIPTION "Port for Hardware-in-the-loop communication"
DEFAULT "0" DEFAULT "0"
OPTIONS "0" "1" "2" "3") OPTIONS "0" "1" "2" "3")
apm_option("HIL_PROTOCOL" TYPE "COMBO" apm_option("HIL_PROTOCOL" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "Hardware-in-the-loop protocol?" DESCRIPTION "Hardware-in-the-loop protocol?"
DEFAULT "HIL_PROTOCOL_MAVLINK" DEFAULT "HIL_PROTOCOL_MAVLINK"
OPTIONS "HIL_PROTOCOL_MAVLINK" "HIL_PROTOCOL_XPLANE") OPTIONS "HIL_PROTOCOL_MAVLINK" "HIL_PROTOCOL_XPLANE")
apm_option("GPS_PROTOCOL" TYPE "COMBO" apm_option("GPS_PROTOCOL" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "Ground station protocol?" DESCRIPTION "Ground station protocol?"
DEFAULT "GCS_PROTOCOL_MAVLINK" DEFAULT "GCS_PROTOCOL_MAVLINK"
OPTIONS "GCS_PROTOCOL_NONE" "GCS_PROTOCOL_MAVLINK") OPTIONS "GCS_PROTOCOL_NONE" "GCS_PROTOCOL_MAVLINK")
apm_option("GCS_PORT" TYPE "COMBO" ADVANCED apm_option("GCS_PORT" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Ground station port?" DESCRIPTION "Ground station port?"
DESCRIPTION "3" DESCRIPTION "3"
OPTIONS "0" "1" "2" "3") OPTIONS "0" "1" "2" "3")
apm_option("MAV_SYSTEM_ID" TYPE "STRING" ADVANCED apm_option("MAV_SYSTEM_ID" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "MAVLink System ID?" DESCRIPTION "MAVLink System ID?"
DESCRIPTION "1") DESCRIPTION "1")
apm_option("SERIAL0_BAUD" TYPE "COMBO" ADVANCED apm_option("SERIAL0_BAUD" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Serial 0 baudrate?" DESCRIPTION "Serial 0 baudrate?"
DEFAULT "115200" DEFAULT "115200"
OPTIONS "57600" "115200") OPTIONS "57600" "115200")
apm_option("SERIAL3_BAUD" TYPE "COMBO" ADVANCED apm_option("SERIAL3_BAUD" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Serial 3 baudrate?" DESCRIPTION "Serial 3 baudrate?"
DEFAULT "57600" DEFAULT "57600"
OPTIONS "57600" "115200") OPTIONS "57600" "115200")
apm_option("BATTERY_EVENT" TYPE "BOOL" ADVANCED apm_option("BATTERY_EVENT" TYPE BOOL ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Enable low voltage/ high discharge warnings?" DESCRIPTION "Enable low voltage/ high discharge warnings?"
DEFAULT OFF) DEFAULT OFF)
apm_option("LOW_VOLTAGE" TYPE "STRING" ADVANCED apm_option("LOW_VOLTAGE" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Voltage to consider low (volts)?" DESCRIPTION "Voltage to consider low (volts)?"
DEFAULT "9.6") DEFAULT "9.6")
apm_option("VOLT_DIV_RATIO" TYPE "STRING" ADVANCED apm_option("VOLT_DIV_RATIO" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Voltage division ratio?" DESCRIPTION "Voltage division ratio?"
DEFAULT "3.56") DEFAULT "3.56")
apm_option("CUR_AMPS_PER_VOLT" TYPE "STRING" ADVANCED apm_option("CUR_AMPS_PER_VOLT" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Current amps/volt?" DESCRIPTION "Current amps/volt?"
DEFAULT "27.32") DEFAULT "27.32")
apm_option("CUR_AMPS_PER_VOLT" TYPE "STRING" ADVANCED apm_option("CUR_AMPS_OFFSET" TYPE STRING ADVANCED
DESCRIPTION "Current amps/volt?" DEPENDS IS_ARDUPLANE
DEFAULT "27.32") DESCRIPTION "Current amps offset?"
DEFAULT "0.0")
apm_option("CUR_AMPS_OFFSET" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Current amps offset?"
DEFAULT "0.0")
#set(CUR_AMPS_PER_VOLT "27.32" CACHE STRING "Current amps/volt?") #set(CUR_AMPS_PER_VOLT "27.32" CACHE STRING "Current amps/volt?")
#set(CUR_AMPS_OFFSET "0.0" CACHE STRING "Current amps offset?") #set(CUR_AMPS_OFFSET "0.0" CACHE STRING "Current amps offset?")

View File

@ -24,23 +24,21 @@ include(CMakeParseArguments)
include(APMOption) include(APMOption)
# options # options
apm_option("APM_PROGRAMMING_PORT" TYPE "STRING" apm_option("APM_PROGRAMMING_PORT" TYPE STRING
DESCRIPTION "Programming upload port?" DESCRIPTION "Programming upload port?"
DEFAULT "/dev/ttyUSB0") DEFAULT "/dev/ttyUSB0")
apm_option("APM_BOARD" TYPE "COMBO" apm_option("APM_BOARD" TYPE STRING
DESCRIPTION "ArduPilotMega board?" DESCRIPTION "ArduPilotMega board?"
DEFAULT "mega2560" DEFAULT "mega2560"
OPTIONS "mega" "mega2560") OPTIONS "mega" "mega2560")
apm_option("APM_PROJECT" TYPE "COMBO" apm_option("APM_PROJECT" TYPE STRING
DESCRIPTION "ArduPilotMega project to build?" DESCRIPTION "ArduPilotMega project to build?"
DEFAULT "ArduPlane" DEFAULT "ArduPlane"
OPTIONS "ArduPlane" "ArduCopter") OPTIONS "ArduPlane" "ArduCopter")
if(APM_PROJECT STREQUAL "ArduPlane") include(cmake/options-ArduPlane.cmake)
include(cmake/options-ArduPlane.cmake)
endif()
# modify flags from default toolchain flags # modify flags from default toolchain flags
set(APM_OPT_FLAGS "-Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2") set(APM_OPT_FLAGS "-Wformat -Wall -Wshadow -Wpointer-arith -Wcast-align -Wwrite-strings -Wformat=2")

View File

@ -1,27 +1,36 @@
macro(apm_option NAME) function(apm_option NAME)
cmake_parse_arguments(ARG cmake_parse_arguments(ARG
"ADVANCED" "ADVANCED"
"TYPE;DESCRIPTION;DEFAULT" "OPTIONS" ${ARGN}) "TYPE;DESCRIPTION;DEFAULT" "OPTIONS;DEPENDS" ${ARGN})
if ("${ARG_TYPE}" STREQUAL "BOOL") #message(STATUS "parsing argument: ${NAME}")
set("${NAME}" "${ARG_DEFAULT}" CACHE BOOL "${ARG_DESCRIPTION}")
elseif ( ("${ARG_TYPE}" STREQUAL "STRING") OR ("${ARG_TYPE}" STREQUAL "COMBO"))
set("${NAME}" "${ARG_DEFAULT}" CACHE STRING "${ARG_DESCRIPTION}")
else()
message(FATAL_ERROR "unknown type: \""${ARG_TYPE}"\" for add_option(${NAME}...")
endif()
if ("${ARG_TYPE}" STREQUAL "COMBO") # if option dependencies not met, hide the option
if ("${ARG_OPTIONS}" STREQUAL "") foreach(DEPEND ${ARG_DEPENDS})
message(FATAL_ERROR "must set OPTIONS for add_option(${NAME}...") if (NOT ${${DEPEND}})
else() #message(STATUS "\tfailed dep: ${DEPEND}")
set_property(CACHE "${NAME}" PROPERTY STRINGS "${ARG_OPTIONS}") set(ARG_TYPE "INTERNAL")
set("${NAME}" "${ARG_DEFAULT}" CACHE INTERNAL "${ARG_DESCRIPTION}" FORCE)
return()
endif() endif()
endforeach()
# set variable
set("${NAME}" "${ARG_DEFAULT}" CACHE "${ARG_TYPE}" "${ARG_DESCRIPTION}")
# force variable reinit if it was internal (hidden)
get_property(VAR_TYPE CACHE ${NAME} PROPERTY TYPE)
if ("${VAR_TYPE}" STREQUAL "INTERNAL")
message(STATUS "\tVAR_TYPE: ${VAR_TYPE}")
set("${NAME}" "${ARG_DEFAULT}" CACHE "${ARG_TYPE}" "${ARG_DESCRIPTION}" FORCE)
endif() endif()
if (ARG_ADVANCED) # set options for combo box
set_property(CACHE "${NAME}" PROPERTY STRINGS ${ARG_OPTIONS})
# mark as advanced if advanced option given
if(ARG_ADVANCED)
mark_as_advanced(FORCE "${NAME}") mark_as_advanced(FORCE "${NAME}")
endif() endif()
endmacro() endfunction()

213
cmake/options.cmake Normal file
View File

@ -0,0 +1,213 @@
# options
#bool_option(LOGGING DESCRIPTION "Logging support?" DEFAULT OFF)
#bool_option(GPS "Gps support?" ON)
#option(CLI_SLIDER "Command-line-interface slider support?" OFF)
#option(APM2 "Build for APM 2.0" OFF)
# set booleans for project
foreach(PROJECT_NAME "ArduPlane;ArduCopter")
if ("${APM_PROJECT}" STREQUAL "${PROJECT_NAME}")
set(IS_${PROJECT_NAME} true)
else()
set(IS_${PROJECT_NAME} false)
endif()
endforeach()
if (IS_ARDUCOPTER)
endif()
apm_option("APM_FRAME" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "Vehicle type?"
DEFAULT "PLANE_FRAME"
OPTIONS
"PLANE FRAME"
"HELI_FRAME"
"HEXA_FRAME"
"OCTA_FRAME"
"Y6_FRAME"
)
apm_option("GPS_PROTOCOL" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "GPS protocol?"
DEFAULT "GPS_PROTOCOL_AUTO"
OPTIONS
"GPS_PROTOOCL_NONE"
"GPS_PROTOCOL_AUTO"
"GPS_PROTOCOL_NONE"
"GPS_PROTOCOL_IMU"
"GPS_PROTOCOL_MTK"
"GPS_PROTOCOL_MTK16"
"GPS_PROTOCOL_UBLOX"
"GPS_PROTOCOL_SIRF"
"GPS_PROTOCOL_NMEA")
apm_option("AIRSPEED_SENSOR" TYPE BOOL
DEPENDS IS_ARDUPLANE
DESCRIPTION "Enable airspeed sensor?"
DEFAULT OFF)
apm_option("AIRSPEED_RATIO" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Airspeed ratio?"
DEFAULT "1.9936")
apm_option("MAGNETOMETER" TYPE BOOL
DEPENDS IS_ARDUPLANE
DESCRIPTION "Enable airspeed sensor?"
DEFAULT OFF)
apm_option("MAG_ORIENTATION" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Magnetometer orientation?"
DEFAULT "AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD"
OPTIONS
"AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD"
"AP_COMPASS_COMPONENTS_DOWN_PINS_BACK"
"AP_COMPASS_COMPONENTS_UP_PINS_FORWARD"
"AP_COMPASS_COMPONENTS_UP_PINS_BACK")
apm_option("HIL_MODE" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "Hardware-in-the-loop- mode?"
DEFAULT "HIL_MODE_DISABLED"
OPTIONS
"HIL_MODE_DISABLED"
"HIL_MODE_ATTITUDE"
"HIL_MODE_SENSORS")
apm_option("HIL_PORT" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "Port for Hardware-in-the-loop communication"
DEFAULT "0"
OPTIONS "0" "1" "2" "3")
apm_option("HIL_PROTOCOL" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "Hardware-in-the-loop protocol?"
DEFAULT "HIL_PROTOCOL_MAVLINK"
OPTIONS "HIL_PROTOCOL_MAVLINK" "HIL_PROTOCOL_XPLANE")
apm_option("GPS_PROTOCOL" TYPE STRING
DEPENDS IS_ARDUPLANE
DESCRIPTION "Ground station protocol?"
DEFAULT "GCS_PROTOCOL_MAVLINK"
OPTIONS "GCS_PROTOCOL_NONE" "GCS_PROTOCOL_MAVLINK")
apm_option("GCS_PORT" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Ground station port?"
DESCRIPTION "3"
OPTIONS "0" "1" "2" "3")
apm_option("MAV_SYSTEM_ID" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "MAVLink System ID?"
DESCRIPTION "1")
apm_option("SERIAL0_BAUD" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Serial 0 baudrate?"
DEFAULT "115200"
OPTIONS "57600" "115200")
apm_option("SERIAL3_BAUD" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Serial 3 baudrate?"
DEFAULT "57600"
OPTIONS "57600" "115200")
apm_option("BATTERY_EVENT" TYPE BOOL ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Enable low voltage/ high discharge warnings?"
DEFAULT OFF)
apm_option("LOW_VOLTAGE" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Voltage to consider low (volts)?"
DEFAULT "9.6")
apm_option("VOLT_DIV_RATIO" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Voltage division ratio?"
DEFAULT "3.56")
apm_option("CUR_AMPS_PER_VOLT" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Current amps/volt?"
DEFAULT "27.32")
apm_option("CUR_AMPS_OFFSET" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Current amps offset?"
DEFAULT "0.0")
apm_option("CUR_AMPS_OFFSET" TYPE STRING ADVANCED
DEPENDS IS_ARDUPLANE
DESCRIPTION "Current amps offset?"
DEFAULT "0.0")
#set(CUR_AMPS_PER_VOLT "27.32" CACHE STRING "Current amps/volt?")
#set(CUR_AMPS_OFFSET "0.0" CACHE STRING "Current amps offset?")
#set(HIGH_DISCHARGE "1760" CACHE STRING "What to consider high discharge rate (milliamp-hours)?")
#set(INPUT_VOLTAGE "4.68" CACHE STRING "Voltage measured at the processor (volts)?")
#set(FLIGHT_MODE_CHANNEL "8" CACHE STRING "The radio channel to control the flight mode.")
#set_property(CACHE FLIGHT_MODE_CHANNEL PROPERTY STRINGS 1 2 3 4 5 6 7 8)
#set(FLIGHT_MODES MANUAL STABILIZE FLY_BY_WIRE_A FLY_BY_WIRE_B RTL AUTO LOITER CIRCLE)
#set(FLIGHT_MODE_1 "RTL" CACHE STRING "Flight mode for radio position 1 (1165 ms)?")
#set_property(CACHE FLIGHT_MODE_1 PROPERTY STRINGS ${FLIGHT_MODES})
#set(FLIGHT_MODE_2 "RTL" CACHE STRING "Flight mode for radio position 2 (1295 ms)?")
#set_property(CACHE FLIGHT_MODE_2 PROPERTY STRINGS ${FLIGHT_MODES})
#set(FLIGHT_MODE_3 "STABILIZE" CACHE STRING "Flight mode for radio position 3 (1425 ms)?")
#set_property(CACHE FLIGHT_MODE_3 PROPERTY STRINGS ${FLIGHT_MODES})
#set(FLIGHT_MODE_4 "STABILIZE" CACHE STRING "Flight mode for radio position 4 (1555 ms)?")
#set_property(CACHE FLIGHT_MODE_4 PROPERTY STRINGS ${FLIGHT_MODES})
#set(FLIGHT_MODE_5 "MANUAL" CACHE STRING "Flight mode for radio position 5 (FAILSAFE if using channel 8) (1685 ms)?")
#set_property(CACHE FLIGHT_MODE_5 PROPERTY STRINGS ${FLIGHT_MODES})
#set(FLIGHT_MODE_6 "MANUAL" CACHE STRING "Flight mode for radio position 6 (FAILSAFE is using channel 8) (1815 ms)?")
#set_property(CACHE FLIGHT_MODE_6 PROPERTY STRINGS ${FLIGHT_MODES})
#set(FLAP_1_SPEED "0" CACHE STRING "Speed below which flaps are deployed (m/s)?")
#set(FLAP_1_PERCENT "0" CACHE STRING "Flap deployment percentage (%)?")
#set(FLAP_2_SPEED "0" CACHE STRING "Speed below which flaps are deployed (m/s)?")
#set(FLAP_2_PERCENT "0" CACHE STRING "Flap deployment percentage (%)?")
#set(THROTTLE_FAILSAFE "ENABLED" CACHE STRING "Enable throttle shuttoff when radio below failsafe value?")
#set_property(CACHE THROTTLE_FAILSAFE PROPERTY STRINGS ENABLED DISABLED)
#set(THROTTLE_FS_VALUE "950" CACHE STRING "Radio value at which to disable throttle (ms).")
#set(GCS_HEARTBEAT_FAILSAFE "DISABLED" CACHE STRING "Enable failsafe when ground station communication lost?")
#set_property(CACHE GCS_HEARTBEAT_FAILSAFE PROPERTY STRINGS ENABLED DISABLED)
#set(SHORT_FAILSAFE_ACTION "0" CACHE STRING "Failsafe mode RTL, then return to AUTO/LOITER")
#set(LONG_FAILSAFE_ACTION "0" CACHE STRING "Failsafe mode RTL")
#set(AUTO_TRIM "DISABLED" CACHE STRING "Update trim with manual radio input when leaving MANUAL mode?")
#set_property(CACHE AUTO_TRIM PROPERTY STRINGS ENABLED DISABLED)
#set(THROTTLE_REVERSE "DISABLED" CACHE STRING "Reverse throttle output signal?")
#set_property(CACHE THROTTLE_REVERSE PROPERTY STRINGS ENABLED DISABLED)
#set(ENABLE_STICK_MIXING "DISABLED" CACHE STRING "Enable manual input in autopilot modes?")
#set_property(CACHE THROTTLE_REVERSE PROPERTY STRINGS ENABLED DISABLED)
#set(THROTTLE_OUT "ENABLED" CACHE STRING "Disabled throttle output? (useful for debugging)?")
#set_property(CACHE THROTTLE_OUT PROPERTY STRINGS ENABLED DISABLED)
#set(GROUND_START_DELAY "0" CACHE STRING "Delay between power-up and IMU calibration (s)?")
#set(ENABLE_AIR_START "DISABLED" CACHE STRING "Enable in-air restart?")
#set_property(CACHE ENABLE_AIR_START PROPERTY STRINGS ENABLED DISABLED)