diff --git a/CMakeLists.txt b/CMakeLists.txt
index bfc853a29a8de1346047745815685bd06a8580a9..829c2c1a3e7dd8a05a85f38d1936a258101bdc16 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -10,14 +10,6 @@ set(PROJECT_VERSION_MINOR "3")
 set(PROJECT_VERSION_PATCH "3")
 set(PROJECT_VERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}.${PROJECT_VERSION_PATCH}")
 
-# options
-option(BUILD_2560 "Build 2560 firmware?" ON)
-option(BUILD_1280 "Build 1280 firmware?" OFF)
-
-if (NOT DEFINED PORT)
-	message(WARNING "please define the upload port (for example: cmake -DPORT=/dev/ttyACM0, assuming /dev/ttyACM0")
-	set(PORT "/dev/ttyACM0")
-endif()
 
 # macro path
 list(APPEND CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake/modules")
@@ -27,39 +19,40 @@ 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 "COMBO"
+    DESCRIPTION "ArduPilotMega board?" 
+    DEFAULT "mega2560"
+    OPTIONS "mega" "mega2560")
+
+apm_option("APM_PROJECT" TYPE "COMBO"
+    DESCRIPTION "ArduPilotMega project to build?"
+    DEFAULT "ArduPlane"
+    OPTIONS "ArduPlane" "ArduCopter")
+
+if(APM_PROJECT STREQUAL "ArduPlane")
+    include(cmake/options-ArduPlane.cmake)
+endif()
+
 # 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")
 
-# projects
-set(PROJECT_LIST
-    ArduPlane
-    ArduCopter
-    #apo
-    #ArduBoat
-    #ArduRover
-    )
-
-# macro for building firmware for all projects
-macro(build_apm_firmware BOARD)
-    foreach(PROJECT ${PROJECT_LIST})
-        set(${PROJECT}_SKETCH ${CMAKE_SOURCE_DIR}/${PROJECT})
-        set(${PROJECT}_BOARD ${BOARD})
-        set(${PROJECT}_PORT ${PORT})
-        generate_arduino_firmware(${PROJECT})
-    endforeach()
-endmacro()
-
-# build firmware based on options
-if (BUILD_2560)
-    build_apm_firmware(mega2560)
-endif()
-
-if (BUILD_1280)
-    build_apm_firmware(mega)
-endif()
+# 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.")
@@ -79,5 +72,5 @@ set(CPACK_SOURCE_IGNORE_FILES ${CPACK_SOURCE_IGNORE_FILES}
 set(CPACK_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}")
 set(CPACK_SOURCE_GENERATOR "ZIP")
 set(CPACK_GENERATOR "ZIP")
-set(CPACK_PACKAGE_NAME "${APPLICATION_NAME}_${BOARD}")
+set(CPACK_PACKAGE_NAME "${APM_PROJECT}_${BOARD}_${HIL_MODE}")
 include(CPack)
diff --git a/cmake/modules/APMOption.cmake b/cmake/modules/APMOption.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..5f5597de27b1087b2ec9c8e0d84c2d9b2502f2c6
--- /dev/null
+++ b/cmake/modules/APMOption.cmake
@@ -0,0 +1,27 @@
+macro(apm_option NAME)
+    cmake_parse_arguments(ARG
+        "ADVANCED"
+        "TYPE;DESCRIPTION;DEFAULT" "OPTIONS" ${ARGN})
+
+    if ("${ARG_TYPE}" STREQUAL "BOOL")
+        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 ("${ARG_OPTIONS}" STREQUAL "")
+            message(FATAL_ERROR "must set OPTIONS for add_option(${NAME}...")
+        else()
+            set_property(CACHE "${NAME}" PROPERTY STRINGS "${ARG_OPTIONS}")
+        endif()
+    endif()
+
+    if (ARG_ADVANCED)
+        mark_as_advanced(FORCE "${NAME}")
+    endif()
+
+endmacro()
+
diff --git a/cmake/options-ArduPlane.cmake b/cmake/options-ArduPlane.cmake
new file mode 100644
index 0000000000000000000000000000000000000000..b28bd8016eab6b044b67fae454f40038eb94bfad
--- /dev/null
+++ b/cmake/options-ArduPlane.cmake
@@ -0,0 +1,171 @@
+# 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)
+
+apm_option("APM_FRAME" TYPE "COMBO"
+    DESCRIPTION "Vehicle type?"
+    DEFAULT "PLANE_FRAME"
+    OPTIONS "HELI_FRAME" "HEXA_FRAME" "OCTA_FRAME" "Y6_FRAME")
+
+apm_option("GPS_PROTOCOL" TYPE "COMBO"
+    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"
+    DESCRIPTION "Enable airspeed sensor?"
+    DEFAULT OFF)
+
+apm_option("AIRSPEED_RATIO" TYPE "STRING" ADVANCED
+    DESCRIPTION "Airspeed ratio?"
+    DEFAULT "1.9936")
+
+apm_option("MAGNETOMETER" TYPE "BOOL"
+    DESCRIPTION "Enable airspeed sensor?"
+    DEFAULT OFF)
+
+apm_option("MAG_ORIENTATION" TYPE "COMBO" ADVANCED
+    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 "COMBO"
+    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 "COMBO"
+    DESCRIPTION "Port for Hardware-in-the-loop communication"
+    DEFAULT "0"
+    OPTIONS "0" "1" "2" "3")
+
+apm_option("HIL_PROTOCOL" TYPE "COMBO"
+    DESCRIPTION "Hardware-in-the-loop protocol?"
+    DEFAULT "HIL_PROTOCOL_MAVLINK"
+    OPTIONS "HIL_PROTOCOL_MAVLINK" "HIL_PROTOCOL_XPLANE")
+
+apm_option("GPS_PROTOCOL" TYPE "COMBO"
+    DESCRIPTION "Ground station protocol?"
+    DEFAULT "GCS_PROTOCOL_MAVLINK"
+    OPTIONS "GCS_PROTOCOL_NONE" "GCS_PROTOCOL_MAVLINK")
+
+apm_option("GCS_PORT" TYPE "COMBO" ADVANCED
+    DESCRIPTION "Ground station port?"
+    DESCRIPTION "3"
+    OPTIONS "0" "1" "2" "3")
+
+apm_option("MAV_SYSTEM_ID" TYPE "STRING" ADVANCED
+    DESCRIPTION "MAVLink System ID?"
+    DESCRIPTION "1")
+
+apm_option("SERIAL0_BAUD" TYPE "COMBO" ADVANCED
+    DESCRIPTION "Serial 0 baudrate?"
+    DEFAULT "115200" 
+    OPTIONS "57600" "115200") 
+
+apm_option("SERIAL3_BAUD" TYPE "COMBO" ADVANCED
+    DESCRIPTION "Serial 3 baudrate?"
+    DEFAULT "57600" 
+    OPTIONS "57600" "115200") 
+
+apm_option("BATTERY_EVENT" TYPE "BOOL" ADVANCED
+    DESCRIPTION "Enable low voltage/ high discharge warnings?"
+    DEFAULT OFF)
+
+apm_option("LOW_VOLTAGE" TYPE "STRING" ADVANCED
+    DESCRIPTION "Voltage to consider low (volts)?"
+    DEFAULT "9.6")
+
+apm_option("VOLT_DIV_RATIO" TYPE "STRING" ADVANCED
+    DESCRIPTION "Voltage division ratio?"
+    DEFAULT "3.56")
+
+apm_option("CUR_AMPS_PER_VOLT" TYPE "STRING" ADVANCED
+    DESCRIPTION "Current amps/volt?"
+    DEFAULT "27.32")
+
+apm_option("CUR_AMPS_PER_VOLT" TYPE "STRING" ADVANCED
+    DESCRIPTION "Current amps/volt?"
+    DEFAULT "27.32")
+
+#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) 
+
+