mirror of https://github.com/ArduPilot/ardupilot
Updated ArduPlane/ArduCopter cmake options.
This commit is contained in:
parent
935f918e55
commit
0a38e2b8d4
|
@ -5,14 +5,44 @@ cmake_minimum_required(VERSION 2.8)
|
||||||
project(ArduCopter C CXX)
|
project(ArduCopter C CXX)
|
||||||
|
|
||||||
set(PROJECT_VERSION_MAJOR "2")
|
set(PROJECT_VERSION_MAJOR "2")
|
||||||
set(PROJECT_VERSION_MINOR "3")
|
set(PROJECT_VERSION_MINOR "6")
|
||||||
set(PROJECT_VERSION_PATCH "3")
|
set(PROJECT_VERSION_PATCH "0")
|
||||||
set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}")
|
|
||||||
|
|
||||||
set(PROJECT_DESCRIPTION "ArduPilotMega based Quadrotor Autopilot.")
|
set(PROJECT_DESCRIPTION "ArduPilotMega based Rotor-craft Autopilot.")
|
||||||
|
|
||||||
# macro path
|
# macro path
|
||||||
list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/../cmake/modules")
|
list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/../cmake/modules")
|
||||||
|
include(CMakeParseArguments)
|
||||||
|
include(APMOption)
|
||||||
|
|
||||||
# common project setup
|
# options
|
||||||
include(APMProject)
|
add_definitions(-DUSE_CMAKE_APM_CONFIG)
|
||||||
|
include(options.cmake)
|
||||||
|
include_directories(${CMAKE_BINARY_DIR})
|
||||||
|
apm_option_generate_config(FILE "APM_Config_cmake.h" OPTIONS ${APM_OPTIONS})
|
||||||
|
|
||||||
|
# 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.")
|
||||||
|
|
||||||
|
# built variables
|
||||||
|
set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}")
|
||||||
|
set(FIRMWARE_NAME "${PROJECT_NAME}-${APM_HARDWARE}-${APM_PROCESSOR}-${HIL_MODE}")
|
||||||
|
|
||||||
|
# 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(ARDUINO_EXTRA_LIBRARIES_PATH ${CMAKE_SOURCE_DIR}/../libraries)
|
||||||
|
set(${FIRMWARE_NAME}_SKETCH ${CMAKE_SOURCE_DIR}/../${PROJECT_NAME})
|
||||||
|
set(${FIRMWARE_NAME}_BOARD ${APM_PROCESSOR})
|
||||||
|
set(${FIRMWARE_NAME}_PORT ${APM_PROGRAMMING_PORT})
|
||||||
|
generate_arduino_firmware(${FIRMWARE_NAME})
|
||||||
|
install(FILES ${CMAKE_BINARY_DIR}/${FIRMWARE_NAME}.hex DESTINATION "/")
|
||||||
|
|
||||||
|
# cpack
|
||||||
|
include(APMCPackConfig)
|
||||||
|
|
|
@ -28,7 +28,12 @@
|
||||||
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
|
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
|
||||||
/// change in your local copy of APM_Config.h.
|
/// change in your local copy of APM_Config.h.
|
||||||
///
|
///
|
||||||
|
#ifdef USE_CMAKE_APM_CONFIG
|
||||||
|
#include "APM_Config_cmake.h" // <== Prefer cmake config if it exists
|
||||||
|
#else
|
||||||
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
|
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
|
@ -1,23 +1,42 @@
|
||||||
# options
|
#
|
||||||
|
# This files is used by cmake to present options to the
|
||||||
|
# user in the cmake-gui, it can also be used directly to
|
||||||
|
# set options in the cmake command line.
|
||||||
|
#
|
||||||
|
# This file generates APM_Config_cmake.h
|
||||||
|
# which overrides the APM_Config.h file. When disributing
|
||||||
|
# to the Arduino IDE user. APM_Confg_cmake.h could be copied to
|
||||||
|
# APM_Config.h, but this is not necessary. The
|
||||||
|
# advantage would be that the Arduino user would have
|
||||||
|
# a more up-to-date/ complete list of options and the developers
|
||||||
|
# using cmake have a nice gui/ command-line interface.
|
||||||
|
#
|
||||||
|
|
||||||
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 STRING
|
apm_option("APM_HARDWARE" TYPE STRING
|
||||||
DESCRIPTION "ArduPilotMega board?"
|
DESCRIPTION "APM Hardware?"
|
||||||
|
OPTIONS "APM_HARDARE_APM2" "APM2_BETA_HARDWARE" "APM1"
|
||||||
|
DEFAULT "APM_HARDARE_APM2")
|
||||||
|
|
||||||
|
apm_option("APM_PROCESSOR" TYPE STRING
|
||||||
|
DESCRIPTION "ArduPilotMega processor (2560 for APM2 and later APM1)?"
|
||||||
DEFAULT "mega2560"
|
DEFAULT "mega2560"
|
||||||
OPTIONS "mega" "mega2560")
|
OPTIONS "mega" "mega2560")
|
||||||
|
|
||||||
apm_option("APM_FRAME" TYPE STRING
|
apm_option("CLI_SLIDER_ENABLED" TYPE BOOL
|
||||||
DESCRIPTION "Vehicle type?"
|
DESCRIPTION "Enable command line interface switch?"
|
||||||
DEFAULT "PLANE_FRAME"
|
DEFAULT OFF)
|
||||||
OPTIONS
|
|
||||||
"PLANE FRAME"
|
apm_option("LOGGING_ENABLED" TYPE BOOL
|
||||||
"HELI_FRAME"
|
DESCRIPTION "Enable logging?"
|
||||||
"HEXA_FRAME"
|
DEFAULT OFF)
|
||||||
"OCTA_FRAME"
|
|
||||||
"Y6_FRAME"
|
apm_option("QUATERNION_ENABLE" TYPE BOOL ADVANCED
|
||||||
)
|
DESCRIPTION "Enable quaterion navigation?"
|
||||||
|
DEFAULT OFF)
|
||||||
|
|
||||||
apm_option("GPS_PROTOCOL" TYPE STRING
|
apm_option("GPS_PROTOCOL" TYPE STRING
|
||||||
DESCRIPTION "GPS protocol?"
|
DESCRIPTION "GPS protocol?"
|
||||||
|
@ -72,19 +91,19 @@ apm_option("HIL_PROTOCOL" TYPE STRING
|
||||||
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 STRING
|
apm_option("GCS_PROTOCOL" TYPE STRING
|
||||||
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 STRING ADVANCED
|
apm_option("GCS_PORT" TYPE STRING ADVANCED
|
||||||
DESCRIPTION "Ground station port?"
|
DESCRIPTION "Ground station port?"
|
||||||
DESCRIPTION "3"
|
DEFAULT "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
|
||||||
DESCRIPTION "MAVLink System ID?"
|
DESCRIPTION "MAVLink System ID?"
|
||||||
DESCRIPTION "1")
|
DEFAULT "1")
|
||||||
|
|
||||||
apm_option("SERIAL0_BAUD" TYPE STRING ADVANCED
|
apm_option("SERIAL0_BAUD" TYPE STRING ADVANCED
|
||||||
DESCRIPTION "Serial 0 baudrate?"
|
DESCRIPTION "Serial 0 baudrate?"
|
||||||
|
@ -116,6 +135,41 @@ apm_option("CUR_AMPS_OFFSET" TYPE STRING ADVANCED
|
||||||
DESCRIPTION "Current amps offset?"
|
DESCRIPTION "Current amps offset?"
|
||||||
DEFAULT "0.0")
|
DEFAULT "0.0")
|
||||||
|
|
||||||
apm_option("CUR_AMPS_OFFSET" TYPE STRING ADVANCED
|
# arducopter specific
|
||||||
DESCRIPTION "Current amps offset?"
|
apm_option("FRAME_CONFIG" TYPE STRING
|
||||||
DEFAULT "0.0")
|
DESCRIPTION "Vehicle type?"
|
||||||
|
DEFAULT "QUAD_FRAME"
|
||||||
|
OPTIONS
|
||||||
|
"QUAD_FRAME"
|
||||||
|
"TRI_FRAME"
|
||||||
|
"HEXA_FRAME"
|
||||||
|
"Y6_FRAME"
|
||||||
|
"OCTA_FRAME"
|
||||||
|
"OCTA_QUAD_FRAME"
|
||||||
|
"HELI_FRAME"
|
||||||
|
)
|
||||||
|
|
||||||
|
apm_option("FRAME_ORIENTATION" TYPE STRING
|
||||||
|
DESCRIPTION "Vehicle type?"
|
||||||
|
DEFAULT "QUAD_FRAME"
|
||||||
|
OPTIONS
|
||||||
|
"PLUS_FRAME"
|
||||||
|
"X_FRAME"
|
||||||
|
"V_FRAME"
|
||||||
|
)
|
||||||
|
|
||||||
|
apm_option("CH7_OPTION" TYPE STRING
|
||||||
|
DESCRIPTION "Channel 7 option? (ADC_FILTER is experimental)"
|
||||||
|
DEFAULT "CH7_SAVE_WP"
|
||||||
|
OPTIONS
|
||||||
|
"CH7_DO_NOTHING"
|
||||||
|
"CH7_SET_HOVER"
|
||||||
|
"CH7_FLIP"
|
||||||
|
"CH7_RTL"
|
||||||
|
"CH7_AUTO_TRIM"
|
||||||
|
"CH7_ADC_FILTER"
|
||||||
|
"CH7_SAVE_WP")
|
||||||
|
|
||||||
|
apm_option("ACCEL_ALT_HOLD" TYPE BOOL ADVANCED
|
||||||
|
DESCRIPTION "Disabled by default, work in progress."
|
||||||
|
DEFAULT OFF)
|
||||||
|
|
|
@ -16,9 +16,7 @@
|
||||||
// The following are the recommended settings for Xplane
|
// The following are the recommended settings for Xplane
|
||||||
// simulation. Remove the leading "/* and trailing "*/" to enable:
|
// simulation. Remove the leading "/* and trailing "*/" to enable:
|
||||||
|
|
||||||
/*
|
#define HIL_MODE HIL_MODE_DISABLED
|
||||||
#define HIL_MODE HIL_MODE_ATTITUDE
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
// HIL_MODE SELECTION
|
// HIL_MODE SELECTION
|
||||||
|
|
|
@ -7,12 +7,43 @@ project(ArduPlane C CXX)
|
||||||
set(PROJECT_VERSION_MAJOR "2")
|
set(PROJECT_VERSION_MAJOR "2")
|
||||||
set(PROJECT_VERSION_MINOR "3")
|
set(PROJECT_VERSION_MINOR "3")
|
||||||
set(PROJECT_VERSION_PATCH "3")
|
set(PROJECT_VERSION_PATCH "3")
|
||||||
set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}")
|
|
||||||
|
|
||||||
set(PROJECT_DESCRIPTION "ArduPilotMega based Airplane Autopilot.")
|
set(PROJECT_DESCRIPTION "ArduPilotMega based Airplane Autopilot.")
|
||||||
|
|
||||||
# macro path
|
# macro path
|
||||||
list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/../cmake/modules")
|
list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/../cmake/modules")
|
||||||
|
include(CMakeParseArguments)
|
||||||
|
include(APMOption)
|
||||||
|
|
||||||
# common project setup
|
# options
|
||||||
include(APMProject)
|
add_definitions(-DUSE_CMAKE_APM_CONFIG)
|
||||||
|
include(options.cmake)
|
||||||
|
include_directories(${CMAKE_BINARY_DIR})
|
||||||
|
apm_option_generate_config(FILE "APM_Config_cmake.h" OPTIONS ${APM_OPTIONS})
|
||||||
|
#configure_file(APM_Config2.h.cmake APM_Config2.h)
|
||||||
|
|
||||||
|
# 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.")
|
||||||
|
|
||||||
|
# built variables
|
||||||
|
set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}")
|
||||||
|
set(FIRMWARE_NAME "${PROJECT_NAME}-${APM_HARDWARE}-${APM_PROCESSOR}-${HIL_MODE}")
|
||||||
|
|
||||||
|
# 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(ARDUINO_EXTRA_LIBRARIES_PATH ${CMAKE_SOURCE_DIR}/../libraries)
|
||||||
|
set(${FIRMWARE_NAME}_SKETCH ${CMAKE_SOURCE_DIR}/../${PROJECT_NAME})
|
||||||
|
set(${FIRMWARE_NAME}_BOARD ${APM_PROCESSOR})
|
||||||
|
set(${FIRMWARE_NAME}_PORT ${APM_PROGRAMMING_PORT})
|
||||||
|
generate_arduino_firmware(${FIRMWARE_NAME})
|
||||||
|
install(FILES ${CMAKE_BINARY_DIR}/${FIRMWARE_NAME}.hex DESTINATION "/")
|
||||||
|
|
||||||
|
# cpack
|
||||||
|
include(APMCPackConfig)
|
||||||
|
|
|
@ -26,7 +26,11 @@
|
||||||
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
|
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
|
||||||
/// change in your local copy of APM_Config.h.
|
/// change in your local copy of APM_Config.h.
|
||||||
///
|
///
|
||||||
|
#ifdef USE_CMAKE_APM_CONFIG
|
||||||
|
#include "APM_Config_cmake.h" // <== Prefer cmake config if it exists
|
||||||
|
#else
|
||||||
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
|
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
|
||||||
|
#endif
|
||||||
///
|
///
|
||||||
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
|
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
|
||||||
/// change in your local copy of APM_Config.h.
|
/// change in your local copy of APM_Config.h.
|
||||||
|
|
|
@ -1,29 +1,42 @@
|
||||||
# options
|
#
|
||||||
#bool_option(LOGGING DESCRIPTION "Logging support?" DEFAULT OFF)
|
# This files is used by cmake to present options to the
|
||||||
#bool_option(GPS "Gps support?" ON)
|
# user in the cmake-gui, it can also be used directly to
|
||||||
#option(CLI_SLIDER "Command-line-interface slider support?" OFF)
|
# set options in the cmake command line.
|
||||||
#option(APM2 "Build for APM 2.0" OFF)
|
#
|
||||||
|
# This file generates APM_Config_cmake.h
|
||||||
|
# which overrides the APM_Config.h file. When disributing
|
||||||
|
# to the Arduino IDE user. APM_Confg_cmake.h could be copied to
|
||||||
|
# APM_Config.h, but this is not necessary. The
|
||||||
|
# advantage would be that the Arduino user would have
|
||||||
|
# a more up-to-date/ complete list of options and the developers
|
||||||
|
# using cmake have a nice gui/ command-line interface.
|
||||||
|
#
|
||||||
|
|
||||||
# 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 STRING
|
apm_option("APM_HARDWARE" TYPE STRING
|
||||||
DESCRIPTION "ArduPilotMega board?"
|
DESCRIPTION "APM Hardware?"
|
||||||
|
OPTIONS "APM_HARDARE_APM2" "APM2_BETA_HARDWARE" "APM1"
|
||||||
|
DEFAULT "APM_HARDARE_APM2")
|
||||||
|
|
||||||
|
apm_option("APM_PROCESSOR" TYPE STRING
|
||||||
|
DESCRIPTION "ArduPilotMega processor (2560 for APM2 and later APM1)?"
|
||||||
DEFAULT "mega2560"
|
DEFAULT "mega2560"
|
||||||
OPTIONS "mega" "mega2560")
|
OPTIONS "mega" "mega2560")
|
||||||
|
|
||||||
apm_option("APM_FRAME" TYPE STRING
|
apm_option("CLI_ENABLED" TYPE BOOL
|
||||||
DESCRIPTION "Vehicle type?"
|
DESCRIPTION "Enable command line interface switch?"
|
||||||
DEFAULT "PLANE_FRAME"
|
DEFAULT OFF)
|
||||||
OPTIONS
|
|
||||||
"PLANE FRAME"
|
apm_option("LOGGING_ENABLED" TYPE BOOL
|
||||||
"HELI_FRAME"
|
DESCRIPTION "Enable logging?"
|
||||||
"HEXA_FRAME"
|
DEFAULT OFF)
|
||||||
"OCTA_FRAME"
|
|
||||||
"Y6_FRAME"
|
apm_option("QUATERNION_ENABLE" TYPE BOOL
|
||||||
)
|
DESCRIPTION "Enable quaterion navigation?"
|
||||||
|
DEFAULT OFF)
|
||||||
|
|
||||||
apm_option("GPS_PROTOCOL" TYPE STRING
|
apm_option("GPS_PROTOCOL" TYPE STRING
|
||||||
DESCRIPTION "GPS protocol?"
|
DESCRIPTION "GPS protocol?"
|
||||||
|
@ -78,19 +91,19 @@ apm_option("HIL_PROTOCOL" TYPE STRING
|
||||||
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 STRING
|
apm_option("GCS_PROTOCOL" TYPE STRING
|
||||||
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 STRING ADVANCED
|
apm_option("GCS_PORT" TYPE STRING ADVANCED
|
||||||
DESCRIPTION "Ground station port?"
|
DESCRIPTION "Ground station port?"
|
||||||
DESCRIPTION "3"
|
DEFAULT "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
|
||||||
DESCRIPTION "MAVLink System ID?"
|
DESCRIPTION "MAVLink System ID?"
|
||||||
DESCRIPTION "1")
|
DEFAULT "1")
|
||||||
|
|
||||||
apm_option("SERIAL0_BAUD" TYPE STRING ADVANCED
|
apm_option("SERIAL0_BAUD" TYPE STRING ADVANCED
|
||||||
DESCRIPTION "Serial 0 baudrate?"
|
DESCRIPTION "Serial 0 baudrate?"
|
||||||
|
@ -122,39 +135,47 @@ apm_option("CUR_AMPS_OFFSET" TYPE STRING ADVANCED
|
||||||
DESCRIPTION "Current amps offset?"
|
DESCRIPTION "Current amps offset?"
|
||||||
DEFAULT "0.0")
|
DEFAULT "0.0")
|
||||||
|
|
||||||
apm_option("CUR_AMPS_OFFSET" TYPE STRING ADVANCED
|
apm_option("HIGH_DISCHARGE" TYPE STRING ADVANCED
|
||||||
DESCRIPTION "Current amps offset?"
|
DESCRIPTION "What to consider high discharge rate (milliamps)?"
|
||||||
DEFAULT "0.0")
|
DEFAULT "1760")
|
||||||
|
|
||||||
|
apm_option("INPUT_VOLTAGE" TYPE STRING ADVANCED
|
||||||
|
DESCRIPTION "Voltage measured at the process (V)? (affects ADC measurements)"
|
||||||
|
DEFAULT "4.68")
|
||||||
|
|
||||||
#set(CUR_AMPS_PER_VOLT "27.32" CACHE STRING "Current amps/volt?")
|
set(RADIO_CHANNELS "1" "2" "3" "4" "5" "6" "7" "8")
|
||||||
#set(CUR_AMPS_OFFSET "0.0" CACHE STRING "Current amps offset?")
|
apm_option("FLIGHT_MODE_CHANNEL" TYPE STRING ADVANCED
|
||||||
#set(HIGH_DISCHARGE "1760" CACHE STRING "What to consider high discharge rate (milliamp-hours)?")
|
DESCRIPTION "The radio channel to control the flight mode."
|
||||||
|
DEFAULT "8"
|
||||||
|
OPTIONS ${RADIO_CHANNELS})
|
||||||
|
|
||||||
#set(INPUT_VOLTAGE "4.68" CACHE STRING "Voltage measured at the processor (volts)?")
|
set(FLIGHT_MODES
|
||||||
|
MANUAL STABILIZE
|
||||||
|
FLY_BY_WIRE_A
|
||||||
|
FLY_BY_WIRE_B
|
||||||
|
RTL
|
||||||
|
AUTO
|
||||||
|
LOITER CIRCLE)
|
||||||
|
|
||||||
#set(FLIGHT_MODE_CHANNEL "8" CACHE STRING "The radio channel to control the flight mode.")
|
set(FLIGHT_MODES_RADIO_PWM 1165 1295 1425 1555 1685 1815)
|
||||||
#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_MODES_DEFAULT
|
||||||
|
RTL
|
||||||
|
RTL
|
||||||
|
STABILIZE
|
||||||
|
STABILIZE
|
||||||
|
MANUAL
|
||||||
|
MANUAL)
|
||||||
|
|
||||||
#set(FLIGHT_MODE_1 "RTL" CACHE STRING "Flight mode for radio position 1 (1165 ms)?")
|
foreach(MODE 1 2 3 4 5 6)
|
||||||
#set_property(CACHE FLIGHT_MODE_1 PROPERTY STRINGS ${FLIGHT_MODES})
|
math(EXPR INDEX "${MODE} -1")
|
||||||
|
list(GET FLIGHT_MODES_RADIO_PWM ${INDEX} RADIO_PWM)
|
||||||
#set(FLIGHT_MODE_2 "RTL" CACHE STRING "Flight mode for radio position 2 (1295 ms)?")
|
list(GET FLIGHT_MODES_DEFAULT ${INDEX} FLIGHT_MODE_DEFAULT)
|
||||||
#set_property(CACHE FLIGHT_MODE_2 PROPERTY STRINGS ${FLIGHT_MODES})
|
apm_option("FLIGHT_MODE_${MODE}" TYPE STRING ADVANCED
|
||||||
|
DESCRIPTION "Flight mode ${MODE} (pwm ${RADIO_PWM} ms)?"
|
||||||
#set(FLIGHT_MODE_3 "STABILIZE" CACHE STRING "Flight mode for radio position 3 (1425 ms)?")
|
DEFAULT "${FLIGHT_MODE_DEFAULT}"
|
||||||
#set_property(CACHE FLIGHT_MODE_3 PROPERTY STRINGS ${FLIGHT_MODES})
|
OPTIONS ${FLIGHT_MODES})
|
||||||
|
endforeach()
|
||||||
#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_SPEED "0" CACHE STRING "Speed below which flaps are deployed (m/s)?")
|
||||||
#set(FLAP_1_PERCENT "0" CACHE STRING "Flap deployment percentage (%)?")
|
#set(FLAP_1_PERCENT "0" CACHE STRING "Flap deployment percentage (%)?")
|
||||||
|
|
|
@ -0,0 +1,20 @@
|
||||||
|
# packaging settings
|
||||||
|
set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "${PROJECT_DESCRIPTION}")
|
||||||
|
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 "${PROJECT_VERSION_MAJOR}")
|
||||||
|
set(CPACK_PACKAGE_VERSION_MINOR "${PROJECT_VERSION_MINOR}")
|
||||||
|
set(CPACK_PACKAGE_VERSION_PATCH "${PROJECT_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 "${FIRMWARE_NAME}")
|
||||||
|
include(CPack)
|
|
@ -23,6 +23,12 @@ function(apm_option NAME)
|
||||||
if ("${VAR_TYPE}" STREQUAL "INTERNAL")
|
if ("${VAR_TYPE}" STREQUAL "INTERNAL")
|
||||||
message(STATUS "\tVAR_TYPE: ${VAR_TYPE}")
|
message(STATUS "\tVAR_TYPE: ${VAR_TYPE}")
|
||||||
set("${NAME}" "${ARG_DEFAULT}" CACHE "${ARG_TYPE}" "${ARG_DESCRIPTION}" FORCE)
|
set("${NAME}" "${ARG_DEFAULT}" CACHE "${ARG_TYPE}" "${ARG_DESCRIPTION}" FORCE)
|
||||||
|
|
||||||
|
# if not hidden, add it to the global options list
|
||||||
|
else()
|
||||||
|
set(APM_OPTIONS ${APM_OPTIONS} ${NAME} CACHE INTERNAL "list of all options")
|
||||||
|
list(REMOVE_DUPLICATES APM_OPTIONS)
|
||||||
|
#message(STATUS "APM_OPTIONS: ${APM_OPTIONS}")
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
# set options for combo box
|
# set options for combo box
|
||||||
|
@ -34,3 +40,16 @@ function(apm_option NAME)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
endfunction()
|
endfunction()
|
||||||
|
|
||||||
|
function(apm_option_generate_config)
|
||||||
|
cmake_parse_arguments(ARG "" "FILE" "" ${ARGN})
|
||||||
|
list(REMOVE_DUPLICATES APM_OPTIONS)
|
||||||
|
file (WRITE "${CMAKE_BINARY_DIR}/${ARG_FILE}" "//automatically generated, do not edit\n")
|
||||||
|
file (APPEND "${CMAKE_BINARY_DIR}/${ARG_FILE}" "#define OFF 0\n#define ON 1\n")
|
||||||
|
foreach(ITEM ${APM_OPTIONS})
|
||||||
|
#message(STATUS "item: ${ITEM}")
|
||||||
|
get_property(ITEM_VALUE CACHE ${ITEM} PROPERTY VALUE)
|
||||||
|
get_property(ITEM_HELP CACHE ${ITEM} PROPERTY HELPSTRING)
|
||||||
|
file(APPEND "${CMAKE_BINARY_DIR}/${ARG_FILE}" "\n#define ${ITEM} ${ITEM_VALUE} // ${ITEM_HELP}")
|
||||||
|
endforeach()
|
||||||
|
endfunction()
|
||||||
|
|
|
@ -1,45 +0,0 @@
|
||||||
# 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
|
|
||||||
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(ARDUINO_EXTRA_LIBRARIES_PATH ${CMAKE_SOURCE_DIR}/../libraries)
|
|
||||||
set(${PROJECT_NAME}_SKETCH ${CMAKE_SOURCE_DIR}/../${PROJECT_NAME})
|
|
||||||
set(${PROJECT_NAME}_BOARD ${APM_BOARD})
|
|
||||||
set(${PROJECT_NAME}_PORT ${APM_PROGRAMMING_PORT})
|
|
||||||
generate_arduino_firmware(${PROJECT_NAME})
|
|
||||||
|
|
||||||
# packaging settings
|
|
||||||
set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "${PROJECT_DESCRIPTION}")
|
|
||||||
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)
|
|
|
@ -1,213 +0,0 @@
|
||||||
# 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)
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue