diff --git a/.project b/.project
new file mode 100644
index 0000000000..e6215fa3bb
--- /dev/null
+++ b/.project
@@ -0,0 +1,11 @@
+
+
+ ArduPilotMega-Source@ardupilotone
+
+
+
+
+
+
+
+
diff --git a/ArduBoat/.cproject b/ArduBoat/.cproject
deleted file mode 100644
index adf5adc365..0000000000
--- a/ArduBoat/.cproject
+++ /dev/null
@@ -1,46 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/ArduBoat/.project b/ArduBoat/.project
deleted file mode 100644
index 969ff0d90c..0000000000
--- a/ArduBoat/.project
+++ /dev/null
@@ -1,79 +0,0 @@
-
-
- ArduBoat
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
- ?name?
-
-
-
- org.eclipse.cdt.make.core.append_environment
- true
-
-
- org.eclipse.cdt.make.core.autoBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.buildArguments
-
-
-
- org.eclipse.cdt.make.core.buildCommand
- make
-
-
- org.eclipse.cdt.make.core.cleanBuildTarget
- clean
-
-
- org.eclipse.cdt.make.core.contents
- org.eclipse.cdt.make.core.activeConfigSettings
-
-
- org.eclipse.cdt.make.core.enableAutoBuild
- false
-
-
- org.eclipse.cdt.make.core.enableCleanBuild
- true
-
-
- org.eclipse.cdt.make.core.enableFullBuild
- true
-
-
- org.eclipse.cdt.make.core.fullBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.stopOnError
- true
-
-
- org.eclipse.cdt.make.core.useDefaultBuildCmd
- true
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
-
-
diff --git a/ArduBoat/ArduBoat.cpp b/ArduBoat/ArduBoat.cpp
deleted file mode 100644
index bd0063b5ff..0000000000
--- a/ArduBoat/ArduBoat.cpp
+++ /dev/null
@@ -1,25 +0,0 @@
-// Libraries
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-// Vehicle Configuration
-#include "BoatGeneric.h"
-
-// ArduPilotOne Default Setup
-#include "APO_DefaultSetup.h"
-
-#include ; int main(void) {init();setup();for(;;) loop(); return 0; }
-// vim:ts=4:sw=4:expandtab
diff --git a/ArduBoat/ArduBoat.pde b/ArduBoat/ArduBoat.pde
index 8cc21d430a..2ac3b8afee 100644
--- a/ArduBoat/ArduBoat.pde
+++ b/ArduBoat/ArduBoat.pde
@@ -13,7 +13,6 @@
#include
#include
#include
-#include
// Vehicle Configuration
#include "BoatGeneric.h"
diff --git a/ArduCopter/.cproject b/ArduCopter/.cproject
deleted file mode 100644
index b27b2109a4..0000000000
--- a/ArduCopter/.cproject
+++ /dev/null
@@ -1,970 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- make
-
-
- true
- true
- true
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- make
-
-
- true
- true
- true
-
-
-
-
-
-
-
-
-
diff --git a/ArduCopter/.project b/ArduCopter/.project
deleted file mode 100644
index a70da34626..0000000000
--- a/ArduCopter/.project
+++ /dev/null
@@ -1,84 +0,0 @@
-
-
- ArduCopterMega
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
- ?name?
-
-
-
- org.eclipse.cdt.make.core.append_environment
- true
-
-
- org.eclipse.cdt.make.core.autoBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.buildArguments
-
-
-
- org.eclipse.cdt.make.core.buildCommand
- make
-
-
- org.eclipse.cdt.make.core.buildLocation
- ${workspace_loc:/ArduCopterMega/Debug}
-
-
- org.eclipse.cdt.make.core.cleanBuildTarget
- clean
-
-
- org.eclipse.cdt.make.core.contents
- org.eclipse.cdt.make.core.activeConfigSettings
-
-
- org.eclipse.cdt.make.core.enableAutoBuild
- false
-
-
- org.eclipse.cdt.make.core.enableCleanBuild
- true
-
-
- org.eclipse.cdt.make.core.enableFullBuild
- true
-
-
- org.eclipse.cdt.make.core.fullBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.stopOnError
- true
-
-
- org.eclipse.cdt.make.core.useDefaultBuildCmd
- true
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- de.innot.avreclipse.core.avrnature
-
-
diff --git a/ArduCopter/CMakeLists.txt b/ArduCopter/CMakeLists.txt
deleted file mode 100644
index ba540e183c..0000000000
--- a/ArduCopter/CMakeLists.txt
+++ /dev/null
@@ -1,165 +0,0 @@
-#=============================================================================#
-# Author: Niklaa Goddemeier & Sebastian Rohde #
-# Date: 04.09.2011 #
-#=============================================================================#
-
-set(CMAKE_SOURCE_DIR "${CMAKE_SOURCE_DIR}/../")
-
-set(CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/modules) # CMake module search path
-set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Arduino.cmake) # Arduino Toolchain
-#include(ArduinoProcessing)
-
-set (CMAKE_CXX_SOURCE_FILE_EXTENSIONS pde)
-
-
-message(STATUS "DIR: ${CMAKE_SOURCE_DIR}")
-
-cmake_minimum_required(VERSION 2.8)
-#====================================================================#
-# Setup Project #
-#====================================================================#
-project(ArduCopter C CXX)
-
-find_package(Arduino 22 REQUIRED)
-
-if (NOT DEFINED BOARD)
- message(STATUS "board not defined, assuming mega, use cmake -DBOARD=mega2560 , etc. to specify")
- set(BOARD "mega")
-endif()
-message(STATUS "Board configured as: ${BOARD}")
-
-add_subdirectory(../libraries "${CMAKE_CURRENT_BINARY_DIR}/libs")
-
-#add_subdirectory(${CMAKE_SOURCE_DIR}/ArduCopter)
-#add_subdirectory(testtool)
-
-PRINT_BOARD_SETTINGS(${BOARD})
-
-
-
-#=============================================================================#
-# Author: Niklas Goddemeier & Sebastian Rohde #
-# Date: 04.09.2011 #
-#=============================================================================#
-
-
-#====================================================================#
-# Settings #
-#====================================================================#
-set(FIRMWARE_NAME arducopter)
-
-set(${FIRMWARE_NAME}_BOARD ${BOARD}) # Arduino Target board
-
-set(${FIRMWARE_NAME}_SKETCHES
- ArduCopter.pde
- Attitude.pde
- Camera.pde
- commands.pde
- commands_logic.pde
- commands_process.pde
- control_modes.pde
- events.pde
- flip.pde
- GCS.pde
- GCS_Ardupilot.pde
- #GCS_IMU_output.pde
- GCS_Jason_text.pde
- GCS_Mavlink.pde
- GCS_Standard.pde
- GCS_Xplane.pde
- heli.pde
- HIL_Xplane.pde
- leds.pde
- Log.pde
- motors_hexa.pde
- motors_octa.pde
- motors_octa_quad.pde
- motors_quad.pde
- motors_tri.pde
- motors_y6.pde
- navigation.pde
- planner.pde
- radio.pde
- read_commands.pde
- sensors.pde
- setup.pde
- system.pde
- test.pde
- ) # Firmware sketches
-
-#create dummy sourcefile
-file(WRITE ${FIRMWARE_NAME}.cpp "// Do not edit")
-
-set(${FIRMWARE_NAME}_SRCS
- #test.cpp
- ${FIRMWARE_NAME}.cpp
- ) # Firmware sources
-
-set(${FIRMWARE_NAME}_HDRS
- APM_Config.h
- APM_Config_mavlink_hil.h
- APM_Config_xplane.h
- config.h
- defines.h
- GCS.h
- HIL.h
- Mavlink_Common.h
- Parameters.h
- ) # Firmware sources
-
-set(${FIRMWARE_NAME}_LIBS
- DataFlash
- AP_Math
- PID
- RC_Channel
- AP_OpticalFlow
- ModeFilter
- memcheck
- #AP_PID
- APM_PI
- #APO
- FastSerial
- AP_Common
- GCS_MAVLink
- AP_GPS
- APM_RC
- AP_DCM
- AP_ADC
- AP_Compass
- AP_IMU
- AP_RangeFinder
- APM_BMP085
- c
- m
-)
-
-#${CONSOLE_PORT}
-set(${FIRMWARE_NAME}_PORT COM2) # Serial upload port
-set(${FIRMWARE_NAME}_SERIAL putty -serial COM2 -sercfg 57600,8,n,1,X ) # Serial terminal cmd
-
-include_directories(
-${CMAKE_SOURCE_DIR}/libraries/DataFlash
-${CMAKE_SOURCE_DIR}/libraries/AP_Math
-${CMAKE_SOURCE_DIR}/libraries/PID
-${CMAKE_SOURCE_DIR}/libraries/AP_Common
-${CMAKE_SOURCE_DIR}/libraries/RC_Channel
-${CMAKE_SOURCE_DIR}/libraries/AP_OpticalFlow
-${CMAKE_SOURCE_DIR}/libraries/ModeFilter
-${CMAKE_SOURCE_DIR}/libraries/memcheck
-#${CMAKE_SOURCE_DIR}/libraries/AP_PID
-${CMAKE_SOURCE_DIR}/libraries/APM_PI
-${CMAKE_SOURCE_DIR}/libraries/FastSerial
-${CMAKE_SOURCE_DIR}/libraries/AP_Compass
-${CMAKE_SOURCE_DIR}/libraries/AP_RangeFinder
-${CMAKE_SOURCE_DIR}/libraries/AP_GPS
-${CMAKE_SOURCE_DIR}/libraries/AP_IMU
-${CMAKE_SOURCE_DIR}/libraries/AP_ADC
-${CMAKE_SOURCE_DIR}/libraries/AP_DCM
-${CMAKE_SOURCE_DIR}/libraries/APM_RC
-${CMAKE_SOURCE_DIR}/libraries/GCS_MAVLink
-${CMAKE_SOURCE_DIR}/libraries/APM_BMP085
-)
-#====================================================================#
-# Target generation #
-#====================================================================#
-generate_arduino_firmware(${FIRMWARE_NAME})
diff --git a/ArduCopter/GCS.h b/ArduCopter/GCS.h
index 5f999f6ca2..7172eeaf52 100644
--- a/ArduCopter/GCS.h
+++ b/ArduCopter/GCS.h
@@ -152,6 +152,7 @@ private:
uint16_t waypoint_count;
uint32_t waypoint_timelast_send; // milliseconds
uint32_t waypoint_timelast_receive; // milliseconds
+ uint32_t waypoint_timelast_request; // milliseconds
uint16_t waypoint_send_timeout; // milliseconds
uint16_t waypoint_receive_timeout; // milliseconds
diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde
index ce351f2987..1f4a5c10bd 100644
--- a/ArduCopter/GCS_Mavlink.pde
+++ b/ArduCopter/GCS_Mavlink.pde
@@ -572,18 +572,26 @@ GCS_MAVLINK::update(void)
send_message(MSG_NEXT_PARAM);
}
+ if (!waypoint_receiving && !waypoint_sending) {
+ return;
+ }
+
+ uint32_t tnow = millis();
+
if (waypoint_receiving &&
- waypoint_request_i <= (unsigned)g.waypoint_total) {
+ waypoint_request_i <= (unsigned)g.waypoint_total &&
+ tnow > waypoint_timelast_request + 500) {
+ waypoint_timelast_request = tnow;
send_message(MSG_NEXT_WAYPOINT);
}
// stop waypoint sending if timeout
- if (waypoint_sending && (millis() - waypoint_timelast_send) > waypoint_send_timeout){
+ if (waypoint_sending && (tnow - waypoint_timelast_send) > waypoint_send_timeout){
waypoint_sending = false;
}
// stop waypoint receiving if timeout
- if (waypoint_receiving && (millis() - waypoint_timelast_receive) > waypoint_receive_timeout){
+ if (waypoint_receiving && (tnow - waypoint_timelast_receive) > waypoint_receive_timeout){
waypoint_receiving = false;
}
}
@@ -1151,6 +1159,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
waypoint_receiving = true;
waypoint_sending = false;
waypoint_request_i = 0;
+ waypoint_timelast_request = 0;
break;
}
@@ -1296,6 +1305,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// update waypoint receiving state machine
waypoint_timelast_receive = millis();
+ waypoint_timelast_request = 0;
waypoint_request_i++;
if (waypoint_request_i > (uint16_t)g.waypoint_total){
diff --git a/ArduPlane/.cproject b/ArduPlane/.cproject
deleted file mode 100644
index f25b686356..0000000000
--- a/ArduPlane/.cproject
+++ /dev/null
@@ -1,468 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- make
-
-
- true
- true
- true
-
-
-
-
-
-
-
-
-
diff --git a/ArduPlane/.gitignore b/ArduPlane/.gitignore
deleted file mode 100644
index 733b1fe2ff..0000000000
--- a/ArduPlane/.gitignore
+++ /dev/null
@@ -1 +0,0 @@
-ArduPlane.cpp
diff --git a/ArduPlane/.project b/ArduPlane/.project
deleted file mode 100644
index def98a75a5..0000000000
--- a/ArduPlane/.project
+++ /dev/null
@@ -1,80 +0,0 @@
-
-
- ArduPilotMega
-
-
- libraries
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
- ?name?
-
-
-
- org.eclipse.cdt.make.core.append_environment
- true
-
-
- org.eclipse.cdt.make.core.autoBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.buildArguments
-
-
-
- org.eclipse.cdt.make.core.buildCommand
- make
-
-
- org.eclipse.cdt.make.core.cleanBuildTarget
- clean
-
-
- org.eclipse.cdt.make.core.contents
- org.eclipse.cdt.make.core.activeConfigSettings
-
-
- org.eclipse.cdt.make.core.enableAutoBuild
- false
-
-
- org.eclipse.cdt.make.core.enableCleanBuild
- true
-
-
- org.eclipse.cdt.make.core.enableFullBuild
- true
-
-
- org.eclipse.cdt.make.core.fullBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.stopOnError
- true
-
-
- org.eclipse.cdt.make.core.useDefaultBuildCmd
- true
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
-
-
diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index 55d2e2b93a..95cd4bf307 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -42,6 +42,7 @@ version 2.1 of the License, or (at your option) any later version.
#include // Range finder library
#include
#include // APM relay
+#include // Camera/Antenna mount
#include // MAVLink GCS definitions
#include
@@ -404,6 +405,13 @@ static float load; // % MCU cycles used
AP_Relay relay;
+// Camera/Antenna mount tracking and stabilisation stuff
+// --------------------------------------
+#if MOUNT == ENABLED
+AP_Mount camera_mount(g_gps, &dcm);
+#endif
+
+
////////////////////////////////////////////////////////////////////////////////
// Top-level logic
////////////////////////////////////////////////////////////////////////////////
@@ -529,6 +537,10 @@ static void fast_loop()
static void medium_loop()
{
+#if MOUNT == ENABLED
+ camera_mount.update_mount_position();
+#endif
+
// This is the start of the medium (10 Hz) loop pieces
// -----------------------------------------
switch(medium_loopCounter) {
@@ -669,6 +681,9 @@ static void slow_loop()
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
+#if MOUNT == ENABLED
+ camera_mount.update_mount_type();
+#endif
break;
case 2:
diff --git a/ArduPlane/CMakeLists.txt b/ArduPlane/CMakeLists.txt
deleted file mode 100644
index 9b53e492be..0000000000
--- a/ArduPlane/CMakeLists.txt
+++ /dev/null
@@ -1,168 +0,0 @@
-#=============================================================================#
-# Author: Niklaa Goddemeier & Sebastian Rohde #
-# Date: 04.09.2011 #
-#=============================================================================#
-
-set(CMAKE_SOURCE_DIR "${CMAKE_SOURCE_DIR}/../")
-
-set(CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/modules) # CMake module search path
-set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Arduino.cmake) # Arduino Toolchain
-#include(ArduinoProcessing)
-
-set (CMAKE_CXX_SOURCE_FILE_EXTENSIONS pde)
-
-
-message(STATUS "DIR: ${CMAKE_SOURCE_DIR}")
-
-cmake_minimum_required(VERSION 2.8)
-#====================================================================#
-# Setup Project #
-#====================================================================#
-project(ArduPlane C CXX)
-
-find_package(Arduino 22 REQUIRED)
-
-if (NOT DEFINED BOARD)
- message(STATUS "board not defined, assuming mega, use cmake -DBOARD=mega2560 , etc. to specify")
- set(BOARD "mega")
-endif()
-message(STATUS "Board configured as: ${BOARD}")
-
-add_subdirectory(../libraries "${CMAKE_CURRENT_BINARY_DIR}/libs")
-
-#add_subdirectory(${CMAKE_SOURCE_DIR}/ArduCopter)
-#add_subdirectory(testtool)
-
-PRINT_BOARD_SETTINGS(${BOARD})
-
-
-
-#=============================================================================#
-# Author: Niklas Goddemeier & Sebastian Rohde #
-# Date: 04.09.2011 #
-#=============================================================================#
-
-
-#====================================================================#
-# Settings #
-#====================================================================#
-set(FIRMWARE_NAME ArduPlane)
-
-set(${FIRMWARE_NAME}_BOARD ${BOARD}) # Arduino Target board
-
-set(${FIRMWARE_NAME}_SKETCHES
- ArduPlane.pde
- Attitude.pde
- climb_rate.pde
- commands.pde
- commands_logic.pde
- commands_process.pde
- control_modes.pde
- events.pde
- #flip.pde
- #GCS.pde
- #GCS_Ardupilot.pde
- #GCS_IMU_output.pde
- #GCS_Jason_text.pde
- GCS_Mavlink.pde
- #GCS_Standard.pde
- #GCS_Xplane.pde
- #heli.pde
- #HIL_Xplane.pde
- #leds.pde
- Log.pde
- #motors_hexa.pde
- #motors_octa.pde
- #motors_octa_quad.pde
- #motors_quad.pde
- #motors_tri.pde
- #motors_y6.pde
- navigation.pde
- planner.pde
- radio.pde
- #read_commands.pde
- sensors.pde
- setup.pde
- system.pde
- test.pde
- ) # Firmware sketches
-
-#create dummy sourcefile
-file(WRITE ${FIRMWARE_NAME}.cpp "// Do not edit")
-
-set(${FIRMWARE_NAME}_SRCS
- #test.cpp
- ${FIRMWARE_NAME}.cpp
- ) # Firmware sources
-
-set(${FIRMWARE_NAME}_HDRS
- APM_Config.h
- APM_Config_mavlink_hil.h
- #APM_Config_xplane.h
- config.h
- defines.h
- GCS.h
- #HIL.h
- #Mavlink_Common.h
- Parameters.h
- ) # Firmware sources
-
-set(${FIRMWARE_NAME}_LIBS
- DataFlash
- AP_Math
- PID
- RC_Channel
- AP_OpticalFlow
- ModeFilter
- memcheck
- #AP_PID
- APM_PI
- #APO
- FastSerial
- AP_Common
- GCS_MAVLink
- AP_GPS
- APM_RC
- AP_DCM
- AP_ADC
- AP_Compass
- AP_IMU
- AP_RangeFinder
- APM_BMP085
- c
- m
-)
-
-#${CONSOLE_PORT}
-set(${FIRMWARE_NAME}_PORT COM2) # Serial upload port
-set(${FIRMWARE_NAME}_SERIAL putty -serial COM2 -sercfg 57600,8,n,1,X ) # Serial terminal cmd
-
-include_directories(
-${CMAKE_SOURCE_DIR}/libraries/DataFlash
-${CMAKE_SOURCE_DIR}/libraries/AP_Math
-${CMAKE_SOURCE_DIR}/libraries/PID
-${CMAKE_SOURCE_DIR}/libraries/AP_Common
-${CMAKE_SOURCE_DIR}/libraries/RC_Channel
-${CMAKE_SOURCE_DIR}/libraries/AP_OpticalFlow
-${CMAKE_SOURCE_DIR}/libraries/ModeFilter
-${CMAKE_SOURCE_DIR}/libraries/memcheck
-#${CMAKE_SOURCE_DIR}/libraries/AP_PID
-${CMAKE_SOURCE_DIR}/libraries/APM_PI
-${CMAKE_SOURCE_DIR}/libraries/FastSerial
-${CMAKE_SOURCE_DIR}/libraries/AP_Compass
-${CMAKE_SOURCE_DIR}/libraries/AP_RangeFinder
-${CMAKE_SOURCE_DIR}/libraries/AP_GPS
-${CMAKE_SOURCE_DIR}/libraries/AP_IMU
-${CMAKE_SOURCE_DIR}/libraries/AP_ADC
-${CMAKE_SOURCE_DIR}/libraries/AP_DCM
-${CMAKE_SOURCE_DIR}/libraries/APM_RC
-${CMAKE_SOURCE_DIR}/libraries/GCS_MAVLink
-${CMAKE_SOURCE_DIR}/libraries/APM_BMP085
-#new
-#${CMAKE_SOURCE_DIR}/libraries/Wire
-#${CMAKE_SOURCE_DIR}/libraries/SPI
-)
-#====================================================================#
-# Target generation #
-#====================================================================#
-generate_arduino_firmware(${FIRMWARE_NAME})
diff --git a/ArduPlane/GCS.h b/ArduPlane/GCS.h
index 5f999f6ca2..7172eeaf52 100644
--- a/ArduPlane/GCS.h
+++ b/ArduPlane/GCS.h
@@ -152,6 +152,7 @@ private:
uint16_t waypoint_count;
uint32_t waypoint_timelast_send; // milliseconds
uint32_t waypoint_timelast_receive; // milliseconds
+ uint32_t waypoint_timelast_request; // milliseconds
uint16_t waypoint_send_timeout; // milliseconds
uint16_t waypoint_receive_timeout; // milliseconds
diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde
index 22bbd0dfe3..20c2043c25 100644
--- a/ArduPlane/GCS_Mavlink.pde
+++ b/ArduPlane/GCS_Mavlink.pde
@@ -28,16 +28,11 @@ static bool mavlink_active;
static NOINLINE void send_heartbeat(mavlink_channel_t chan)
{
#ifdef MAVLINK10
- uint8_t base_mode = 0;
+ uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
uint8_t system_status = MAV_STATE_ACTIVE;
+ uint32_t custom_mode = control_mode;
- // we map the custom_mode to our internal mode plus 16, to lower
- // the chance that a ground station will give us 0 and we
- // interpret it as manual. This is necessary as the SET_MODE
- // command has no way to indicate that the custom_mode is filled in
- uint32_t custom_mode = control_mode + 16;
-
- // work out the base_mode. This value is almost completely useless
+ // work out the base_mode. This value is not very useful
// for APM, but we calculate it as best we can so a generic
// MAVLink enabled ground station can work out something about
// what the MAV is up to. The actual bit values are highly
@@ -93,6 +88,9 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
}
+ // indicate we have set a custom mode
+ base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
+
mavlink_msg_heartbeat_send(
chan,
MAV_TYPE_FIXED_WING,
@@ -284,7 +282,6 @@ static void NOINLINE send_meminfo(mavlink_channel_t chan)
static void NOINLINE send_location(mavlink_channel_t chan)
{
Matrix3f rot = dcm.get_dcm_matrix(); // neglecting angle of attack for now
-#ifdef MAVLINK10
mavlink_msg_global_position_int_send(
chan,
millis(),
@@ -296,16 +293,6 @@ static void NOINLINE send_location(mavlink_channel_t chan)
g_gps->ground_speed * rot.b.x, // Y speed cm/s
g_gps->ground_speed * rot.c.x,
g_gps->ground_course); // course in 1/100 degree
-#else // MAVLINK10
- mavlink_msg_global_position_int_send(
- chan,
- current_loc.lat,
- current_loc.lng,
- current_loc.alt * 10,
- g_gps->ground_speed * rot.a.x,
- g_gps->ground_speed * rot.b.x,
- g_gps->ground_speed * rot.c.x);
-#endif // MAVLINK10
}
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
@@ -366,7 +353,6 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
// normalized values scaled to -10000 to 10000
// This is used for HIL. Do not change without discussing with
// HIL maintainers
-#ifdef MAVLINK10
mavlink_msg_rc_channels_scaled_send(
chan,
millis(),
@@ -380,26 +366,11 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
0,
0,
rssi);
-
-#else // MAVLINK10
- mavlink_msg_rc_channels_scaled_send(
- chan,
- 10000 * g.channel_roll.norm_output(),
- 10000 * g.channel_pitch.norm_output(),
- 10000 * g.channel_throttle.norm_output(),
- 10000 * g.channel_rudder.norm_output(),
- 0,
- 0,
- 0,
- 0,
- rssi);
-#endif // MAVLINK10
}
static void NOINLINE send_radio_in(mavlink_channel_t chan)
{
uint8_t rssi = 1;
-#ifdef MAVLINK10
mavlink_msg_rc_channels_raw_send(
chan,
millis(),
@@ -413,25 +384,10 @@ static void NOINLINE send_radio_in(mavlink_channel_t chan)
g.rc_7.radio_in,
g.rc_8.radio_in,
rssi);
-
-#else // MAVLINK10
- mavlink_msg_rc_channels_raw_send(
- chan,
- g.channel_roll.radio_in,
- g.channel_pitch.radio_in,
- g.channel_throttle.radio_in,
- g.channel_rudder.radio_in,
- g.rc_5.radio_in, // XXX currently only 4 RC channels defined
- g.rc_6.radio_in,
- g.rc_7.radio_in,
- g.rc_8.radio_in,
- rssi);
-#endif // MAVLINK10
}
static void NOINLINE send_radio_out(mavlink_channel_t chan)
{
-#ifdef MAVLINK10
mavlink_msg_servo_output_raw_send(
chan,
micros(),
@@ -444,18 +400,6 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
g.rc_6.radio_out,
g.rc_7.radio_out,
g.rc_8.radio_out);
-#else // MAVLINK10
- mavlink_msg_servo_output_raw_send(
- chan,
- g.channel_roll.radio_out,
- g.channel_pitch.radio_out,
- g.channel_throttle.radio_out,
- g.channel_rudder.radio_out,
- g.rc_5.radio_out, // XXX currently only 4 RC channels defined
- g.rc_6.radio_out,
- g.rc_7.radio_out,
- g.rc_8.radio_out);
-#endif // MAVLINK10
}
static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
@@ -748,11 +692,7 @@ void mavlink_send_text(mavlink_channel_t chan, gcs_severity severity, const char
mavlink_send_message(chan, MSG_STATUSTEXT, 0);
} else {
// send immediately
-#ifdef MAVLINK10
mavlink_msg_statustext_send(chan, severity, str);
-#else
- mavlink_msg_statustext_send(chan, severity, (const int8_t*) str);
-#endif
}
}
@@ -837,8 +777,15 @@ GCS_MAVLINK::update(void)
send_message(MSG_NEXT_PARAM);
}
+ if (!waypoint_receiving && !waypoint_sending) {
+ return;
+ }
+
+ uint32_t tnow = millis();
+
if (waypoint_receiving &&
- waypoint_request_i <= (unsigned)g.command_total) {
+ waypoint_request_i <= (unsigned)g.command_total &&
+ tnow > waypoint_timelast_request + 500) {
send_message(MSG_NEXT_WAYPOINT);
}
@@ -1198,13 +1145,13 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_msg_set_mode_decode(msg, &packet);
#ifdef MAVLINK10
- // we ignore base_mode as there is no sane way to map
- // from that bitmap to a APM flight mode. We rely on
- // custom_mode instead.
- // see comment on custom_mode above
- int16_t adjusted_mode = packet.custom_mode - 16;
-
- switch (adjusted_mode) {
+ if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
+ // we ignore base_mode as there is no sane way to map
+ // from that bitmap to a APM flight mode. We rely on
+ // custom_mode instead.
+ break;
+ }
+ switch (packet.custom_mode) {
case MANUAL:
case CIRCLE:
case STABILIZE:
@@ -1214,7 +1161,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case AUTO:
case RTL:
case LOITER:
- set_mode(adjusted_mode);
+ set_mode(packet.custom_mode);
break;
}
@@ -1473,6 +1420,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
g.command_total.set_and_save(packet.count - 1);
waypoint_timelast_receive = millis();
+ waypoint_timelast_request = 0;
waypoint_receiving = true;
waypoint_sending = false;
waypoint_request_i = 0;
@@ -1649,6 +1597,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// update waypoint receiving state machine
waypoint_timelast_receive = millis();
+ waypoint_timelast_request = 0;
waypoint_request_i++;
if (waypoint_request_i > (uint16_t)g.command_total){
@@ -1731,7 +1680,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// we send the value we actually set, which could be
// different from the value sent, in case someone sent
// a fractional value to an integer type
-#ifdef MAVLINK10
mavlink_msg_param_value_send(
chan,
key,
@@ -1739,14 +1687,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mav_var_type(vp->meta_type_id()),
_count_parameters(),
-1); // XXX we don't actually know what its index is...
-#else // MAVLINK10
- mavlink_msg_param_value_send(
- chan,
- (int8_t *)key,
- vp->cast_to_float(),
- _count_parameters(),
- -1); // XXX we don't actually know what its index is...
-#endif // MAVLINK10
}
break;
@@ -1828,7 +1768,48 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
airspeed = 100*packet.airspeed;
break;
}
+#ifdef MAVLINK10
+ case MAVLINK_MSG_ID_HIL_STATE:
+ {
+ mavlink_hil_state_t packet;
+ mavlink_msg_hil_state_decode(msg, &packet);
+
+ float vel = sqrt((packet.vx * packet.vx) + (packet.vy * packet.vy));
+ float cog = wrap_360(ToDeg(atan2(packet.vx, packet.vy)) * 100);
+
+ // set gps hil sensor
+ g_gps->setHIL(packet.time_usec/1000.0,
+ packet.lat*1.0e-7, packet.lon*1.0e-7, packet.alt*1.0e-3,
+ vel*1.0e-2, cog*1.0e-2, 0, 0);
+
+ #if HIL_MODE == HIL_MODE_SENSORS
+
+ // rad/sec
+ Vector3f gyros;
+ gyros.x = (float)packet.xgyro / 1000.0;
+ gyros.y = (float)packet.ygyro / 1000.0;
+ gyros.z = (float)packet.zgyro / 1000.0;
+ // m/s/s
+ Vector3f accels;
+ accels.x = (float)packet.xacc / 1000.0;
+ accels.y = (float)packet.yacc / 1000.0;
+ accels.z = (float)packet.zacc / 1000.0;
+ imu.set_gyro(gyros);
+
+ imu.set_accel(accels);
+
+ #else
+
+ // set dcm hil sensor
+ dcm.setHil(packet.roll,packet.pitch,packet.yaw,packet.rollspeed,
+ packet.pitchspeed,packet.yawspeed);
+
+ #endif
+
+ break;
+ }
+#endif // MAVLINK10
#endif
#if HIL_MODE == HIL_MODE_ATTITUDE
case MAVLINK_MSG_ID_ATTITUDE:
@@ -1890,6 +1871,26 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
#endif // HIL_MODE
+
+#if MOUNT == ENABLED
+ case MAVLINK_MSG_ID_MOUNT_CONFIGURE:
+ {
+ camera_mount.configure_msg(msg);
+ break;
+ }
+
+ case MAVLINK_MSG_ID_MOUNT_CONTROL:
+ {
+ camera_mount.control_msg(msg);
+ break;
+ }
+
+ case MAVLINK_MSG_ID_MOUNT_STATUS:
+ {
+ camera_mount.status_msg(msg);
+ break;
+ }
+#endif // MOUNT == ENABLED
} // end switch
} // end handle mavlink
@@ -1959,7 +1960,6 @@ GCS_MAVLINK::queued_param_send()
char param_name[ONBOARD_PARAM_NAME_LENGTH]; /// XXX HACK
vp->copy_name(param_name, sizeof(param_name));
-#ifdef MAVLINK10
mavlink_msg_param_value_send(
chan,
param_name,
@@ -1967,14 +1967,6 @@ GCS_MAVLINK::queued_param_send()
mav_var_type(vp->meta_type_id()),
_queued_parameter_count,
_queued_parameter_index);
-#else // MAVLINK10
- mavlink_msg_param_value_send(
- chan,
- (int8_t*)param_name,
- value,
- _queued_parameter_count,
- _queued_parameter_index);
-#endif // MAVLINK10
_queued_parameter_index++;
}
diff --git a/ArduPlane/Mavlink_compat.h b/ArduPlane/Mavlink_compat.h
index a9884bf780..267c73832e 100644
--- a/ArduPlane/Mavlink_compat.h
+++ b/ArduPlane/Mavlink_compat.h
@@ -72,10 +72,101 @@ static uint8_t mav_var_type(AP_Meta_class::Type_id t)
#else
+static uint8_t mav_var_type(AP_Meta_class::Type_id t)
+{
+ return 0;
+}
+
#define MAV_MISSION_ACCEPTED 0
#define MAV_MISSION_UNSUPPORTED 1
#define MAV_MISSION_UNSUPPORTED_FRAME 1
#define MAV_MISSION_ERROR 1
#define MAV_MISSION_INVALID_SEQUENCE 1
+/*
+ some functions have some extra params in MAVLink 1.0
+ */
+
+static void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon,
+ int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy,
+ int16_t vz, uint16_t hdg)
+{
+ mavlink_msg_global_position_int_send(
+ chan,
+ lat,
+ lon,
+ alt,
+ vx, vy, vz);
+}
+
+static void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port,
+ int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled,
+ int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled,
+ int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
+{
+ mavlink_msg_rc_channels_scaled_send(
+ chan,
+ chan1_scaled,
+ chan2_scaled,
+ chan3_scaled,
+ chan4_scaled,
+ chan5_scaled,
+ chan6_scaled,
+ chan7_scaled,
+ chan8_scaled,
+ rssi);
+}
+
+static void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port,
+ uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw,
+ uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw,
+ uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
+{
+ mavlink_msg_rc_channels_raw_send(
+ chan,
+ chan1_raw,
+ chan2_raw,
+ chan3_raw,
+ chan4_raw,
+ chan5_raw,
+ chan6_raw,
+ chan7_raw,
+ chan8_raw,
+ rssi);
+}
+
+
+static void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port,
+ uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw,
+ uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw,
+ uint16_t servo7_raw, uint16_t servo8_raw)
+{
+ mavlink_msg_servo_output_raw_send(
+ chan,
+ servo1_raw,
+ servo2_raw,
+ servo3_raw,
+ servo4_raw,
+ servo5_raw,
+ servo6_raw,
+ servo7_raw,
+ servo8_raw);
+}
+
+static void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text)
+{
+ mavlink_msg_statustext_send(chan, severity, (const int8_t*) text);
+}
+
+static void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id,
+ float param_value, uint8_t param_type,
+ uint16_t param_count, uint16_t param_index)
+{
+ mavlink_msg_param_value_send(
+ chan,
+ (int8_t *)param_id,
+ param_value,
+ param_count,
+ param_index);
+}
#endif
diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde
index 11145912d8..2e5524e6b1 100644
--- a/ArduPlane/commands_logic.pde
+++ b/ArduPlane/commands_logic.pde
@@ -115,6 +115,25 @@ static void handle_process_do_command()
case MAV_CMD_DO_REPEAT_RELAY:
do_repeat_relay();
break;
+
+#if MOUNT == ENABLED
+ // Sets the region of interest (ROI) for a sensor set or the
+ // vehicle itself. This can then be used by the vehicles control
+ // system to control the vehicle attitude and the attitude of various
+ // devices such as cameras.
+ // |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
+ case MAV_CMD_DO_SET_ROI:
+ camera_mount.set_roi_cmd();
+ break;
+
+ case MAV_CMD_DO_MOUNT_CONFIGURE: // Mission command to configure a camera mount |Mount operation mode (see MAV_CONFIGURE_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|
+ camera_mount.configure_cmd();
+ break;
+
+ case MAV_CMD_DO_MOUNT_CONTROL: // Mission command to control a camera mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty|
+ camera_mount.control_cmd();
+ break;
+#endif
}
}
diff --git a/ArduPlane/commands_process.pde b/ArduPlane/commands_process.pde
index 5ef18b36b1..a5dcffcc82 100644
--- a/ArduPlane/commands_process.pde
+++ b/ArduPlane/commands_process.pde
@@ -50,7 +50,7 @@ static void process_next_command()
// and loads conditional or immediate commands if applicable
struct Location temp;
- byte old_index;
+ byte old_index = 0;
// these are Navigation/Must commands
// ---------------------------------
diff --git a/ArduPlane/config.h b/ArduPlane/config.h
index 692c016136..7b7c6d0b76 100644
--- a/ArduPlane/config.h
+++ b/ArduPlane/config.h
@@ -331,6 +331,20 @@
# define ELEVON_CH2_REVERSE DISABLED
#endif
+//////////////////////////////////////////////////////////////////////////////
+// MOUNT (ANTENNA OR CAMERA)
+//
+#ifndef MOUNT
+# define MOUNT DISABLED
+#endif
+
+#if defined( __AVR_ATmega1280__ ) && CAMERA == ENABLED
+// The small ATmega1280 chip does not have enough memory for camera support
+// so disable CLI, this will allow camera support and other improvements to fit.
+// This should almost have no side effects, because the APM planner can now do a complete board setup.
+#define CLI_ENABLED DISABLED
+#endif
+
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
diff --git a/ArduRover/.cproject b/ArduRover/.cproject
deleted file mode 100644
index 7a4dd5232b..0000000000
--- a/ArduRover/.cproject
+++ /dev/null
@@ -1,46 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/ArduRover/.project b/ArduRover/.project
deleted file mode 100644
index 4494bc9869..0000000000
--- a/ArduRover/.project
+++ /dev/null
@@ -1,79 +0,0 @@
-
-
- ArduRover
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
- ?name?
-
-
-
- org.eclipse.cdt.make.core.append_environment
- true
-
-
- org.eclipse.cdt.make.core.autoBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.buildArguments
-
-
-
- org.eclipse.cdt.make.core.buildCommand
- make
-
-
- org.eclipse.cdt.make.core.cleanBuildTarget
- clean
-
-
- org.eclipse.cdt.make.core.contents
- org.eclipse.cdt.make.core.activeConfigSettings
-
-
- org.eclipse.cdt.make.core.enableAutoBuild
- false
-
-
- org.eclipse.cdt.make.core.enableCleanBuild
- true
-
-
- org.eclipse.cdt.make.core.enableFullBuild
- true
-
-
- org.eclipse.cdt.make.core.fullBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.stopOnError
- true
-
-
- org.eclipse.cdt.make.core.useDefaultBuildCmd
- true
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
-
-
diff --git a/ArduRover/ArduRover.cpp b/ArduRover/ArduRover.cpp
deleted file mode 100644
index 3341f3e598..0000000000
--- a/ArduRover/ArduRover.cpp
+++ /dev/null
@@ -1,26 +0,0 @@
-// Libraries
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-// Vehicle Configuration
-#include "CarStampede.h"
-
-// ArduPilotOne Default Setup
-#include "APO_DefaultSetup.h"
-
-#include ; int main(void) {init();setup();for(;;) loop(); return 0; }
-// vim:ts=4:sw=4:expandtab
diff --git a/CMakeLists.txt b/CMakeLists.txt
index fc36d92527..4c54fc7836 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,4 +1,4 @@
-cmake_minimum_required(VERSION 2.8)
+cmake_minimum_required(VERSION 2.8.5)
set(CMAKE_MODULE_PATH ${CMAKE_SOURCE_DIR}/cmake/modules)
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Arduino.cmake)
@@ -42,6 +42,12 @@ if (NOT DEFINED BOARD)
set(BOARD "mega")
endif()
+if (NOT DEFINED PORT)
+ message(STATUS "please define the upload port (for example: cmake
+ -DPORT=/dev/ttyUSB0, assuming /dev/ttyUSB0")
+ set(PORT "/dev/ttyUSB0")
+endif()
+
# cpack settings
set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "A universal autopilot system for the ArduPilotMega board.")
set(CPACK_PACKAGE_VENDOR "DIYDRONES")
@@ -72,31 +78,84 @@ if (NOT DEFINED BOARD)
endif()
message(STATUS "Board configured as: ${BOARD}")
-set (CMAKE_CXX_SOURCE_FILE_EXTENSIONS pde)
+# add a sketch
+macro(add_sketch SKETCH_NAME BOARD PORT)
-# standard apm project setup
-macro(apm_project PROJECT_NAME BOARD SRCS)
- message(STATUS "creating apo project ${PROJECT_NAME}")
- set(${PROJECT_NAME}_BOARD ${BOARD})
- set(${PROJECT_NAME}_AFLAGS "-assembler-with-cpp")
- file(GLOB HDRS ${PROJECT_NAME}/*.h)
- file(GLOB PDE ${PROJECT_NAME}/*.pde)
- set(${PROJECT_NAME}_SRCS ${SRCS} ${HDRS} ${PDE})
- set(${PROJECT_NAME}_LIBS c)
- message(STATUS "sources: ${SRCS}")
- message(STATUS "headers: ${HDRS}")
- message(STATUS "pde: ${PDE}")
- generate_arduino_firmware(${PROJECT_NAME})
- set_target_properties(${PROJECT_NAME} PROPERTIES LINKER_LANGUAGE CXX)
+ message(STATUS "Generating sketch ${SKETCH_NAME}")
+
+ # files
+ set(SKETCH_CPP ${CMAKE_CURRENT_BINARY_DIR}/${SKETCH_NAME}/${SKETCH_NAME}.cpp)
+ set(SKETCH_PDE ${CMAKE_CURRENT_SOURCE_DIR}/${SKETCH_NAME}/${SKETCH_NAME}.pde)
+ message(STATUS "SKETCH_PDE:\n${SKETCH_PDE}")
+ message(STATUS "SKETCH_CPP:\n${SKETCH_CPP}")
+
+ # settings
+ set(${SKETCH_NAME}_BOARD ${BOARD})
+ set(${SKETCH_NAME}_PORT ${PORT})
+ set(${SKETCH_NAME}_SRCS ${SKETCH_CPP})
+ set(${SKETCH_NAME}_LIBS m c)
+
+ # find pde files
+ file(GLOB PDE_SOURCES ${SKETCH_NAME}/*.pde)
+
+ # find the head of the main pde
+ file(WRITE ${SKETCH_CPP} "// automatically generated by arduino-cmake\n")
+ file(READ ${SKETCH_PDE} FILE)
+
+ string(FIND "${FILE}" "#include" POS1 REVERSE)
+ string(LENGTH "${FILE}" FILE_LENGTH)
+ math(EXPR LENGTH_STR1 "${FILE_LENGTH}-${POS1}")
+ string(SUBSTRING "${FILE}" ${POS1} ${LENGTH_STR1} STR1)
+ string(FIND "${STR1}" "\n" POS2)
+ math(EXPR POS3 "${POS1}+${POS2}")
+ string(SUBSTRING "${FILE}" 0 ${POS3} FILE_HEAD)
+ message(STATUS "FILE_HEAD:\n${FILE_HEAD}")
+
+ # find the body of the main pde
+ math(EXPR BODY_LENGTH "${FILE_LENGTH}-${POS3}-1")
+ string(SUBSTRING "${FILE}" "${POS3}+1" "${BODY_LENGTH}" FILE_BODY)
+ message(STATUS "BODY:\n${FILE_BODY}")
+
+ # write the file head
+ file(APPEND ${SKETCH_CPP} "${FILE_HEAD}")
+ file(APPEND ${SKETCH_CPP} "\n#include \"WProgram.h\"\n")
+
+ # write prototypes
+ foreach(PDE ${PDE_SOURCES})
+ message(STATUS "pde: ${PDE}")
+ file(READ ${PDE} 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};")
+ endforeach()
+ endforeach()
+
+
+ # write source
+ file(APPEND ${SKETCH_CPP} "\n${FILE_BODY}")
+ list(REMOVE_ITEM PDE_SOURCES ${SKETCH_PDE})
+ list(SORT PDE_SOURCES)
+ foreach (PDE ${PDE_SOURCES})
+ file(READ ${PDE} FILE)
+ file(APPEND ${SKETCH_CPP} "${FILE}")
+ endforeach()
+
+ # generate firmware
+ include_directories(${CMAKE_CURRENT_SOURCE_DIR}/${SKETCH_NAME})
+ generate_arduino_firmware(${SKETCH_NAME})
+ set_target_properties(${SKETCH_NAME} PROPERTIES LINKER_LANGUAGE CXX)
+
+ # install settings
install(FILES
- ${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}.hex
+ ${CMAKE_CURRENT_BINARY_DIR}/${SKETCH_NAME}.hex
DESTINATION bin
)
endmacro()
# projects
-apm_project(apo ${BOARD} apo/apo.cpp)
-apm_project(ArduRover ${BOARD} ArduRover/ArduRover.cpp)
-apm_project(ArduBoat ${BOARD} ArduBoat/ArduBoat.cpp)
-#apm_project(ArduPlane ${BOARD} ArduPlane/ArduPlane.cpp)
-#apm_project(ArduCopter ${BOARD} ArduCopter/ArduCopter.cpp)
+add_sketch(apo ${BOARD} ${PORT})
+add_sketch(ArduRover ${BOARD} ${PORT})
+add_sketch(ArduBoat ${BOARD} ${PORT})
+add_sketch(ArduPlane ${BOARD} ${PORT})
+#add_sketch(ArduCopter ${BOARD} ${PORT})
diff --git a/README.txt b/README.txt
index b8f91718d6..50d0d38478 100644
--- a/README.txt
+++ b/README.txt
@@ -17,6 +17,55 @@ Building using cmake
- cmake ..
- make (will build every sketch)
- make ArduPlane (will build just ArduPlane etc.)
+
+Building using eclipse
+-----------------------------------------------
+
+ Getting the Source:
+
+ assuming source located here: /home/name/apm-src
+ You can either download it or grab it from git:
+ git clone https://code.google.com/p/ardupilot-mega/ /home/name/apm-src
+
+ Generating the Eclipse Project for Your System:
+
+ mkdir /home/name/apm-build
+ cd /home/name/apm-build
+ cmake -G"Eclipse CDT4 - Unix Makefiles" -D CMAKE_BUILD_TYPE=Debug ../apm-src -D BOARD=mega -D PORT=/dev/ttyUSB0
+
+ Note: Unix can be substituted for MinGW/ MSYS/ NMake (for windows)
+ (see http://www.vtk.org/Wiki/Eclipse_CDT4_Generator)
+
+ PORT is the port for uploading to the board, COM0 etc on windows.
+ BOARD is your board type, mega for the 1280 or mega2560 for the 2560 boards.
+
+ Importing the Eclipse Build Project:
+
+ Import project using Menu File->Import
+ Select General->Existing projects into workspace:
+ Browse where your build tree is and select the root build tree directory.
+ Keep "Copy projects into workspace" unchecked.
+ You get a fully functional eclipse project
+
+ Importing the Eclipse Source Project:
+
+ You can also import the source repository (/home/name/apm-src) if you want to modify the source/ commit using git.
+
+ Settings up Eclipse to Recognize PDE files:
+
+ Window > Preferences > General > Content Types. This tree associates a
+ filename or filename pattern with its content type so that tools can treat it
+ properly. Source and header files for most languages are under the Text tree.
+ Add "*.pde" as a C++ Source.
+
+ Autocompletion:
+
+ Right click on source project -> Properties -> Project References -> apm-build Project
+
+ Advanced:
+
+ * Regenerating the eclipse source project file:
+ cmake -G"Eclipse CDT4 - Unix Makefiles" -DECLIPSE_CDT4_GENERATE_SOURCE_PROJECT=TRUE /home/name/apm-src
Build a package using cpack
-----------------------------------------------
@@ -24,3 +73,6 @@ Build a package using cpack
- cmake ..
- make package
- make package_source
+
+
+vim:ts=4:sw=4:expandtab
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log
index 10604a699c..3e86d02fc8 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log
+++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log
@@ -5,13 +5,15 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
-/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
+/root/apm/ardupilot-mega/ArduCopter/Parameters.h:407: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)':
-/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
-/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
-/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
+/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
+/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
+/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()':
-/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
+/root/apm/ardupilot-mega/ArduCopter/heli.pde:64: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
+/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'int heli_get_scaled_throttle(int)':
+/root/apm/ardupilot-mega/ArduCopter/heli.pde:205: warning: unused variable 'scaled_throttle'
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
@@ -19,7 +21,9 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
-autogenerated: At global scope:
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:179: warning: 'int alt_hold_velocity()' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:209: warning: 'int get_angle_boost(int)' defined but not used
autogenerated:51: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:52: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:53: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
@@ -28,36 +32,39 @@ autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but nev
autogenerated:111: warning: 'void Log_Write_Control_Tuning()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/Log.pde:776: warning: 'void Log_Write_Attitude()' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/Log.pde:835: warning: 'void Log_Write_Attitude()' defined but not used
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
-autogenerated:213: warning: 'void debug_motors()' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
-autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
-autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
-autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
-autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
-autogenerated:246: warning: 'void ReadSCP1000()' declared 'static' but never defined
-autogenerated:247: warning: 'void init_barometer()' declared 'static' but never defined
-autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
-autogenerated:249: warning: 'long int read_barometer()' declared 'static' but never defined
-autogenerated:250: warning: 'void read_airspeed()' declared 'static' but never defined
-autogenerated:251: warning: 'void zero_airspeed()' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used
-autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
-autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
+autogenerated:215: warning: 'void debug_motors()' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/navigation.pde:213: warning: 'int get_loiter_angle()' defined but not used
+autogenerated:237: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
+autogenerated:238: warning: 'long int cross_track_test()' declared 'static' but never defined
+autogenerated:239: warning: 'void reset_crosstrack()' declared 'static' but never defined
+autogenerated:241: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/radio.pde:134: warning: 'void throttle_failsafe(uint16_t)' defined but not used
+autogenerated:250: warning: 'void ReadSCP1000()' declared 'static' but never defined
+autogenerated:251: warning: 'void init_barometer()' declared 'static' but never defined
+autogenerated:252: warning: 'long int read_baro_filtered()' declared 'static' but never defined
+autogenerated:253: warning: 'long int read_barometer()' declared 'static' but never defined
+autogenerated:254: warning: 'void read_airspeed()' declared 'static' but never defined
+autogenerated:255: warning: 'void zero_airspeed()' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/system.pde:456: warning: 'void set_failsafe(boolean)' defined but not used
+autogenerated:290: warning: 'void init_optflow()' declared 'static' but never defined
+autogenerated:297: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_min' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:344: warning: 'old_altitude' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:362: warning: 'abs_pressure' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:363: warning: 'ground_pressure' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:364: warning: 'ground_temperature' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:369: warning: 'baro_alt' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:347: warning: 'old_altitude' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:348: warning: 'old_rate' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:366: warning: 'abs_pressure' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:367: warning: 'ground_pressure' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:368: warning: 'ground_temperature' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:373: warning: 'baro_alt' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:389: warning: 'angle_boost' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1727: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.size.txt
index e8146f2219..8c64ea4fd3 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.size.txt
+++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.size.txt
@@ -10,6 +10,7 @@
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
+00000001 b mavlink_active
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
@@ -47,8 +48,10 @@
00000002 b loiter_sum
00000002 b event_delay
00000002 b event_value
+00000002 b CH7_wp_index
00000002 b event_repeat
00000002 b loiter_total
+00000002 b manual_boost
00000002 b nav_throttle
00000002 b x_rate_error
00000002 b y_rate_error
@@ -86,6 +89,7 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
+00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@@ -124,6 +128,7 @@
00000004 b fiftyhz_loopTimer
00000004 b old_target_bearing
00000004 b throttle_integrator
+00000004 b heli_throttle_scaler
00000004 r __menu_name__log_menu
00000004 b command_yaw_start_time
00000004 b initial_simple_bearing
@@ -284,6 +289,8 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
+0000000a V Parameters::Parameters()::__c
+0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
@@ -416,7 +423,6 @@
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r setup_heli(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
-00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
@@ -427,8 +433,8 @@
00000018 r __menu_name__main_menu
00000018 W AP_VarT::serialize(void*, unsigned int) const
00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c
+00000019 r Log_Read_Motors()::__c
0000001a r print_log_menu()::__c
-0000001a r Log_Read_Nav_Tuning()::__c
0000001b r setup_heli(unsigned char, Menu::arg const*)::__c
0000001b r report_heli()::__c
0000001c W AP_VarS >::unserialize(void*, unsigned int)
@@ -437,6 +443,7 @@
0000001c W AP_VarS >::serialize(void*, unsigned int) const
0000001c W AP_VarS >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c
+0000001d r Log_Read_Performance()::__c
0000001e r report_heli()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
@@ -446,10 +453,8 @@
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
-00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
-00000022 t reset_hold_I()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarS >::~AP_VarS()
00000022 W AP_VarS >::~AP_VarS()
@@ -459,13 +464,13 @@
00000023 r setup_heli(unsigned char, Menu::arg const*)::__c
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
+00000024 t reset_hold_I()
00000024 r setup_heli(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
-00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
@@ -476,14 +481,16 @@
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
+0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t setup_motors(unsigned char, Menu::arg const*)
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
+0000002e r init_ardupilot()::__c
+0000002e r Log_Read_Nav_Tuning()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
-0000002f r init_ardupilot()::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 B imu
@@ -496,19 +503,17 @@
00000034 t _MAV_RETURN_float
00000034 t heli_get_servo(int)
00000034 W AP_Float16::serialize(void*, unsigned int) const
-00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
+00000036 r Log_Read_Control_Tuning()::__c
00000037 r print_wp(Location*, unsigned char)::__c
-00000038 t init_throttle_cruise()
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003a B g_gps_driver
-0000003c W RC_Channel::~RC_Channel()
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 W AP_Float16::unserialize(void*, unsigned int)
@@ -517,6 +522,7 @@
00000042 t report_sonar()
00000042 r setup_heli(unsigned char, Menu::arg const*)::__c
00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
+00000046 W RC_Channel::~RC_Channel()
00000048 t change_command(unsigned char)
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
@@ -549,9 +555,9 @@
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
+00000068 W GCS_MAVLINK::~GCS_MAVLINK()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t read_num_from_serial()
-0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
00000074 t output_motors_armed()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
@@ -572,11 +578,11 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
+00000094 t init_throttle_cruise()
00000096 t print_wp(Location*, unsigned char)
+00000098 B gcs0
+00000098 B gcs3
0000009a t planner_gcs(unsigned char, Menu::arg const*)
-0000009a t Log_Read_Motors()
-0000009b B gcs0
-0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode()
@@ -585,12 +591,13 @@
000000a4 T __vector_55
000000a6 t send_servo_out(mavlink_channel_t)
000000aa t test_sonar(unsigned char, Menu::arg const*)
-000000aa t Log_Read_Nav_Tuning()
000000ab B compass
+000000ae t Log_Read_Motors()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b4 t read_radio()
000000b6 t get_log_boundaries(unsigned char, int&, int&)
+000000b6 t Log_Read_Performance()
000000be t update_events()
000000c2 t setup_compass(unsigned char, Menu::arg const*)
000000c2 t send_radio_out(mavlink_channel_t)
@@ -599,7 +606,6 @@
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t send_radio_in(mavlink_channel_t)
-000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000d0 t get_bearing(Location*, Location*)
000000d2 t print_switch(unsigned char, unsigned char, bool)
@@ -607,29 +613,31 @@
000000d4 t get_stabilize_pitch(long)
000000d4 t Log_Read(int, int)
000000d8 t test_radio(unsigned char, Menu::arg const*)
+000000de t Log_Read_Nav_Tuning()
000000e0 r test_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
-000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
+000000f8 t heli_get_angle_boost(int)
+000000fa t calc_loiter_pitch_roll()
00000100 r setup_menu_commands
+00000102 t Log_Read_Control_Tuning()
00000106 t setup_gyro(unsigned char, Menu::arg const*)
0000010a t mavlink_delay(unsigned long)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
-0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
+00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
+00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
-00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
-00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
-0000012c t calc_loiter_pitch_roll()
0000012e t arm_motors()
00000130 t report_compass()
+00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000148 t Log_Read_GPS()
00000156 t update_commands()
0000015c t update_trig()
@@ -637,38 +645,38 @@
00000160 t send_nav_controller_output(mavlink_channel_t)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
-00000168 T GCS_MAVLINK::update()
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
00000184 t test_imu(unsigned char, Menu::arg const*)
00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
+000001a0 T GCS_MAVLINK::update()
000001a8 t print_radio_values()
000001cc t start_new_log()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001e6 t verify_nav_wp()
000001ea t init_home()
-00000216 t set_mode(unsigned char)
00000220 t test_wp(unsigned char, Menu::arg const*)
+00000226 t set_mode(unsigned char)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
-0000030c t heli_init_swash()
-00000312 W Parameters::~Parameters()
+00000298 T update_throttle_mode()
+00000326 W Parameters::~Parameters()
0000032a t report_heli()
-00000330 t tuning()
+0000033a t heli_init_swash()
+0000036a t tuning()
00000384 t print_log_menu()
-0000039a T update_throttle_mode()
0000039c t __static_initialization_and_destruction_0(int, int)
+0000039e T update_roll_pitch_mode()
000003a0 t read_battery()
0000045c T update_yaw_mode()
-0000046e T update_roll_pitch_mode()
0000052e t heli_move_swash(int, int, int, int)
-00000622 t init_ardupilot()
+00000600 t init_ardupilot()
0000071a t update_nav_wp()
000007ec t setup_heli(unsigned char, Menu::arg const*)
00000870 t process_next_command()
-000009b8 W Parameters::Parameters()
-00000a1f b g
-0000100a T loop
+00000a64 W Parameters::Parameters()
+00000b2d b g
+000010b6 T loop
00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log
index 10604a699c..3e86d02fc8 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log
+++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log
@@ -5,13 +5,15 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
-/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
+/root/apm/ardupilot-mega/ArduCopter/Parameters.h:407: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde: In function 'bool mavlink_try_send_message(mavlink_channel_t, ap_message, uint16_t)':
-/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
-/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
-/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:296: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
+/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU1' not handled in switch
+/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU2' not handled in switch
+/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:299: warning: enumeration value 'MSG_RAW_IMU3' not handled in switch
/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()':
-/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
+/root/apm/ardupilot-mega/ArduCopter/heli.pde:64: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
+/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'int heli_get_scaled_throttle(int)':
+/root/apm/ardupilot-mega/ArduCopter/heli.pde:205: warning: unused variable 'scaled_throttle'
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
@@ -19,7 +21,9 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
-autogenerated: At global scope:
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:179: warning: 'int alt_hold_velocity()' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:209: warning: 'int get_angle_boost(int)' defined but not used
autogenerated:51: warning: 'void send_raw_imu1(mavlink_channel_t)' declared 'static' but never defined
autogenerated:52: warning: 'void send_raw_imu2(mavlink_channel_t)' declared 'static' but never defined
autogenerated:53: warning: 'void send_raw_imu3(mavlink_channel_t)' declared 'static' but never defined
@@ -28,36 +32,39 @@ autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but nev
autogenerated:111: warning: 'void Log_Write_Control_Tuning()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/Log.pde:776: warning: 'void Log_Write_Attitude()' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/Log.pde:835: warning: 'void Log_Write_Attitude()' defined but not used
autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
-autogenerated:213: warning: 'void debug_motors()' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
-autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
-autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
-autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
-autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
-autogenerated:246: warning: 'void ReadSCP1000()' declared 'static' but never defined
-autogenerated:247: warning: 'void init_barometer()' declared 'static' but never defined
-autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
-autogenerated:249: warning: 'long int read_barometer()' declared 'static' but never defined
-autogenerated:250: warning: 'void read_airspeed()' declared 'static' but never defined
-autogenerated:251: warning: 'void zero_airspeed()' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used
-autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
-autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
+autogenerated:215: warning: 'void debug_motors()' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/navigation.pde:213: warning: 'int get_loiter_angle()' defined but not used
+autogenerated:237: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
+autogenerated:238: warning: 'long int cross_track_test()' declared 'static' but never defined
+autogenerated:239: warning: 'void reset_crosstrack()' declared 'static' but never defined
+autogenerated:241: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/radio.pde:134: warning: 'void throttle_failsafe(uint16_t)' defined but not used
+autogenerated:250: warning: 'void ReadSCP1000()' declared 'static' but never defined
+autogenerated:251: warning: 'void init_barometer()' declared 'static' but never defined
+autogenerated:252: warning: 'long int read_baro_filtered()' declared 'static' but never defined
+autogenerated:253: warning: 'long int read_barometer()' declared 'static' but never defined
+autogenerated:254: warning: 'void read_airspeed()' declared 'static' but never defined
+autogenerated:255: warning: 'void zero_airspeed()' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/system.pde:456: warning: 'void set_failsafe(boolean)' defined but not used
+autogenerated:290: warning: 'void init_optflow()' declared 'static' but never defined
+autogenerated:297: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_min' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:344: warning: 'old_altitude' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:362: warning: 'abs_pressure' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:363: warning: 'ground_pressure' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:364: warning: 'ground_temperature' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:369: warning: 'baro_alt' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:347: warning: 'old_altitude' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:348: warning: 'old_rate' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:366: warning: 'abs_pressure' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:367: warning: 'ground_pressure' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:368: warning: 'ground_temperature' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:373: warning: 'baro_alt' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:389: warning: 'angle_boost' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1727: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/test.pde:13: warning: 'int8_t test_adc(uint8_t, const Menu::arg*)' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:26: warning: 'int8_t test_baro(uint8_t, const Menu::arg*)' declared 'static' but never defined
%% libraries/APM_BMP085/APM_BMP085.o
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.size.txt
index c3ae322200..d90c94c76f 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.size.txt
+++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.size.txt
@@ -10,6 +10,7 @@
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
+00000001 b mavlink_active
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
@@ -47,8 +48,10 @@
00000002 b loiter_sum
00000002 b event_delay
00000002 b event_value
+00000002 b CH7_wp_index
00000002 b event_repeat
00000002 b loiter_total
+00000002 b manual_boost
00000002 b nav_throttle
00000002 b x_rate_error
00000002 b y_rate_error
@@ -86,6 +89,7 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
+00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@@ -124,6 +128,7 @@
00000004 b fiftyhz_loopTimer
00000004 b old_target_bearing
00000004 b throttle_integrator
+00000004 b heli_throttle_scaler
00000004 r __menu_name__log_menu
00000004 b command_yaw_start_time
00000004 b initial_simple_bearing
@@ -284,6 +289,8 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
+0000000a V Parameters::Parameters()::__c
+0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
@@ -416,7 +423,6 @@
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r setup_heli(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
-00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
@@ -427,8 +433,8 @@
00000018 r __menu_name__main_menu
00000018 W AP_VarT::serialize(void*, unsigned int) const
00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c
+00000019 r Log_Read_Motors()::__c
0000001a r print_log_menu()::__c
-0000001a r Log_Read_Nav_Tuning()::__c
0000001b r setup_heli(unsigned char, Menu::arg const*)::__c
0000001b r report_heli()::__c
0000001c W AP_VarS >::unserialize(void*, unsigned int)
@@ -437,6 +443,7 @@
0000001c W AP_VarS >::serialize(void*, unsigned int) const
0000001c W AP_VarS >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c
+0000001d r Log_Read_Performance()::__c
0000001e r report_heli()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
@@ -446,10 +453,8 @@
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
-00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
-00000022 t reset_hold_I()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarS >::~AP_VarS()
00000022 W AP_VarS >::~AP_VarS()
@@ -459,13 +464,13 @@
00000023 r setup_heli(unsigned char, Menu::arg const*)::__c
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
+00000024 t reset_hold_I()
00000024 r setup_heli(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
-00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
@@ -476,14 +481,16 @@
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
+0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t setup_motors(unsigned char, Menu::arg const*)
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
+0000002e r init_ardupilot()::__c
+0000002e r Log_Read_Nav_Tuning()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
-0000002f r init_ardupilot()::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000030 B imu
@@ -496,19 +503,17 @@
00000034 t _MAV_RETURN_float
00000034 t heli_get_servo(int)
00000034 W AP_Float16::serialize(void*, unsigned int) const
-00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
+00000036 r Log_Read_Control_Tuning()::__c
00000037 r print_wp(Location*, unsigned char)::__c
-00000038 t init_throttle_cruise()
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
0000003a B g_gps_driver
-0000003c W RC_Channel::~RC_Channel()
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
00000040 W AP_Float16::unserialize(void*, unsigned int)
@@ -517,6 +522,7 @@
00000042 t report_sonar()
00000042 r setup_heli(unsigned char, Menu::arg const*)::__c
00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
+00000046 W RC_Channel::~RC_Channel()
00000048 t change_command(unsigned char)
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
@@ -549,9 +555,9 @@
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
+00000068 W GCS_MAVLINK::~GCS_MAVLINK()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t read_num_from_serial()
-0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
00000074 t output_motors_armed()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
@@ -572,11 +578,11 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
+00000094 t init_throttle_cruise()
00000096 t print_wp(Location*, unsigned char)
+00000098 B gcs0
+00000098 B gcs3
0000009a t planner_gcs(unsigned char, Menu::arg const*)
-0000009a t Log_Read_Motors()
-0000009b B gcs0
-0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*)
@@ -585,12 +591,13 @@
000000a4 T __vector_55
000000a6 t send_servo_out(mavlink_channel_t)
000000a8 t test_sonar(unsigned char, Menu::arg const*)
-000000aa t Log_Read_Nav_Tuning()
000000ab B compass
+000000ae t Log_Read_Motors()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b4 t read_radio()
000000b6 t get_log_boundaries(unsigned char, int&, int&)
+000000b6 t Log_Read_Performance()
000000be t update_events()
000000c2 t test_eedump(unsigned char, Menu::arg const*)
000000c2 t setup_compass(unsigned char, Menu::arg const*)
@@ -599,7 +606,6 @@
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t send_radio_in(mavlink_channel_t)
-000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000d0 t get_bearing(Location*, Location*)
000000d0 t print_switch(unsigned char, unsigned char, bool)
@@ -607,29 +613,31 @@
000000d4 t get_stabilize_pitch(long)
000000d4 t Log_Read(int, int)
000000d8 t test_radio(unsigned char, Menu::arg const*)
+000000de t Log_Read_Nav_Tuning()
000000e0 r test_menu_commands
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
-000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
+000000f8 t heli_get_angle_boost(int)
+000000fa t calc_loiter_pitch_roll()
00000100 r setup_menu_commands
+00000102 t Log_Read_Control_Tuning()
00000108 t setup_gyro(unsigned char, Menu::arg const*)
0000010a t mavlink_delay(unsigned long)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
-0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
+00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
+00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
-00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
-00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
-0000012c t calc_loiter_pitch_roll()
0000012e t arm_motors()
00000130 t report_compass()
+00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000148 t Log_Read_GPS()
00000156 t update_commands()
0000015c t update_trig()
@@ -637,38 +645,38 @@
00000160 t send_nav_controller_output(mavlink_channel_t)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
-00000168 T GCS_MAVLINK::update()
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
00000178 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
00000184 t test_imu(unsigned char, Menu::arg const*)
00000188 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
+000001a0 T GCS_MAVLINK::update()
000001a8 t print_radio_values()
000001cc t start_new_log()
000001e4 t verify_nav_wp()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home()
-00000216 t set_mode(unsigned char)
0000021c t test_wp(unsigned char, Menu::arg const*)
+00000226 t set_mode(unsigned char)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
-0000030c t heli_init_swash()
-00000312 W Parameters::~Parameters()
+00000298 T update_throttle_mode()
+00000326 W Parameters::~Parameters()
00000328 t report_heli()
-00000330 t tuning()
+0000033a t heli_init_swash()
+0000036a t tuning()
00000382 t print_log_menu()
-0000039a T update_throttle_mode()
0000039c t __static_initialization_and_destruction_0(int, int)
+0000039e T update_roll_pitch_mode()
000003a0 t read_battery()
0000045c T update_yaw_mode()
-0000046e T update_roll_pitch_mode()
0000052e t heli_move_swash(int, int, int, int)
-00000620 t init_ardupilot()
+000005fe t init_ardupilot()
0000071a t update_nav_wp()
000007e8 t setup_heli(unsigned char, Menu::arg const*)
00000870 t process_next_command()
-000009b8 W Parameters::Parameters()
-00000a1f b g
-0000100a T loop
+00000a64 W Parameters::Parameters()
+00000b2d b g
+000010b6 T loop
00001604 T GCS_MAVLINK::handleMessage(__mavlink_message*)
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log
index d420f23d8f..e2ae2c5243 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log
+++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log
@@ -5,17 +5,21 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
-/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
+/root/apm/ardupilot-mega/ArduCopter/Parameters.h:407: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()':
-/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
+/root/apm/ardupilot-mega/ArduCopter/heli.pde:64: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
+/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'int heli_get_scaled_throttle(int)':
+/root/apm/ardupilot-mega/ArduCopter/heli.pde:205: warning: unused variable 'scaled_throttle'
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
-/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
+/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
-autogenerated: At global scope:
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:179: warning: 'int alt_hold_velocity()' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:209: warning: 'int get_angle_boost(int)' defined but not used
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
@@ -23,24 +27,25 @@ autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but ne
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
-autogenerated:213: warning: 'void debug_motors()' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
-autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
-autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
-autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
-autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
+autogenerated:215: warning: 'void debug_motors()' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/navigation.pde:213: warning: 'int get_loiter_angle()' defined but not used
+autogenerated:237: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
+autogenerated:238: warning: 'long int cross_track_test()' declared 'static' but never defined
+autogenerated:239: warning: 'void reset_crosstrack()' declared 'static' but never defined
+autogenerated:241: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/radio.pde:134: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
-autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
+autogenerated:252: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used
-autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
-autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/system.pde:456: warning: 'void set_failsafe(boolean)' defined but not used
+autogenerated:290: warning: 'void init_optflow()' declared 'static' but never defined
+autogenerated:297: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_min' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1727: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt
index 41607607b2..4f8bcc3fd3 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt
+++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt
@@ -10,6 +10,7 @@
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
+00000001 b mavlink_active
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
@@ -45,10 +46,13 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
+00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
+00000002 b CH7_wp_index
00000002 b event_repeat
00000002 b loiter_total
+00000002 b manual_boost
00000002 b nav_throttle
00000002 b x_rate_error
00000002 b y_rate_error
@@ -71,6 +75,7 @@
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
+00000002 b old_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@@ -85,6 +90,7 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
+00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@@ -125,6 +131,7 @@
00000004 b fiftyhz_loopTimer
00000004 b old_target_bearing
00000004 b throttle_integrator
+00000004 b heli_throttle_scaler
00000004 r __menu_name__log_menu
00000004 b command_yaw_start_time
00000004 b initial_simple_bearing
@@ -287,6 +294,8 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
+0000000a V Parameters::Parameters()::__c
+0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
@@ -418,7 +427,6 @@
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r setup_heli(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
-00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
@@ -429,8 +437,8 @@
00000018 r __menu_name__main_menu
00000018 W AP_VarT::serialize(void*, unsigned int) const
00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c
+00000019 r Log_Read_Motors()::__c
0000001a r print_log_menu()::__c
-0000001a r Log_Read_Nav_Tuning()::__c
0000001b r setup_heli(unsigned char, Menu::arg const*)::__c
0000001b r report_heli()::__c
0000001c W AP_VarA::unserialize(void*, unsigned int)
@@ -441,6 +449,7 @@
0000001c W AP_VarS >::serialize(void*, unsigned int) const
0000001c W AP_VarS >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c
+0000001d r Log_Read_Performance()::__c
0000001e r report_heli()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
@@ -450,10 +459,8 @@
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
-00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
-00000022 t reset_hold_I()
00000022 t startup_ground()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA::~AP_VarA()
@@ -465,13 +472,13 @@
00000023 r setup_heli(unsigned char, Menu::arg const*)::__c
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
+00000024 t reset_hold_I()
00000024 r setup_heli(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
-00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
@@ -482,14 +489,16 @@
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
+0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t setup_motors(unsigned char, Menu::arg const*)
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
+0000002e r init_ardupilot()::__c
+0000002e r Log_Read_Nav_Tuning()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
-0000002f r init_ardupilot()::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000031 r setup_heli(unsigned char, Menu::arg const*)::__c
@@ -500,18 +509,16 @@
00000033 b pending_status
00000034 t heli_get_servo(int)
00000034 W AP_Float16::serialize(void*, unsigned int) const
-00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
+00000036 r Log_Read_Control_Tuning()::__c
00000037 r print_wp(Location*, unsigned char)::__c
-00000038 t init_throttle_cruise()
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
-0000003c W RC_Channel::~RC_Channel()
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
@@ -523,6 +530,7 @@
00000042 t report_sonar()
00000042 r setup_heli(unsigned char, Menu::arg const*)::__c
00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
+00000046 W RC_Channel::~RC_Channel()
00000048 t change_command(unsigned char)
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
@@ -553,9 +561,9 @@
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
+00000068 W GCS_MAVLINK::~GCS_MAVLINK()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t read_num_from_serial()
-0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
00000074 t output_motors_armed()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
@@ -579,12 +587,12 @@
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 t report_tuning()
00000092 T GCS_MAVLINK::queued_param_send()
+00000094 t init_throttle_cruise()
00000096 t print_wp(Location*, unsigned char)
+00000098 B gcs0
+00000098 B gcs3
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
-0000009a t Log_Read_Motors()
-0000009b B gcs0
-0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Write_Cmd(unsigned char, Location*)
000000a0 t Log_Read_Mode()
@@ -593,11 +601,12 @@
000000a4 T __vector_55
000000a6 t send_servo_out(mavlink_channel_t)
000000aa t test_sonar(unsigned char, Menu::arg const*)
-000000aa t Log_Read_Nav_Tuning()
+000000ae t Log_Read_Motors()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b4 t read_radio()
000000b6 t get_log_boundaries(unsigned char, int&, int&)
+000000b6 t Log_Read_Performance()
000000b7 B compass
000000be t update_events()
000000c2 t setup_compass(unsigned char, Menu::arg const*)
@@ -607,7 +616,6 @@
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t test_eedump(unsigned char, Menu::arg const*)
000000c6 t send_radio_in(mavlink_channel_t)
-000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t init_barometer()
@@ -618,30 +626,32 @@
000000d4 t Log_Read(int, int)
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000d8 t read_barometer()
+000000de t Log_Read_Nav_Tuning()
000000de t test_adc(unsigned char, Menu::arg const*)
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
-000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
+000000f8 t heli_get_angle_boost(int)
+000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands
00000100 r setup_menu_commands
+00000102 t Log_Read_Control_Tuning()
00000106 t setup_gyro(unsigned char, Menu::arg const*)
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
-0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
+00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
+00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
-00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
-00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
-0000012c t calc_loiter_pitch_roll()
00000130 t report_compass()
+00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000148 t Log_Read_GPS()
00000156 t update_commands()
0000015c t update_trig()
@@ -650,10 +660,10 @@
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
-00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*)
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
+000001a0 T GCS_MAVLINK::update()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001be t arm_motors()
@@ -661,29 +671,29 @@
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001e6 t verify_nav_wp()
000001ea t init_home()
-00000216 t set_mode(unsigned char)
0000021a t send_raw_imu1(mavlink_channel_t)
00000220 t test_wp(unsigned char, Menu::arg const*)
+00000226 t set_mode(unsigned char)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
-0000030c t heli_init_swash()
-00000312 W Parameters::~Parameters()
+00000298 T update_throttle_mode()
+00000326 W Parameters::~Parameters()
0000032a t report_heli()
-00000330 t tuning()
+0000033a t heli_init_swash()
+0000036a t tuning()
00000384 t print_log_menu()
-0000039a T update_throttle_mode()
+0000039e T update_roll_pitch_mode()
000003a0 t read_battery()
0000045c T update_yaw_mode()
-0000046e T update_roll_pitch_mode()
0000053e t heli_move_swash(int, int, int, int)
000005cc t __static_initialization_and_destruction_0(int, int)
-00000620 t init_ardupilot()
+000005fe t init_ardupilot()
0000071a t update_nav_wp()
000007ec t setup_heli(unsigned char, Menu::arg const*)
00000870 t process_next_command()
-000009b8 W Parameters::Parameters()
-00000a1f b g
+00000a64 W Parameters::Parameters()
+00000b2d b g
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
-00001598 T loop
+000016c8 T loop
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log
index d420f23d8f..e2ae2c5243 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log
+++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log
@@ -5,17 +5,21 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:55:
/usr/local/share/arduino/libraries/SPI/SPI.h:20:1: warning: this is the location of the previous definition
In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/Parameters.h: In constructor 'Parameters::Parameters()':
-/root/apm/ardupilot-mega/ArduCopter/Parameters.h:399: warning: overflow in implicit constant conversion
+/root/apm/ardupilot-mega/ArduCopter/Parameters.h:407: warning: overflow in implicit constant conversion
/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()':
-/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
+/root/apm/ardupilot-mega/ArduCopter/heli.pde:64: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
+/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'int heli_get_scaled_throttle(int)':
+/root/apm/ardupilot-mega/ArduCopter/heli.pde:205: warning: unused variable 'scaled_throttle'
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
-/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
+/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
-autogenerated: At global scope:
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde: At global scope:
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:179: warning: 'int alt_hold_velocity()' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/Attitude.pde:209: warning: 'int get_angle_boost(int)' defined but not used
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
autogenerated:90: warning: 'void Log_Write_Attitude2()' declared 'static' but never defined
autogenerated:91: warning: 'void Log_Read_Attitude2()' declared 'static' but never defined
@@ -23,24 +27,25 @@ autogenerated:121: warning: 'void decrement_WP_index()' declared 'static' but ne
/root/apm/ardupilot-mega/ArduCopter/commands.pde:132: warning: 'Location get_LOITER_home_wp()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/commands_logic.pde:432: warning: 'bool verify_loiter_unlim()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/events.pde:46: warning: 'void low_battery_event()' defined but not used
-autogenerated:213: warning: 'void debug_motors()' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/navigation.pde:183: warning: 'int get_loiter_angle()' defined but not used
-autogenerated:234: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
-autogenerated:235: warning: 'long int cross_track_test()' declared 'static' but never defined
-autogenerated:236: warning: 'void reset_crosstrack()' declared 'static' but never defined
-autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
-/root/apm/ardupilot-mega/ArduCopter/radio.pde:130: warning: 'void throttle_failsafe(uint16_t)' defined but not used
+autogenerated:215: warning: 'void debug_motors()' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/navigation.pde:95: warning: 'void calc_loiter2(int, int)' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/navigation.pde:213: warning: 'int get_loiter_angle()' defined but not used
+autogenerated:237: warning: 'long int get_crosstrack_correction()' declared 'static' but never defined
+autogenerated:238: warning: 'long int cross_track_test()' declared 'static' but never defined
+autogenerated:239: warning: 'void reset_crosstrack()' declared 'static' but never defined
+autogenerated:241: warning: 'long int get_alt_distance(Location*, Location*)' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/radio.pde:134: warning: 'void throttle_failsafe(uint16_t)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:6: warning: 'void ReadSCP1000()' defined but not used
-autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
+autogenerated:252: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used
-autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
-autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
+/root/apm/ardupilot-mega/ArduCopter/system.pde:456: warning: 'void set_failsafe(boolean)' defined but not used
+autogenerated:290: warning: 'void init_optflow()' declared 'static' but never defined
+autogenerated:297: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_min' defined but not used
/root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:277: warning: 'heli_servo_max' defined but not used
-/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1706: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
+/root/apm/ardupilot-mega/ArduCopter/GCS_Mavlink.pde:1727: warning: 'void gcs_send_text_fmt(const prog_char_t*, ...)' defined but not used
%% libraries/APM_BMP085/APM_BMP085.o
%% libraries/APM_BMP085/APM_BMP085_hil.o
%% libraries/APM_PI/APM_PI.o
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt
index 0f00a831cc..5f1c4d5346 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt
+++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt
@@ -10,6 +10,7 @@
00000001 b land_complete
00000001 b throttle_mode
00000001 b command_may_ID
+00000001 b mavlink_active
00000001 b wp_verify_byte
00000001 d altitude_sensor
00000001 b command_must_ID
@@ -45,10 +46,13 @@
00000002 T userhook_init()
00000002 b climb_rate
00000002 b loiter_sum
+00000002 b angle_boost
00000002 b event_delay
00000002 b event_value
+00000002 b CH7_wp_index
00000002 b event_repeat
00000002 b loiter_total
+00000002 b manual_boost
00000002 b nav_throttle
00000002 b x_rate_error
00000002 b y_rate_error
@@ -71,6 +75,7 @@
00000002 b g_gps
00000002 b airspeed
00000002 b baro_alt
+00000002 b old_rate
00000002 b sonar_alt
00000002 b arm_motors()::arming_counter
00000002 r setup_frame(unsigned char, Menu::arg const*)::__c
@@ -85,6 +90,7 @@
00000003 r setup_sonar(unsigned char, Menu::arg const*)::__c
00000003 r print_enabled(unsigned char)::__c
00000003 r setup_compass(unsigned char, Menu::arg const*)::__c
+00000003 V RC_Channel::RC_Channel(unsigned int, prog_char_t const*)::__c
00000004 d cos_roll_x
00000004 b land_start
00000004 b long_error
@@ -125,6 +131,7 @@
00000004 b fiftyhz_loopTimer
00000004 b old_target_bearing
00000004 b throttle_integrator
+00000004 b heli_throttle_scaler
00000004 r __menu_name__log_menu
00000004 b command_yaw_start_time
00000004 b initial_simple_bearing
@@ -287,6 +294,8 @@
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
0000000a V Parameters::Parameters()::__c
+0000000a V Parameters::Parameters()::__c
+0000000a V Parameters::Parameters()::__c
0000000a T setup
0000000b r test_relay(unsigned char, Menu::arg const*)::__c
0000000b r report_batt_monitor()::__c
@@ -418,7 +427,6 @@
00000014 r test_tri(unsigned char, Menu::arg const*)::__c
00000015 r setup_heli(unsigned char, Menu::arg const*)::__c
00000015 r init_ardupilot()::__c
-00000015 r Log_Read_Motors()::__c
00000015 r print_hit_enter()::__c
00000015 r GCS_MAVLINK::handleMessage(__mavlink_message*)::__c
00000016 T piezo_beep()
@@ -429,8 +437,8 @@
00000018 r __menu_name__main_menu
00000018 W AP_VarT::serialize(void*, unsigned int) const
00000019 r setup_gyro(unsigned char, Menu::arg const*)::__c
+00000019 r Log_Read_Motors()::__c
0000001a r print_log_menu()::__c
-0000001a r Log_Read_Nav_Tuning()::__c
0000001b r setup_heli(unsigned char, Menu::arg const*)::__c
0000001b r report_heli()::__c
0000001c W AP_VarA::unserialize(void*, unsigned int)
@@ -441,6 +449,7 @@
0000001c W AP_VarS >::serialize(void*, unsigned int) const
0000001c W AP_VarS >::serialize(void*, unsigned int) const
0000001d r Log_Read_Attitude()::__c
+0000001d r Log_Read_Performance()::__c
0000001e r report_heli()::__c
0000001e r Log_Read_Optflow()::__c
00000020 t gcs_send_message(ap_message)
@@ -450,10 +459,8 @@
00000021 r print_log_menu()::__c
00000021 r report_compass()::__c
00000021 r Log_Read_Current()::__c
-00000021 r Log_Read_Performance()::__c
00000022 t clear_leds()
00000022 t print_blanks(int)
-00000022 t reset_hold_I()
00000022 t startup_ground()
00000022 W AP_Float16::~AP_Float16()
00000022 W AP_VarA::~AP_VarA()
@@ -465,13 +472,13 @@
00000023 r setup_heli(unsigned char, Menu::arg const*)::__c
00000023 r setup_mode(unsigned char, Menu::arg const*)::__c
00000023 r print_gyro_offsets()::__c
+00000024 t reset_hold_I()
00000024 r setup_heli(unsigned char, Menu::arg const*)::__c
00000024 r init_ardupilot()::__c
00000024 r print_accel_offsets()::__c
00000026 t print_done()
00000026 t print_hit_enter()
00000026 t Log_Read_Startup()
-00000026 r Log_Read_Control_Tuning()::__c
00000028 t test_battery(unsigned char, Menu::arg const*)
00000028 t main_menu_help(unsigned char, Menu::arg const*)
00000028 t help_log(unsigned char, Menu::arg const*)
@@ -482,14 +489,16 @@
00000029 r setup_mode(unsigned char, Menu::arg const*)::__c
00000029 r test_gps(unsigned char, Menu::arg const*)::__c
0000002a t setup_declination(unsigned char, Menu::arg const*)
+0000002a t _mav_put_int8_t_array
0000002b r planner_mode(unsigned char, Menu::arg const*)::__c
0000002e t setup_motors(unsigned char, Menu::arg const*)
0000002e t print_divider()
0000002e t gcs_send_text_P(gcs_severity, prog_char_t const*)
0000002e t gcs_data_stream_send(unsigned int, unsigned int)
0000002e W AP_Var_group::AP_Var_group(unsigned int, prog_char_t const*, unsigned char)
+0000002e r init_ardupilot()::__c
+0000002e r Log_Read_Nav_Tuning()::__c
0000002f r test_radio(unsigned char, Menu::arg const*)::__c
-0000002f r init_ardupilot()::__c
00000030 t planner_mode(unsigned char, Menu::arg const*)
00000030 t send_heartbeat(mavlink_channel_t)
00000031 r setup_heli(unsigned char, Menu::arg const*)::__c
@@ -500,18 +509,16 @@
00000033 b pending_status
00000034 t heli_get_servo(int)
00000034 W AP_Float16::serialize(void*, unsigned int) const
-00000034 t _mav_put_int8_t_array
00000034 t mavlink_msg_statustext_send
00000035 r test_radio_pwm(unsigned char, Menu::arg const*)::__c
00000036 t report_radio()
+00000036 r Log_Read_Control_Tuning()::__c
00000037 r print_wp(Location*, unsigned char)::__c
-00000038 t init_throttle_cruise()
00000038 t send_current_waypoint(mavlink_channel_t)
00000038 r setup_radio(unsigned char, Menu::arg const*)::__c
00000038 r setup_factory(unsigned char, Menu::arg const*)::__c
0000003a t report_gps()
0000003a t report_imu()
-0000003c W RC_Channel::~RC_Channel()
0000003d B g_gps_driver
0000003e T GCS_MAVLINK::send_text(gcs_severity, prog_char_t const*)
0000003e W AP_VarT::AP_VarT(signed char, unsigned int, prog_char_t const*, unsigned char)
@@ -523,6 +530,7 @@
00000042 t report_sonar()
00000042 r setup_heli(unsigned char, Menu::arg const*)::__c
00000044 W AP_VarT::AP_VarT(int, unsigned int, prog_char_t const*, unsigned char)
+00000046 W RC_Channel::~RC_Channel()
00000048 t change_command(unsigned char)
00000048 t update_motor_leds()
00000049 r setup_flightmodes(unsigned char, Menu::arg const*)::__c
@@ -553,9 +561,9 @@
00000064 t mavlink_msg_param_value_send
00000068 t zero_eeprom()
00000068 t find_last_log_page(int)
+00000068 W GCS_MAVLINK::~GCS_MAVLINK()
0000006a T mavlink_send_text(mavlink_channel_t, gcs_severity, char const*)
0000006a t read_num_from_serial()
-0000006a W GCS_MAVLINK::~GCS_MAVLINK()
0000006c t setup_sonar(unsigned char, Menu::arg const*)
00000074 t output_motors_armed()
00000078 t setup_batt_monitor(unsigned char, Menu::arg const*)
@@ -579,12 +587,12 @@
00000090 t report_tuning()
00000092 t test_tuning(unsigned char, Menu::arg const*)
00000092 T GCS_MAVLINK::queued_param_send()
+00000094 t init_throttle_cruise()
00000096 t print_wp(Location*, unsigned char)
+00000098 B gcs0
+00000098 B gcs3
0000009a t planner_gcs(unsigned char, Menu::arg const*)
0000009a t init_compass()
-0000009a t Log_Read_Motors()
-0000009b B gcs0
-0000009b B gcs3
0000009e t setup_mode(unsigned char, Menu::arg const*)
0000009e t Log_Read_Mode()
0000009e t Log_Write_Cmd(unsigned char, Location*)
@@ -593,11 +601,12 @@
000000a4 T __vector_55
000000a6 t send_servo_out(mavlink_channel_t)
000000a8 t test_sonar(unsigned char, Menu::arg const*)
-000000aa t Log_Read_Nav_Tuning()
+000000ae t Log_Read_Motors()
000000b0 t test_relay(unsigned char, Menu::arg const*)
000000b2 t erase_logs(unsigned char, Menu::arg const*)
000000b4 t read_radio()
000000b6 t get_log_boundaries(unsigned char, int&, int&)
+000000b6 t Log_Read_Performance()
000000b7 B compass
000000be t update_events()
000000c2 t test_eedump(unsigned char, Menu::arg const*)
@@ -607,7 +616,6 @@
000000c4 t get_distance(Location*, Location*)
000000c4 r setup_esc(unsigned char, Menu::arg const*)::__c
000000c6 t send_radio_in(mavlink_channel_t)
-000000c6 t Log_Read_Performance()
000000c6 t test_tri(unsigned char, Menu::arg const*)
000000c7 B dcm
000000ca t init_barometer()
@@ -619,29 +627,31 @@
000000d8 t test_radio(unsigned char, Menu::arg const*)
000000d8 t read_barometer()
000000dc t test_adc(unsigned char, Menu::arg const*)
+000000de t Log_Read_Nav_Tuning()
000000e4 t test_radio_pwm(unsigned char, Menu::arg const*)
000000e4 t Log_Read_Optflow()
000000e4 W APM_PI::APM_PI(unsigned int, prog_char_t const*, float const&, float const&, int const&)
000000e8 t Log_Read_Current()
-000000ea t Log_Read_Control_Tuning()
000000ee t report_batt_monitor()
000000f6 t Log_Read_Cmd()
+000000f8 t heli_get_angle_boost(int)
+000000fa t calc_loiter_pitch_roll()
00000100 r test_menu_commands
00000100 r setup_menu_commands
+00000102 t Log_Read_Control_Tuning()
00000108 t setup_gyro(unsigned char, Menu::arg const*)
0000010a t mavlink_delay(unsigned long)
0000010a t send_raw_imu2(mavlink_channel_t)
0000010a t test_gps(unsigned char, Menu::arg const*)
0000010c t test_current(unsigned char, Menu::arg const*)
-0000010e W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
+00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
+00000110 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000112 t set_next_WP(Location*)
00000112 t send_extended_status1(mavlink_channel_t, unsigned int)
-00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
-00000112 T GCS_MAVLINK::GCS_MAVLINK(unsigned int)
00000118 t set_command_with_index(Location, int)
0000011c t get_command_with_index(int)
-0000012c t calc_loiter_pitch_roll()
00000130 t report_compass()
+00000136 W RC_Channel::RC_Channel(unsigned int, prog_char_t const*)
00000148 t Log_Read_GPS()
00000156 t update_commands()
0000015c t update_trig()
@@ -650,10 +660,10 @@
00000162 T GCS_MAVLINK::data_stream_send(unsigned int, unsigned int)
00000166 t select_logs(unsigned char, Menu::arg const*)
00000166 t send_vfr_hud(mavlink_channel_t)
-00000168 T GCS_MAVLINK::update()
0000016c t test_imu(unsigned char, Menu::arg const*)
0000016e t send_attitude(mavlink_channel_t)
00000174 t mavlink_send_message(mavlink_channel_t, ap_message, unsigned int)
+000001a0 T GCS_MAVLINK::update()
000001a2 t mavlink_try_send_message(mavlink_channel_t, ap_message, unsigned int)
000001a8 t print_radio_values()
000001be t arm_motors()
@@ -661,29 +671,29 @@
000001e4 t verify_nav_wp()
000001e4 t setup_flightmodes(unsigned char, Menu::arg const*)
000001ea t init_home()
-00000216 t set_mode(unsigned char)
0000021a t send_raw_imu1(mavlink_channel_t)
0000021c t test_wp(unsigned char, Menu::arg const*)
+00000226 t set_mode(unsigned char)
00000228 t setup_radio(unsigned char, Menu::arg const*)
0000022a t send_gps_raw(mavlink_channel_t)
00000242 t calc_loiter(int, int)
00000268 t send_raw_imu3(mavlink_channel_t)
-0000030c t heli_init_swash()
-00000312 W Parameters::~Parameters()
+00000298 T update_throttle_mode()
+00000326 W Parameters::~Parameters()
00000328 t report_heli()
-00000330 t tuning()
+0000033a t heli_init_swash()
+0000036a t tuning()
00000382 t print_log_menu()
-0000039a T update_throttle_mode()
+0000039e T update_roll_pitch_mode()
000003a0 t read_battery()
0000045c T update_yaw_mode()
-0000046e T update_roll_pitch_mode()
0000053e t heli_move_swash(int, int, int, int)
000005cc t __static_initialization_and_destruction_0(int, int)
-0000061e t init_ardupilot()
+000005fc t init_ardupilot()
0000071a t update_nav_wp()
000007e8 t setup_heli(unsigned char, Menu::arg const*)
00000870 t process_next_command()
-000009b8 W Parameters::Parameters()
-00000a1f b g
+00000a64 W Parameters::Parameters()
+00000b2d b g
000012ec T GCS_MAVLINK::handleMessage(__mavlink_message*)
-00001598 T loop
+000016c8 T loop
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
index c2dccc3239..e338f2b167 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
+++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
@@ -95,7 +95,7 @@
http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex
http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.hex
- ArduCopter V2.0.49 Beta Heli (2560 only)
+ ArduCopter V2.0.50 Beta Heli (2560 only)
#define AUTO_RESET_LOITER 0
#define FRAME_CONFIG HELI_FRAME
@@ -137,7 +137,7 @@
#define NAV_LOITER_IMAX 10
- 111
+ 112
http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex
@@ -157,7 +157,7 @@
http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex
http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.hex
- ArduCopter V2.0.49 Beta Heli Hil
+ ArduCopter V2.0.50 Beta Heli Hil
#define HIL_MODE HIL_MODE_ATTITUDE
@@ -203,6 +203,6 @@
- 111
+ 112
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/git.log b/Tools/ArdupilotMegaPlanner/Firmware/git.log
index 04b288c7e4..ca7ab87b26 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/git.log
+++ b/Tools/ArdupilotMegaPlanner/Firmware/git.log
@@ -1,36 +1,545 @@
From https://code.google.com/p/ardupilot-mega
- 8a21477..b0bfa54 APM_Camera -> origin/APM_Camera
- 6f44fff..076459c master -> origin/master
-Updating 6f44fff..076459c
+ b0bfa54..8d3fb35 APM_Camera -> origin/APM_Camera
+ cd1bcd6..34c9a18 master -> origin/master
+Updating cd1bcd6..34c9a18
Fast-forward
- ArduCopter/control_modes.pde | 16 +
+ .gitignore | 4 +-
+ ArduBoat/ArduBoat.cpp | 7 +-
+ ArduBoat/ArduBoat.pde | 2 +-
+ ArduBoat/BoatGeneric.h | 39 +-
+ ArduBoat/ControllerBoat.h | 157 +-
+ ArduCopter/APM_Config.h | 7 +-
+ ArduCopter/ArduCopter.pde | 64 +-
+ ArduCopter/Attitude.pde | 54 +-
+ ArduCopter/CMakeLists.txt | 165 -
+ ArduCopter/GCS.h | 7 +-
+ ArduCopter/GCS_Mavlink.pde | 23 +-
+ ArduCopter/Log.pde | 261 +-
+ ArduCopter/Parameters.h | 12 +-
+ ArduCopter/config.h | 45 +-
+ ArduCopter/control_modes.pde | 8 +-
ArduCopter/defines.h | 1 +
- ArduCopter/system.pde | 4 +
- ArduPlane/ArduPlane.pde | 10 +-
- ArduPlane/Parameters.h | 3 +
- ArduPlane/config.h | 8 +
- Tools/ArduTracker/tags |148411 --------------------
- Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs | 2 +
- Tools/ArdupilotMegaPlanner/Log.cs | 174 +-
- Tools/ArdupilotMegaPlanner/MainV2.cs | 9 +-
+ ArduCopter/heli.pde | 25 +
+ ArduCopter/motors.pde | 4 +-
+ ArduCopter/navigation.pde | 42 +-
+ ArduCopter/radio.pde | 14 +-
+ ArduCopter/system.pde | 36 +-
+ ArduPlane/.gitignore | 1 -
+ ArduPlane/ArduPlane.pde | 27 +-
+ ArduPlane/CMakeLists.txt | 168 -
+ ArduPlane/GCS.h | 7 +-
+ ArduPlane/GCS_Mavlink.pde | 464 +++-
+ ArduPlane/Log.pde | 10 +-
+ ArduPlane/Mavlink_compat.h | 172 +
+ ArduPlane/Parameters.h | 12 +-
+ ArduPlane/commands.pde | 65 +-
+ ArduPlane/commands_logic.pde | 152 +-
+ ArduPlane/commands_process.pde | 183 +-
+ ArduPlane/config.h | 5 +
+ ArduPlane/defines.h | 3 +-
+ ArduPlane/navigation.pde | 2 +-
+ ArduPlane/system.pde | 21 +-
+ ArduPlane/test.pde | 6 +-
+ ArduRover/ArduRover.cpp | 6 +-
+ ArduRover/ArduRover.pde | 1 +
+ ArduRover/CarStampede.h | 31 +-
+ ArduRover/ControllerCar.h | 158 +-
+ ArduRover/ControllerTank.h | 176 +-
+ ArduRover/TankGeneric.h | 16 +-
+ CMakeLists.txt | 9 +-
+ Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj | 9 +
+ Tools/ArdupilotMegaPlanner/Camera.Designer.cs | 421 +++
+ Tools/ArdupilotMegaPlanner/Camera.cs | 139 +
+ Tools/ArdupilotMegaPlanner/Camera.resx | 120 +
+ Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs | 12 +-
+ Tools/ArdupilotMegaPlanner/CurrentState.cs | 81 +-
+ .../GCSViews/Configuration.Designer.cs | 137 +-
+ .../ArdupilotMegaPlanner/GCSViews/Configuration.cs | 47 +-
+ .../GCSViews/Configuration.resx | 2088 +++++-------
+ Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs | 12 +-
+ .../GCSViews/FlightData.Designer.cs | 155 +-
+ Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs | 164 +-
+ .../ArdupilotMegaPlanner/GCSViews/FlightData.resx | 604 ++--
+ .../ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 4 +-
+ Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs | 18 +-
+ Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs | 7 +
+ Tools/ArdupilotMegaPlanner/Joystick.cs | 50 +-
+ .../ArdupilotMegaPlanner/JoystickSetup.Designer.cs | 276 ++-
+ Tools/ArdupilotMegaPlanner/JoystickSetup.cs | 125 +-
+ Tools/ArdupilotMegaPlanner/JoystickSetup.resx | 763 ++++-
+ Tools/ArdupilotMegaPlanner/MAVLink.cs | 11 +-
+ Tools/ArdupilotMegaPlanner/MainV2.cs | 87 +-
+ Tools/ArdupilotMegaPlanner/MavlinkLog.cs | 9 +-
+ Tools/ArdupilotMegaPlanner/Program.cs | 1 +
.../Properties/AssemblyInfo.cs | 2 +-
+ Tools/ArdupilotMegaPlanner/SerialOutput.cs | 13 +-
+ Tools/ArdupilotMegaPlanner/Setup/Setup.cs | 4 +-
+ Tools/ArdupilotMegaPlanner/Updater/Updater.csproj | 2 +-
.../bin/Release/ArdupilotMegaPlanner.application | 2 +-
- .../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194432 -> 2194944 bytes
+ .../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194944 -> 2188288 bytes
+ .../bin/Release/GCSViews/Configuration.resx | 2088 +++++-------
+ .../bin/Release/GCSViews/FlightData.resx | 604 ++--
+ .../bin/Release/JoystickSetup.resx | 763 ++++-
Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes
Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 20480 bytes
.../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes
.../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 380928 bytes
- apo/ControllerQuad.h | 51 +-
- apo/QuadArducopter.h | 10 +-
- libraries/APO/AP_ArmingMechanism.cpp | 57 +
- libraries/APO/AP_ArmingMechanism.h | 67 +
- libraries/APO/AP_BatteryMonitor.cpp | 2 +
- libraries/APO/AP_BatteryMonitor.h | 58 +-
- libraries/APO/AP_Guide.h | 1 +
- libraries/APO/AP_HardwareAbstractionLayer.h | 13 +
- libraries/APO/AP_Navigator.cpp | 20 +-
- libraries/Desktop/support/FastSerial.cpp | 283 +-
- 27 files changed, 517 insertions(+), 148687 deletions(-)
- delete mode 100644 Tools/ArduTracker/tags
- create mode 100644 libraries/APO/AP_ArmingMechanism.cpp
- create mode 100644 libraries/APO/AP_ArmingMechanism.h
+ Tools/scripts/format.sh | 13 +
+ apo/ControllerPlane.h | 329 +-
+ apo/ControllerQuad.h | 414 +--
+ apo/PlaneEasystar.h | 18 +-
+ apo/QuadArducopter.h | 17 +-
+ apo/apo.pde | 5 +-
+ libraries/APM_BMP085/APM_BMP085.h | 2 +-
+ libraries/APM_PI/APM_PI.cpp | 8 +-
+ libraries/APO/APO.h | 6 +-
+ libraries/APO/APO_DefaultSetup.h | 321 +-
+ libraries/APO/AP_ArmingMechanism.cpp | 14 +-
+ libraries/APO/AP_ArmingMechanism.h | 10 +-
+ libraries/APO/AP_Autopilot.cpp | 461 ++--
+ libraries/APO/AP_Autopilot.h | 195 +-
+ libraries/APO/AP_BatteryMonitor.h | 1 -
+ libraries/APO/AP_CommLink.cpp | 1280 ++++----
+ libraries/APO/AP_CommLink.h | 126 +-
+ libraries/APO/AP_Controller.cpp | 111 +-
+ libraries/APO/AP_Controller.h | 402 ++-
+ libraries/APO/AP_Guide.cpp | 429 ++-
+ libraries/APO/AP_Guide.h | 203 +-
+ libraries/APO/AP_HardwareAbstractionLayer.cpp | 1 +
+ libraries/APO/AP_HardwareAbstractionLayer.h | 258 +-
+ libraries/APO/AP_MavlinkCommand.cpp | 304 +-
+ libraries/APO/AP_MavlinkCommand.h | 654 ++--
+ libraries/APO/AP_Navigator.cpp | 298 +-
+ libraries/APO/AP_Navigator.h | 358 +-
+ libraries/APO/AP_RcChannel.cpp | 125 +-
+ libraries/APO/AP_RcChannel.h | 103 +-
+ libraries/APO/AP_Var_keys.h | 21 +-
+ libraries/APO/constants.h | 1 +
+ libraries/APO/examples/MavlinkTest/MavlinkTest.pde | 64 +-
+ libraries/APO/examples/ServoManual/ServoManual.pde | 144 +-
+ libraries/APO/examples/ServoSweep/ServoSweep.pde | 184 +-
+ libraries/AP_Common/AP_Common.h | 20 +-
+ libraries/AP_Common/AP_Test.h | 4 +-
+ libraries/AP_Common/AP_Var.cpp | 80 +-
+ libraries/AP_Common/AP_Var.h | 12 +-
+ libraries/AP_Common/c++.cpp | 22 +-
+ libraries/AP_Common/examples/menu/menu.pde | 22 +-
+ libraries/AP_Common/include/menu.h | 186 +-
+ libraries/AP_Common/menu.cpp | 198 +-
+ libraries/AP_DCM/AP_DCM_HIL.cpp | 12 +-
+ libraries/AP_GPS/AP_GPS_406.cpp | 72 +-
+ libraries/AP_GPS/AP_GPS_406.h | 8 +-
+ libraries/AP_GPS/AP_GPS_Auto.cpp | 316 +-
+ libraries/AP_GPS/AP_GPS_Auto.h | 58 +-
+ libraries/AP_GPS/AP_GPS_HIL.cpp | 18 +-
+ libraries/AP_GPS/AP_GPS_HIL.h | 10 +-
+ libraries/AP_GPS/AP_GPS_IMU.cpp | 294 +-
+ libraries/AP_GPS/AP_GPS_IMU.h | 68 +-
+ libraries/AP_GPS/AP_GPS_MTK.cpp | 226 +-
+ libraries/AP_GPS/AP_GPS_MTK.h | 74 +-
+ libraries/AP_GPS/AP_GPS_MTK16.cpp | 240 +-
+ libraries/AP_GPS/AP_GPS_MTK16.h | 78 +-
+ libraries/AP_GPS/AP_GPS_NMEA.cpp | 528 ++--
+ libraries/AP_GPS/AP_GPS_NMEA.h | 118 +-
+ libraries/AP_GPS/AP_GPS_None.h | 8 +-
+ libraries/AP_GPS/AP_GPS_SIRF.cpp | 280 +-
+ libraries/AP_GPS/AP_GPS_SIRF.h | 130 +-
+ libraries/AP_GPS/AP_GPS_Shim.h | 38 +-
+ libraries/AP_GPS/AP_GPS_UBLOX.cpp | 292 +-
+ libraries/AP_GPS/AP_GPS_UBLOX.h | 184 +-
+ libraries/AP_GPS/GPS.cpp | 50 +-
+ libraries/AP_GPS/GPS.h | 330 +-
+ .../AP_GPS/examples/GPS_406_test/GPS_406_test.pde | 62 +-
+ .../examples/GPS_AUTO_test/GPS_AUTO_test.pde | 42 +-
+ .../AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde | 60 +-
+ .../examples/GPS_NMEA_test/GPS_NMEA_test.pde | 81 +-
+ .../examples/GPS_UBLOX_test/GPS_UBLOX_test.pde | 60 +-
+ libraries/Desktop/Desktop.mk | 2 +-
+ libraries/Desktop/Makefile.desktop | 3 +
+ libraries/GCS_MAVLink/GCS_MAVLink.cpp | 6 +-
+ libraries/GCS_MAVLink/GCS_MAVLink.h | 18 +-
+ .../include/ardupilotmega/ardupilotmega.h | 74 +-
+ .../include/ardupilotmega/mavlink_msg_ap_adc.h | 254 ++
+ .../ardupilotmega/mavlink_msg_digicam_configure.h | 364 ++
+ .../ardupilotmega/mavlink_msg_digicam_control.h | 342 ++
+ .../ardupilotmega/mavlink_msg_mount_configure.h | 254 ++
+ .../ardupilotmega/mavlink_msg_mount_control.h | 254 ++
+ .../ardupilotmega/mavlink_msg_mount_status.h | 232 ++
+ .../GCS_MAVLink/include/ardupilotmega/testsuite.h | 340 ++
+ .../GCS_MAVLink/include/ardupilotmega/version.h | 2 +-
+ libraries/GCS_MAVLink/include/bittest.c | 39 -
+ libraries/GCS_MAVLink/include/common/common.h | 52 +-
+ .../mavlink_msg_attitude_controller_output.h | 169 -
+ .../include/common/mavlink_msg_attitude_new.h | 268 --
+ .../include/common/mavlink_msg_auth_key.h | 6 +-
+ .../common/mavlink_msg_change_operator_control.h | 6 +-
+ .../include/common/mavlink_msg_debug_vect.h | 6 +-
+ .../include/common/mavlink_msg_full_state.h | 428 ---
+ .../include/common/mavlink_msg_gps_status.h | 30 +-
+ .../include/common/mavlink_msg_named_value_float.h | 6 +-
+ .../include/common/mavlink_msg_named_value_int.h | 6 +-
+ .../common/mavlink_msg_object_detection_event.h | 6 +-
+ .../common/mavlink_msg_param_request_read.h | 6 +-
+ .../include/common/mavlink_msg_param_set.h | 6 +-
+ .../include/common/mavlink_msg_param_value.h | 6 +-
+ .../mavlink_msg_position_controller_output.h | 169 -
+ .../mavlink_msg_request_dynamic_gyro_calibration.h | 177 -
+ .../mavlink_msg_request_static_calibration.h | 138 -
+ .../common/mavlink_msg_set_roll_pitch_yaw.h | 184 -
+ .../common/mavlink_msg_set_roll_pitch_yaw_speed.h | 184 -
+ .../include/common/mavlink_msg_statustext.h | 6 +-
+ .../mavlink_msg_waypoint_set_global_reference.h | 294 --
+ libraries/GCS_MAVLink/include/common/testsuite.h | 30 +-
+ libraries/GCS_MAVLink/include/common/version.h | 2 +-
+ libraries/GCS_MAVLink/include/documentation.dox | 41 -
+ libraries/GCS_MAVLink/include/mavlink_helpers.h | 8 +-
+ libraries/GCS_MAVLink/include/minimal/mavlink.h | 11 -
+ .../include/minimal/mavlink_msg_heartbeat.h | 132 -
+ libraries/GCS_MAVLink/include/minimal/minimal.h | 45 -
+ libraries/GCS_MAVLink/include/pixhawk/mavlink.h | 11 -
+ .../include/pixhawk/mavlink_msg_attitude_control.h | 257 --
+ .../include/pixhawk/mavlink_msg_aux_status.h | 204 -
+ .../include/pixhawk/mavlink_msg_brief_feature.h | 249 --
+ .../include/pixhawk/mavlink_msg_control_status.h | 203 -
+ .../mavlink_msg_data_transmission_handshake.h | 174 -
+ .../include/pixhawk/mavlink_msg_debug_vect.h | 156 -
+ .../pixhawk/mavlink_msg_encapsulated_data.h | 124 -
+ .../pixhawk/mavlink_msg_encapsulated_image.h | 76 -
+ .../include/pixhawk/mavlink_msg_get_image_ack.h | 104 -
+ .../include/pixhawk/mavlink_msg_image_available.h | 586 ---
+ .../pixhawk/mavlink_msg_image_trigger_control.h | 101 -
+ .../include/pixhawk/mavlink_msg_image_triggered.h | 352 --
+ .../include/pixhawk/mavlink_msg_manual_control.h | 191 -
+ .../include/pixhawk/mavlink_msg_marker.h | 236 --
+ .../include/pixhawk/mavlink_msg_pattern_detected.h | 160 -
+ .../pixhawk/mavlink_msg_point_of_interest.h | 241 --
+ .../mavlink_msg_point_of_interest_connection.h | 307 --
+ .../mavlink_msg_position_control_offset_set.h | 206 -
+ .../mavlink_msg_position_control_setpoint.h | 192 -
+ .../mavlink_msg_position_control_setpoint_set.h | 226 --
+ .../include/pixhawk/mavlink_msg_raw_aux.h | 226 --
+ .../pixhawk/mavlink_msg_request_data_stream.h | 118 -
+ .../mavlink_msg_request_dynamic_gyro_calibration.h | 123 -
+ .../mavlink_msg_request_static_calibration.h | 90 -
+ .../include/pixhawk/mavlink_msg_set_altitude.h | 78 -
+ .../include/pixhawk/mavlink_msg_set_cam_shutter.h | 197 -
+ .../include/pixhawk/mavlink_msg_watchdog_command.h | 158 -
+ .../pixhawk/mavlink_msg_watchdog_heartbeat.h | 124 -
+ .../pixhawk/mavlink_msg_watchdog_process_info.h | 186 -
+ .../pixhawk/mavlink_msg_watchdog_process_status.h | 200 -
+ libraries/GCS_MAVLink/include/pixhawk/pixhawk.h | 79 -
+ libraries/GCS_MAVLink/include/protocol.h | 37 +-
+ libraries/GCS_MAVLink/include/slugs/mavlink.h | 11 -
+ .../include/slugs/mavlink_msg_air_data.h | 148 -
+ .../include/slugs/mavlink_msg_cpu_load.h | 138 -
+ .../include/slugs/mavlink_msg_ctrl_srfc_pt.h | 121 -
+ .../include/slugs/mavlink_msg_data_log.h | 216 --
+ .../include/slugs/mavlink_msg_diagnostic.h | 210 --
+ .../include/slugs/mavlink_msg_filtered_data.h | 216 --
+ .../include/slugs/mavlink_msg_gps_date_time.h | 203 -
+ .../include/slugs/mavlink_msg_mid_lvl_cmds.h | 167 -
+ .../GCS_MAVLink/include/slugs/mavlink_msg_pid.h | 130 -
+ .../include/slugs/mavlink_msg_pilot_console.h | 145 -
+ .../include/slugs/mavlink_msg_pwm_commands.h | 235 --
+ .../include/slugs/mavlink_msg_sensor_bias.h | 216 --
+ .../include/slugs/mavlink_msg_slugs_action.h | 138 -
+ .../include/slugs/mavlink_msg_slugs_navigation.h | 272 --
+ libraries/GCS_MAVLink/include/slugs/slugs.h | 56 -
+ libraries/GCS_MAVLink/include/ualberta/mavlink.h | 11 -
+ .../include/ualberta/mavlink_msg_nav_filter_bias.h | 242 --
+ .../ualberta/mavlink_msg_radio_calibration.h | 204 -
+ .../mavlink_msg_request_radio_calibration.h | 59 -
+ .../ualberta/mavlink_msg_request_rc_channels.h | 101 -
+ .../ualberta/mavlink_msg_ualberta_sys_status.h | 135 -
+ libraries/GCS_MAVLink/include/ualberta/ualberta.h | 79 -
+ .../include_v1.0/ardupilotmega/ardupilotmega.h | 122 +
+ .../include_v1.0/ardupilotmega/mavlink.h | 27 +
+ .../ardupilotmega/mavlink_msg_ap_adc.h | 254 ++
+ .../ardupilotmega/mavlink_msg_digicam_configure.h | 364 ++
+ .../ardupilotmega/mavlink_msg_digicam_control.h | 342 ++
+ .../ardupilotmega/mavlink_msg_meminfo.h | 166 +
+ .../ardupilotmega/mavlink_msg_mount_configure.h | 254 ++
+ .../ardupilotmega/mavlink_msg_mount_control.h | 254 ++
+ .../ardupilotmega/mavlink_msg_mount_status.h | 232 ++
+ .../ardupilotmega/mavlink_msg_sensor_offsets.h | 386 ++
+ .../ardupilotmega/mavlink_msg_set_mag_offsets.h | 232 ++
+ .../include_v1.0/ardupilotmega/testsuite.h | 538 +++
+ .../include_v1.0/ardupilotmega/version.h | 12 +
+ libraries/GCS_MAVLink/include_v1.0/checksum.h | 89 +
+ libraries/GCS_MAVLink/include_v1.0/common/common.h | 429 +++
+ .../GCS_MAVLink/include_v1.0/common/mavlink.h | 27 +
+ .../include_v1.0/common/mavlink_msg_attitude.h | 276 ++
+ .../common/mavlink_msg_attitude_quaternion.h | 298 ++
+ .../include_v1.0/common/mavlink_msg_auth_key.h | 144 +
+ .../common/mavlink_msg_change_operator_control.h | 204 +
+ .../mavlink_msg_change_operator_control_ack.h | 188 +
+ .../include_v1.0/common/mavlink_msg_command_ack.h | 166 +
+ .../include_v1.0/common/mavlink_msg_command_long.h | 364 ++
+ .../include_v1.0/common/mavlink_msg_data_stream.h | 188 +
+ .../include_v1.0/common/mavlink_msg_debug.h | 188 +
+ .../include_v1.0/common/mavlink_msg_debug_vect.h | 226 ++
+ .../common/mavlink_msg_extended_message.h | 188 +
+ .../common/mavlink_msg_global_position_int.h | 320 ++
+ .../mavlink_msg_global_position_setpoint_int.h | 232 ++
+ .../mavlink_msg_global_vision_position_estimate.h | 276 ++
+ .../common/mavlink_msg_gps_global_origin.h | 188 +
+ .../include_v1.0/common/mavlink_msg_gps_raw_int.h | 342 ++
+ .../include_v1.0/common/mavlink_msg_gps_status.h | 252 ++
+ .../include_v1.0/common/mavlink_msg_heartbeat.h | 251 ++
+ .../include_v1.0/common/mavlink_msg_hil_controls.h | 364 ++
+ .../common/mavlink_msg_hil_rc_inputs_raw.h | 430 +++
+ .../include_v1.0/common/mavlink_msg_hil_state.h | 474 +++
+ .../common/mavlink_msg_local_position_ned.h | 276 ++
+ .../common/mavlink_msg_local_position_setpoint.h | 232 ++
+ .../common/mavlink_msg_manual_control.h | 320 ++
+ .../include_v1.0/common/mavlink_msg_memory_vect.h | 204 +
+ .../include_v1.0/common/mavlink_msg_mission_ack.h | 188 +
+ .../common/mavlink_msg_mission_clear_all.h | 166 +
+ .../common/mavlink_msg_mission_count.h | 188 +
+ .../common/mavlink_msg_mission_current.h | 144 +
+ .../include_v1.0/common/mavlink_msg_mission_item.h | 430 +++
+ .../common/mavlink_msg_mission_item_reached.h | 144 +
+ .../common/mavlink_msg_mission_request.h | 188 +
+ .../common/mavlink_msg_mission_request_list.h | 166 +
+ .../mavlink_msg_mission_request_partial_list.h | 210 ++
+ .../common/mavlink_msg_mission_set_current.h | 188 +
+ .../mavlink_msg_mission_write_partial_list.h | 210 ++
+ .../common/mavlink_msg_named_value_float.h | 182 +
+ .../common/mavlink_msg_named_value_int.h | 182 +
+ .../common/mavlink_msg_nav_controller_output.h | 298 ++
+ .../include_v1.0/common/mavlink_msg_optical_flow.h | 254 ++
+ .../common/mavlink_msg_param_request_list.h | 166 +
+ .../common/mavlink_msg_param_request_read.h | 204 +
+ .../include_v1.0/common/mavlink_msg_param_set.h | 226 ++
+ .../include_v1.0/common/mavlink_msg_param_value.h | 226 ++
+ .../include_v1.0/common/mavlink_msg_ping.h | 210 ++
+ .../include_v1.0/common/mavlink_msg_raw_imu.h | 342 ++
+ .../include_v1.0/common/mavlink_msg_raw_pressure.h | 232 ++
+ .../common/mavlink_msg_rc_channels_override.h | 342 ++
+ .../common/mavlink_msg_rc_channels_raw.h | 364 ++
+ .../common/mavlink_msg_rc_channels_scaled.h | 364 ++
+ .../common/mavlink_msg_request_data_stream.h | 232 ++
+ ...link_msg_roll_pitch_yaw_speed_thrust_setpoint.h | 232 ++
+ .../mavlink_msg_roll_pitch_yaw_thrust_setpoint.h | 232 ++
+ .../common/mavlink_msg_safety_allowed_area.h | 276 ++
+ .../common/mavlink_msg_safety_set_allowed_area.h | 320 ++
+ .../include_v1.0/common/mavlink_msg_scaled_imu.h | 342 ++
+ .../common/mavlink_msg_scaled_pressure.h | 210 ++
+ .../common/mavlink_msg_servo_output_raw.h | 342 ++
+ .../mavlink_msg_set_global_position_setpoint_int.h | 232 ++
+ .../common/mavlink_msg_set_gps_global_origin.h | 210 ++
+ .../mavlink_msg_set_local_position_setpoint.h | 276 ++
+ .../include_v1.0/common/mavlink_msg_set_mode.h | 188 +
+ .../mavlink_msg_set_roll_pitch_yaw_speed_thrust.h | 254 ++
+ .../common/mavlink_msg_set_roll_pitch_yaw_thrust.h | 254 ++
+ .../common/mavlink_msg_state_correction.h | 320 ++
+ .../include_v1.0/common/mavlink_msg_statustext.h | 160 +
+ .../include_v1.0/common/mavlink_msg_sys_status.h | 408 ++
+ .../include_v1.0/common/mavlink_msg_system_time.h | 166 +
+ .../include_v1.0/common/mavlink_msg_vfr_hud.h | 254 ++
+ .../common}/mavlink_msg_vicon_position_estimate.h | 198 +-
+ .../common}/mavlink_msg_vision_position_estimate.h | 198 +-
+ .../common}/mavlink_msg_vision_speed_estimate.h | 148 +-
+ .../GCS_MAVLink/include_v1.0/common/testsuite.h | 3908 ++++++++++++++++++++
+ .../GCS_MAVLink/include_v1.0/common/version.h | 12 +
+ .../GCS_MAVLink/include_v1.0/mavlink_helpers.h | 488 +++
+ libraries/GCS_MAVLink/include_v1.0/mavlink_types.h | 182 +
+ libraries/GCS_MAVLink/include_v1.0/protocol.h | 319 ++
+ .../message_definitions/ardupilotmega.xml | 132 +
+ libraries/GCS_MAVLink/message_definitions/test.xml | 31 +
+ .../message_definitions_v1.0/ardupilotmega.xml | 177 +
+ .../message_definitions_v1.0/common.xml | 1536 ++++++++
+ .../message_definitions_v1.0/minimal.xml | 16 +
+ .../message_definitions_v1.0/pixhawk.xml | 193 +
+ .../GCS_MAVLink/message_definitions_v1.0/slugs.xml | 144 +
+ .../GCS_MAVLink/message_definitions_v1.0/test.xml | 31 +
+ .../message_definitions_v1.0/ualberta.xml | 54 +
+ libraries/RC_Channel/RC_Channel.cpp | 2 +-
+ libraries/RC_Channel/RC_Channel.h | 8 +-
+ libraries/RC_Channel/RC_Channel_aux.cpp | 2 +-
+ libraries/RC_Channel/RC_Channel_aux.h | 1 +
+ 355 files changed, 43388 insertions(+), 22115 deletions(-)
+ delete mode 100644 ArduCopter/CMakeLists.txt
+ delete mode 100644 ArduPlane/.gitignore
+ delete mode 100644 ArduPlane/CMakeLists.txt
+ create mode 100644 ArduPlane/Mavlink_compat.h
+ create mode 100644 Tools/ArdupilotMegaPlanner/Camera.Designer.cs
+ create mode 100644 Tools/ArdupilotMegaPlanner/Camera.cs
+ create mode 100644 Tools/ArdupilotMegaPlanner/Camera.resx
+ create mode 100755 Tools/scripts/format.sh
+ create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_adc.h
+ create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_digicam_configure.h
+ create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_digicam_control.h
+ create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_configure.h
+ create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_control.h
+ create mode 100644 libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_mount_status.h
+ delete mode 100644 libraries/GCS_MAVLink/include/bittest.c
+ delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_attitude_controller_output.h
+ delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_attitude_new.h
+ delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_full_state.h
+ delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_position_controller_output.h
+ delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_request_dynamic_gyro_calibration.h
+ delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_request_static_calibration.h
+ delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw.h
+ delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_set_roll_pitch_yaw_speed.h
+ delete mode 100644 libraries/GCS_MAVLink/include/common/mavlink_msg_waypoint_set_global_reference.h
+ delete mode 100644 libraries/GCS_MAVLink/include/documentation.dox
+ delete mode 100644 libraries/GCS_MAVLink/include/minimal/mavlink.h
+ delete mode 100644 libraries/GCS_MAVLink/include/minimal/mavlink_msg_heartbeat.h
+ delete mode 100644 libraries/GCS_MAVLink/include/minimal/minimal.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_attitude_control.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_aux_status.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_brief_feature.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_control_status.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_data_transmission_handshake.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_debug_vect.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_encapsulated_data.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_encapsulated_image.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_get_image_ack.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_available.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_trigger_control.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_image_triggered.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_manual_control.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_marker.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_pattern_detected.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_point_of_interest.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_point_of_interest_connection.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_offset_set.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_setpoint.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_position_control_setpoint_set.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_raw_aux.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_data_stream.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_dynamic_gyro_calibration.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_request_static_calibration.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_set_altitude.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_set_cam_shutter.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_command.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_heartbeat.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_process_info.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/mavlink_msg_watchdog_process_status.h
+ delete mode 100644 libraries/GCS_MAVLink/include/pixhawk/pixhawk.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_air_data.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_cpu_load.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_ctrl_srfc_pt.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_data_log.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_diagnostic.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_filtered_data.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_gps_date_time.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_mid_lvl_cmds.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pid.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pilot_console.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_pwm_commands.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_sensor_bias.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_action.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/mavlink_msg_slugs_navigation.h
+ delete mode 100644 libraries/GCS_MAVLink/include/slugs/slugs.h
+ delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink.h
+ delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_nav_filter_bias.h
+ delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_radio_calibration.h
+ delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_request_radio_calibration.h
+ delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_request_rc_channels.h
+ delete mode 100644 libraries/GCS_MAVLink/include/ualberta/mavlink_msg_ualberta_sys_status.h
+ delete mode 100644 libraries/GCS_MAVLink/include/ualberta/ualberta.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_ap_adc.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_digicam_configure.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_digicam_control.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_meminfo.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_configure.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_control.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_mount_status.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/checksum.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/common.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude_quaternion.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_auth_key.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control_ack.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_long.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_data_stream.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug_vect.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_extended_message.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_int.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_setpoint_int.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_vision_position_estimate.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_global_origin.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_raw_int.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_status.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_heartbeat.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_controls.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_rc_inputs_raw.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_state.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_ned.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_setpoint.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_manual_control.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_memory_vect.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_clear_all.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_count.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_current.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item_reached.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_list.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_partial_list.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_set_current.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_write_partial_list.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_float.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_int.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_nav_controller_output.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_optical_flow.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_list.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_read.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_ping.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_imu.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_pressure.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_override.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_raw.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_scaled.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_request_data_stream.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_allowed_area.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_set_allowed_area.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_imu.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_pressure.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_servo_output_raw.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_global_position_setpoint_int.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_gps_global_origin.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_local_position_setpoint.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_mode.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_state_correction.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_statustext.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_sys_status.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_system_time.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vfr_hud.h
+ rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vicon_position_estimate.h (54%)
+ rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vision_position_estimate.h (54%)
+ rename libraries/GCS_MAVLink/{include/pixhawk => include_v1.0/common}/mavlink_msg_vision_speed_estimate.h (57%)
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/testsuite.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/common/version.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/mavlink_helpers.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/mavlink_types.h
+ create mode 100644 libraries/GCS_MAVLink/include_v1.0/protocol.h
+ create mode 100644 libraries/GCS_MAVLink/message_definitions/test.xml
+ create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
+ create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/common.xml
+ create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml
+ create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml
+ create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml
+ create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/test.xml
+ create mode 100644 libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
index a72e79be4a..8ace5c5fd5 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
@@ -488,6 +488,11 @@ namespace ArdupilotMega.GCSViews
((DomainUpDown)text[0]).SelectedIndex = index;
((DomainUpDown)text[0]).BackColor = Color.Green;
}
+ else
+ {
+ ((DomainUpDown)text[0]).Text = option;
+ ((DomainUpDown)text[0]).BackColor = Color.Green;
+ }
}
}
catch { }
@@ -515,8 +520,11 @@ namespace ArdupilotMega.GCSViews
int index = line.IndexOf(',');
+ int index2 = line.IndexOf(',', index + 1);
if (index == -1)
continue;
+ if (index2 != -1)
+ line = line.Replace(',','.');
string name = line.Substring(0, index);
float value = float.Parse(line.Substring(index + 1), new System.Globalization.CultureInfo("en-US"));
@@ -569,7 +577,7 @@ namespace ArdupilotMega.GCSViews
MAVLink.modifyParamForDisplay(false, row.Cells[0].Value.ToString(), ref value);
- sw.WriteLine(row.Cells[0].Value.ToString() + "," + value);
+ sw.WriteLine(row.Cells[0].Value.ToString() + "," + value.ToString(new System.Globalization.CultureInfo("en-US")));
}
sw.Close();
}
diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
index 421048b251..61c3a2661e 100644
--- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
+++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
@@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.0.0.0")]
-[assembly: AssemblyFileVersion("1.0.87")]
+[assembly: AssemblyFileVersion("1.0.88")]
[assembly: NeutralResourcesLanguageAttribute("")]
diff --git a/Tools/ArdupilotMegaPlanner/app.config b/Tools/ArdupilotMegaPlanner/app.config
index ea54d4e7bc..6b78cb190d 100644
--- a/Tools/ArdupilotMegaPlanner/app.config
+++ b/Tools/ArdupilotMegaPlanner/app.config
@@ -2,12 +2,6 @@
-
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application
index a4d78a16dc..7373ea86b1 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application
@@ -11,7 +11,7 @@
- S+dMQOC9TeJyQiYvhw37LpJxZU0=
+ wRpim3tDq7ttru3QnVS/G/tNt8A=
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.exe.config b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.exe.config
index ea54d4e7bc..6b78cb190d 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.exe.config
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.exe.config
@@ -2,12 +2,6 @@
-
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/dataflashlog.xml b/Tools/ArdupilotMegaPlanner/bin/Release/dataflashlog.xml
index 7969461052..430e3cc231 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/dataflashlog.xml
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/dataflashlog.xml
@@ -22,10 +22,15 @@
WP Dist
- WP Verify
- Target Bear
- Long Err
- Lat Err
+ Target Bear
+ Long Err
+ Lat Err
+ nav lon
+ nav lat
+ nav lon I
+ nav lat I
+ Loiter Lon I
+ Loiter Lat I
Yaw Sensor
diff --git a/Tools/ArdupilotMegaPlanner/dataflashlog.xml b/Tools/ArdupilotMegaPlanner/dataflashlog.xml
index 7969461052..430e3cc231 100644
--- a/Tools/ArdupilotMegaPlanner/dataflashlog.xml
+++ b/Tools/ArdupilotMegaPlanner/dataflashlog.xml
@@ -22,10 +22,15 @@
WP Dist
- WP Verify
- Target Bear
- Long Err
- Lat Err
+ Target Bear
+ Long Err
+ Lat Err
+ nav lon
+ nav lat
+ nav lon I
+ nav lat I
+ Loiter Lon I
+ Loiter Lat I
Yaw Sensor
diff --git a/Tools/autotest/ArduCopter.parm b/Tools/autotest/ArduCopter.parm
new file mode 100644
index 0000000000..3465fc56d2
--- /dev/null
+++ b/Tools/autotest/ArduCopter.parm
@@ -0,0 +1,40 @@
+FRAME 0
+RC1_MAX 2000.000000
+RC1_MIN 1000.000000
+RC1_TRIM 1500.000000
+RC2_MAX 2000.000000
+RC2_MIN 1000.000000
+RC2_TRIM 1500.000000
+RC3_MAX 2000.000000
+RC3_MIN 1000.000000
+RC3_TRIM 1500.000000
+RC4_MAX 2000.000000
+RC4_MIN 1000.000000
+RC4_TRIM 1500.000000
+RC5_MAX 2000.000000
+RC5_MIN 1000.000000
+RC5_TRIM 1500.000000
+RC6_MAX 2000.000000
+RC6_MIN 1000.000000
+RC6_TRIM 1500.000000
+RC7_MAX 2000.000000
+RC7_MIN 1000.000000
+RC7_TRIM 1500.000000
+RC8_MAX 2000.000000
+RC8_MIN 1000.000000
+RC8_TRIM 1500.000000
+FLTMODE1 3
+FLTMODE2 1
+FLTMODE3 2
+FLTMODE4 6
+FLTMODE5 5
+FLTMODE6 0
+NAV_LAT_I 0
+NAV_LON_I 0
+NAV_LAT_P 1
+NAV_LON_P 1
+STB_PIT_P 2
+STB_RLL_P 2
+XTRACK_P 1
+RATE_PIT_P 0.1
+RATE_RLL_P 0.1
diff --git a/Tools/autotest/README b/Tools/autotest/README
new file mode 100644
index 0000000000..ba3d36dd04
--- /dev/null
+++ b/Tools/autotest/README
@@ -0,0 +1 @@
+This is an automated test suite for APM
diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py
new file mode 100644
index 0000000000..a98c8bf337
--- /dev/null
+++ b/Tools/autotest/arducopter.py
@@ -0,0 +1,324 @@
+# fly ArduCopter in SIL
+
+import util, pexpect, sys, time, math, shutil, os
+
+# get location of scripts
+testdir=os.path.dirname(os.path.realpath(__file__))
+
+sys.path.insert(0, util.reltopdir('../pymavlink'))
+import mavutil
+
+HOME_LOCATION='-35.362938,149.165085,650,270'
+
+# a list of pexpect objects to read while waiting for
+# messages. This keeps the output to stdout flowing
+expect_list = []
+
+def message_hook(mav, msg):
+ '''called as each mavlink msg is received'''
+ global expect_list
+ if msg.get_type() in [ 'NAV_CONTROLLER_OUTPUT' ]:
+ print(msg)
+ for p in expect_list:
+ try:
+ p.read_nonblocking(100, timeout=0)
+ except pexpect.TIMEOUT:
+ pass
+
+def expect_callback(e):
+ '''called when waiting for a expect pattern'''
+ global expect_list
+ for p in expect_list:
+ if p == e:
+ continue
+ try:
+ while p.read_nonblocking(100, timeout=0):
+ pass
+ except pexpect.TIMEOUT:
+ pass
+
+
+class location(object):
+ '''represent a GPS coordinate'''
+ def __init__(self, lat, lng, alt=0):
+ self.lat = lat
+ self.lng = lng
+ self.alt = alt
+
+def get_distance(loc1, loc2):
+ '''get ground distance between two locations'''
+ dlat = loc2.lat - loc1.lat
+ dlong = loc2.lng - loc1.lng
+ return math.sqrt((dlat*dlat) + (dlong*dlong)) * 1.113195e5
+
+def get_bearing(loc1, loc2):
+ '''get bearing from loc1 to loc2'''
+ off_x = loc2.lng - loc1.lng
+ off_y = loc2.lat - loc1.lat
+ bearing = 90.00 + math.atan2(-off_y, off_x) * 57.2957795
+ if bearing < 0:
+ bearing += 360.00
+ return bearing;
+
+def current_location(mav):
+ '''return current location'''
+ return location(mav.messages['GPS_RAW'].lat,
+ mav.messages['GPS_RAW'].lon,
+ mav.messages['VFR_HUD'].alt)
+
+def wait_altitude(mav, alt_min, alt_max, timeout=30):
+ '''wait for a given altitude range'''
+ tstart = time.time()
+ print("Waiting for altitude between %u and %u" % (alt_min, alt_max))
+ while time.time() < tstart + timeout:
+ m = mav.recv_match(type='VFR_HUD', blocking=True)
+ print("Altitude %u" % m.alt)
+ if m.alt >= alt_min and m.alt <= alt_max:
+ return True
+ print("Failed to attain altitude range")
+ return False
+
+
+def arm_motors(mavproxy):
+ '''arm motors'''
+ mavproxy.send('switch 6\n') # stabilize mode
+ mavproxy.expect('STABILIZE>')
+ mavproxy.send('rc 3 1000\n')
+ mavproxy.send('rc 4 2000\n')
+ mavproxy.expect('APM: ARMING MOTORS')
+ mavproxy.send('rc 4 1500\n')
+ print("MOTORS ARMED OK")
+
+def disarm_motors(mavproxy):
+ '''disarm motors'''
+ mavproxy.send('rc 3 1000\n')
+ mavproxy.send('rc 4 1000\n')
+ mavproxy.expect('APM: DISARMING MOTORS')
+ mavproxy.send('rc 4 1500\n')
+ print("MOTORS DISARMED OK")
+
+
+def takeoff(mavproxy, mav):
+ '''takeoff get to 30m altitude'''
+ mavproxy.send('switch 6\n') # stabilize mode
+ mavproxy.expect('STABILIZE>')
+ mavproxy.send('rc 3 1500\n')
+ wait_altitude(mav, 30, 40)
+ print("TAKEOFF COMPLETE")
+
+
+def loiter(mavproxy, mav, maxaltchange=10, holdtime=10, timeout=60):
+ '''hold loiter position'''
+ mavproxy.send('switch 5\n') # loiter mode
+ mavproxy.expect('LOITER>')
+ mavproxy.send('status\n')
+ mavproxy.expect('>')
+ m = mav.recv_match(type='VFR_HUD', blocking=True)
+ start_altitude = m.alt
+ tstart = time.time()
+ tholdstart = time.time()
+ print("Holding loiter at %u meters for %u seconds" % (start_altitude, holdtime))
+ while time.time() < tstart + timeout:
+ m = mav.recv_match(type='VFR_HUD', blocking=True)
+ print("Altitude %u" % m.alt)
+ if math.fabs(m.alt - start_altitude) > maxaltchange:
+ tholdstart = time.time()
+ if time.time() - tholdstart > holdtime:
+ print("Loiter OK for %u seconds" % holdtime)
+ return True
+ print("Loiter FAILED")
+ return False
+
+
+def wait_heading(mav, heading, accuracy=5, timeout=30):
+ '''wait for a given heading'''
+ tstart = time.time()
+ while time.time() < tstart + timeout:
+ m = mav.recv_match(type='VFR_HUD', blocking=True)
+ print("Heading %u" % m.heading)
+ if math.fabs(m.heading - heading) <= accuracy:
+ return True
+ print("Failed to attain heading %u" % heading)
+ return False
+
+
+def wait_distance(mav, distance, accuracy=5, timeout=30):
+ '''wait for flight of a given distance'''
+ tstart = time.time()
+ start = current_location(mav)
+ while time.time() < tstart + timeout:
+ m = mav.recv_match(type='GPS_RAW', blocking=True)
+ pos = current_location(mav)
+ delta = get_distance(start, pos)
+ print("Distance %.2f meters" % delta)
+ if math.fabs(delta - distance) <= accuracy:
+ return True
+ print("Failed to attain distance %u" % distance)
+ return False
+
+def wait_location(mav, loc, accuracy=5, timeout=30):
+ '''wait for arrival at a location'''
+ tstart = time.time()
+ while time.time() < tstart + timeout:
+ m = mav.recv_match(type='GPS_RAW', blocking=True)
+ pos = current_location(mav)
+ delta = get_distance(loc, pos)
+ print("Distance %.2f meters" % delta)
+ if delta <= accuracy:
+ return True
+ print("Failed to attain location")
+ return False
+
+
+def fly_square(mavproxy, mav, side=50, timeout=120):
+ '''fly a square, flying N then E'''
+ mavproxy.send('switch 6\n')
+ mavproxy.expect('STABILIZE>')
+ tstart = time.time()
+ mavproxy.send('rc 3 1430\n')
+ mavproxy.send('rc 4 1610\n')
+ if not wait_heading(mav, 0):
+ return False
+ mavproxy.send('rc 4 1500\n')
+
+ print("Going north %u meters" % side)
+ mavproxy.send('rc 2 1390\n')
+ ok = wait_distance(mav, side)
+ mavproxy.send('rc 2 1500\n')
+
+ print("Going east %u meters" % side)
+ mavproxy.send('rc 1 1610\n')
+ ok = wait_distance(mav, side)
+ mavproxy.send('rc 1 1500\n')
+
+ print("Going south %u meters" % side)
+ mavproxy.send('rc 2 1610\n')
+ ok = wait_distance(mav, side)
+ mavproxy.send('rc 2 1500\n')
+
+ print("Going west %u meters" % side)
+ mavproxy.send('rc 1 1390\n')
+ ok = wait_distance(mav, side)
+ mavproxy.send('rc 1 1500\n')
+ return ok
+
+
+
+
+def land(mavproxy, mav, timeout=60):
+ '''land the quad'''
+ print("STARTING LANDING")
+ mavproxy.send('switch 6\n')
+ mavproxy.expect('STABILIZE>')
+ mavproxy.send('status\n')
+ mavproxy.expect('>')
+
+ # start by dropping throttle till we have lost 5m
+ mavproxy.send('rc 3 1380\n')
+ m = mav.recv_match(type='VFR_HUD', blocking=True)
+ wait_altitude(mav, 0, m.alt-5)
+
+ # now let it settle gently
+ mavproxy.send('rc 3 1400\n')
+ tstart = time.time()
+ if wait_altitude(mav, -5, 0):
+ print("LANDING OK")
+ return True
+ else:
+ print("LANDING FAILED")
+ return False
+
+
+def fly_mission(mavproxy, mav, filename, timeout=120):
+ '''fly a mission from a file'''
+ startloc = current_location(mav)
+ mavproxy.send('wp load %s\n' % filename)
+ mavproxy.expect('flight plan received')
+ mavproxy.send('wp list\n')
+ mavproxy.expect('Requesting [0-9]+ waypoints')
+ mavproxy.send('switch 1\n') # auto mode
+ mavproxy.expect('AUTO>')
+ wait_distance(mav, 30, timeout=120)
+ wait_location(mav, startloc, timeout=300)
+
+
+def setup_rc(mavproxy):
+ '''setup RC override control'''
+ for chan in range(1,9):
+ mavproxy.send('rc %u 1500\n' % chan)
+ # zero throttle
+ mavproxy.send('rc 3 1000\n')
+
+
+def fly_ArduCopter():
+ '''fly ArduCopter in SIL'''
+ global expect_list
+
+ util.rmfile('eeprom.bin')
+ sil = util.start_SIL('ArduCopter')
+ mavproxy = util.start_MAVProxy_SIL('ArduCopter')
+ mavproxy.expect('Please Run Setup')
+
+ # we need to restart it after eeprom erase
+ mavproxy.close()
+ sil.close()
+ sil = util.start_SIL('ArduCopter')
+ mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:14550 --quadcopter')
+ mavproxy.expect('Received [0-9]+ parameters')
+
+ # setup test parameters
+ mavproxy.send("param load %s/ArduCopter.parm\n" % testdir)
+ mavproxy.expect('Loaded [0-9]+ parameters')
+
+ # reboot with new parameters
+ mavproxy.close()
+ sil.close()
+ sil = util.start_SIL('ArduCopter')
+ mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:14550 --out=192.168.2.15:14550 --quadcopter --streamrate=1')
+ mavproxy.expect('Logging to (\S+)')
+ logfile = mavproxy.match.group(1)
+ print("LOGFILE %s" % logfile)
+ mavproxy.expect("Ready to FLY")
+ mavproxy.expect('Received [0-9]+ parameters')
+
+ util.expect_setup_callback(mavproxy, expect_callback)
+
+ # start hil_quad.py
+ util.run_cmd('pkill -f hil_quad.py', checkfail=False)
+ hquad = pexpect.spawn(util.reltopdir('../HILTest/hil_quad.py') + ' --fgout=192.168.2.15:9123 --home=%s' % HOME_LOCATION,
+ logfile=sys.stdout, timeout=10)
+ hquad.expect('Starting at')
+
+ expect_list.extend([hquad, sil, mavproxy])
+
+ # get a mavlink connection going
+ mav = mavutil.mavlink_connection('127.0.0.1:14550', robust_parsing=True)
+ mav.message_hooks.append(message_hook)
+
+ failed = False
+ try:
+ mav.wait_heartbeat()
+ mav.recv_match(type='GPS_RAW')
+ setup_rc(mavproxy)
+ arm_motors(mavproxy)
+ takeoff(mavproxy, mav)
+ fly_square(mavproxy, mav)
+ loiter(mavproxy, mav)
+ land(mavproxy, mav)
+ fly_mission(mavproxy, mav, os.path.join(testdir, "mission1.txt"))
+ disarm_motors(mavproxy)
+ except pexpect.TIMEOUT, e:
+ failed = True
+
+ mavproxy.close()
+ sil.close()
+ hquad.close()
+
+ shutil.copy(logfile, util.reltopdir("../buildlogs/ArduCopter-test.mavlog"))
+ util.run_cmd(util.reltopdir("../pymavlink/examples/mavtogpx.py") + " " + util.reltopdir("../buildlogs/ArduCopter-test.mavlog"))
+ util.run_cmd(util.reltopdir("../bin/gpxtokml") + " " + util.reltopdir("../buildlogs/ArduCopter-test.mavlog.gpx"))
+
+ if failed:
+ print("FAILED: %s" % e)
+ sys.exit(1)
+
diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py
new file mode 100755
index 0000000000..de645e2952
--- /dev/null
+++ b/Tools/autotest/autotest.py
@@ -0,0 +1,76 @@
+#!/usr/bin/env python
+# APM automatic test suite
+# Andrew Tridgell, October 2011
+
+import pexpect, os, util, sys, shutil, arducopter
+import optparse, fnmatch
+
+os.putenv('TMPDIR', util.reltopdir('tmp'))
+
+def get_default_params(atype):
+ '''get default parameters'''
+ util.rmfile('eeprom.bin')
+ sil = util.start_SIL(atype)
+ mavproxy = util.start_MAVProxy_SIL(atype)
+ idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)'])
+ if idx == 0:
+ # we need to restart it after eeprom erase
+ mavproxy.close()
+ sil.close()
+ sil = util.start_SIL(atype)
+ mavproxy = util.start_MAVProxy_SIL(atype)
+ idx = mavproxy.expect('Saved [0-9]+ parameters to (\S+)')
+ parmfile = mavproxy.match.group(1)
+ dest = util.reltopdir('../buildlogs/%s.defaults.txt' % atype)
+ shutil.copy(parmfile, dest)
+ mavproxy.close()
+ sil.close()
+ print("Saved defaults for %s to %s" % (atype, dest))
+
+
+############## main program #############
+parser = optparse.OptionParser("autotest")
+parser.add_option("--skip", type='string', default='', help='list of steps to skip (comma separated)')
+parser.add_option("--list", action='store_true', default=False, help='list the available steps')
+
+opts, args = parser.parse_args()
+
+steps = [
+ 'build.ArduPlane',
+ 'build.ArduCopter',
+ 'defaults.ArduPlane',
+ 'defaults.ArduCopter',
+ 'fly.ArduCopter'
+ ]
+
+skipsteps = opts.skip.split(',')
+
+def skip_step(step):
+ '''see if a step should be skipped'''
+ for skip in skipsteps:
+ if fnmatch.fnmatch(step, skip):
+ return True
+ return False
+
+# kill any previous instance
+util.kill('ArduCopter.elf')
+util.kill('ArduPilot.elf')
+
+for step in steps:
+ if skip_step(step):
+ continue
+ if step == 'build.ArduPlane':
+ util.build_SIL('ArduPlane')
+ elif step == 'build.ArduCopter':
+ util.build_SIL('ArduCopter')
+ elif step == 'defaults.ArduPlane':
+ get_default_params('ArduPlane')
+ elif step == 'defaults.ArduCopter':
+ get_default_params('ArduCopter')
+ elif step == 'fly.ArduCopter':
+ arducopter.fly_ArduCopter()
+ else:
+ raise RuntimeError("Unknown step %s" % step)
+
+util.kill('ArduCopter.elf')
+util.kill('ArduPilot.elf')
diff --git a/Tools/autotest/mission1.txt b/Tools/autotest/mission1.txt
new file mode 100644
index 0000000000..7162f6a4c7
--- /dev/null
+++ b/Tools/autotest/mission1.txt
@@ -0,0 +1,11 @@
+QGC WPL 110
+0 1 3 0 0.000000 0.000000 0.000000 0.000000 -35.362881 149.165222 582.000000 1
+1 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362324 149.164291 120.000000 1
+2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363670 149.164505 120.000000 1
+3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362358 149.163651 120.000000 1
+4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363777 149.163895 120.000000 1
+5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362411 149.163071 120.000000 1
+6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363865 149.163223 120.000000 1
+7 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362431 149.162384 120.000000 1
+8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363968 149.162567 120.000000 1
+9 0 3 20 0.000000 0.000000 0.000000 0.000000 -35.363228 149.161896 30.000000 1
diff --git a/Tools/autotest/util.py b/Tools/autotest/util.py
new file mode 100644
index 0000000000..df6fd981be
--- /dev/null
+++ b/Tools/autotest/util.py
@@ -0,0 +1,88 @@
+# utility code for autotest
+
+import os, pexpect, sys, time
+from subprocess import call, check_call,Popen, PIPE
+
+
+def topdir():
+ '''return top of git tree where autotest is running from'''
+ d = os.path.dirname(os.path.realpath(__file__))
+ assert(os.path.basename(d)=='autotest')
+ d = os.path.dirname(d)
+ assert(os.path.basename(d)=='Tools')
+ d = os.path.dirname(d)
+ return d
+
+def reltopdir(path):
+ '''return a path relative to topdir()'''
+ return os.path.normpath(os.path.join(topdir(), path))
+
+
+def run_cmd(cmd, dir=".", show=False, output=False, checkfail=True):
+ '''run a shell command'''
+ if show:
+ print("Running: '%s' in '%s'" % (cmd, dir))
+ if output:
+ return Popen([cmd], shell=True, stdout=PIPE, cwd=dir).communicate()[0]
+ elif checkfail:
+ return check_call(cmd, shell=True, cwd=dir)
+ else:
+ return call(cmd, shell=True, cwd=dir)
+
+def rmfile(path):
+ '''remove a file if it exists'''
+ try:
+ os.unlink('eeprom.bin')
+ except Exception:
+ pass
+
+def deltree(path):
+ '''delete a tree of files'''
+ run_cmd('rm -rf %s' % path)
+
+
+
+def build_SIL(atype):
+ '''build desktop SIL'''
+ run_cmd("make -f ../libraries/Desktop/Makefile.desktop clean hil",
+ dir=reltopdir(atype),
+ checkfail=True)
+
+def start_SIL(atype):
+ '''launch a SIL instance'''
+ ret = pexpect.spawn('tmp/%s.build/%s.elf' % (atype, atype),
+ logfile=sys.stdout, timeout=5)
+ ret.expect('Waiting for connection')
+ return ret
+
+def start_MAVProxy_SIL(atype, options=''):
+ '''launch mavproxy connected to a SIL instance'''
+ MAVPROXY = reltopdir('../MAVProxy/mavproxy.py')
+ ret = pexpect.spawn('%s --master=tcp:127.0.0.1:5760 --aircraft=test.%s %s' % (
+ MAVPROXY,atype,options),
+ logfile=sys.stdout, timeout=60)
+ return ret
+
+
+def kill(name):
+ '''kill a process'''
+ run_cmd('killall -9 -q %s' % name, checkfail=False)
+
+
+def expect_setup_callback(e, callback):
+ '''setup a callback that is called once a second while waiting for
+ patterns'''
+ def _expect_callback(pattern, timeout=e.timeout):
+ tstart = time.time()
+ while time.time() < tstart + timeout:
+ try:
+ ret = e.expect_saved(pattern, timeout=1)
+ return ret
+ except pexpect.TIMEOUT:
+ e.expect_user_callback(e)
+ pass
+ raise pexpect.TIMEOUT
+
+ e.expect_user_callback = callback
+ e.expect_saved = e.expect
+ e.expect = _expect_callback
diff --git a/apo/.cproject b/apo/.cproject
deleted file mode 100644
index 00f2f875be..0000000000
--- a/apo/.cproject
+++ /dev/null
@@ -1,46 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/apo/.project b/apo/.project
deleted file mode 100644
index 4152e256c1..0000000000
--- a/apo/.project
+++ /dev/null
@@ -1,79 +0,0 @@
-
-
- apo
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
- ?name?
-
-
-
- org.eclipse.cdt.make.core.append_environment
- true
-
-
- org.eclipse.cdt.make.core.autoBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.buildArguments
-
-
-
- org.eclipse.cdt.make.core.buildCommand
- make
-
-
- org.eclipse.cdt.make.core.cleanBuildTarget
- clean
-
-
- org.eclipse.cdt.make.core.contents
- org.eclipse.cdt.make.core.activeConfigSettings
-
-
- org.eclipse.cdt.make.core.enableAutoBuild
- false
-
-
- org.eclipse.cdt.make.core.enableCleanBuild
- true
-
-
- org.eclipse.cdt.make.core.enableFullBuild
- true
-
-
- org.eclipse.cdt.make.core.fullBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.stopOnError
- true
-
-
- org.eclipse.cdt.make.core.useDefaultBuildCmd
- true
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
-
-
diff --git a/apo/apo.pde b/apo/apo.pde
index cdd4455bfd..a39d6e9f7f 100644
--- a/apo/apo.pde
+++ b/apo/apo.pde
@@ -14,7 +14,6 @@
#include
#include
#include
-#include
// Vehicle Configuration
//#include "QuadArducopter.h"
diff --git a/libraries/.cproject b/libraries/.cproject
deleted file mode 100644
index 141451424b..0000000000
--- a/libraries/.cproject
+++ /dev/null
@@ -1,270 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- make
- true
- true
- true
-
-
- make
-
-
- true
- true
- true
-
-
-
-
-
-
-
-
-
diff --git a/libraries/.project b/libraries/.project
deleted file mode 100644
index 1adae30bd7..0000000000
--- a/libraries/.project
+++ /dev/null
@@ -1,79 +0,0 @@
-
-
- libraries
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
- ?name?
-
-
-
- org.eclipse.cdt.make.core.append_environment
- true
-
-
- org.eclipse.cdt.make.core.autoBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.buildArguments
-
-
-
- org.eclipse.cdt.make.core.buildCommand
- make
-
-
- org.eclipse.cdt.make.core.cleanBuildTarget
- clean
-
-
- org.eclipse.cdt.make.core.contents
- org.eclipse.cdt.make.core.activeConfigSettings
-
-
- org.eclipse.cdt.make.core.enableAutoBuild
- false
-
-
- org.eclipse.cdt.make.core.enableCleanBuild
- true
-
-
- org.eclipse.cdt.make.core.enableFullBuild
- true
-
-
- org.eclipse.cdt.make.core.fullBuildTarget
- all
-
-
- org.eclipse.cdt.make.core.stopOnError
- true
-
-
- org.eclipse.cdt.make.core.useDefaultBuildCmd
- true
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
-
-
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;
diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp
new file mode 100644
index 0000000000..b5b27b1b83
--- /dev/null
+++ b/libraries/AP_Mount/AP_Mount.cpp
@@ -0,0 +1,296 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
+
+#include
+
+extern RC_Channel_aux* g_rc_function[RC_Channel_aux::k_nr_aux_servo_functions]; // the aux. servo ch. assigned to each function
+
+AP_Mount::AP_Mount(GPS *gps, AP_DCM *dcm)
+{
+ _dcm=dcm;
+ _dcm_hil=NULL;
+ _gps=gps;
+ //set_mode(MAV_MOUNT_MODE_RETRACT);
+ //set_mode(MAV_MOUNT_MODE_RC_TARGETING); // FIXME: This is just to test without mavlink
+ set_mode(MAV_MOUNT_MODE_GPS_POINT); // FIXME: this is to test ONLY targeting
+
+ _retract_angles.x=0;
+ _retract_angles.y=0;
+ _retract_angles.z=0;
+}
+
+AP_Mount::AP_Mount(GPS *gps, AP_DCM_HIL *dcm)
+{
+ _dcm=NULL;
+ _dcm_hil=dcm;
+ _gps=gps;
+ //set_mode(MAV_MOUNT_MODE_RETRACT);
+ //set_mode(MAV_MOUNT_MODE_RC_TARGETING); // FIXME: This is just to test without mavlink
+ set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING); // FIXME: this is to test ONLY targeting
+
+ _retract_angles.x=0;
+ _retract_angles.y=0;
+ _retract_angles.z=0;
+}
+
+//sets the servo angles for retraction, note angles are * 100
+void AP_Mount::set_retract_angles(int roll, int pitch, int yaw)
+{
+ _retract_angles.x=roll;
+ _retract_angles.y=pitch;
+ _retract_angles.z=yaw;
+}
+
+//sets the servo angles for neutral, note angles are * 100
+void AP_Mount::set_neutral_angles(int roll, int pitch, int yaw)
+{
+ _neutral_angles.x=roll;
+ _neutral_angles.y=pitch;
+ _neutral_angles.z=yaw;
+}
+
+//sets the servo angles for MAVLink, note angles are * 100
+void AP_Mount::set_mavlink_angles(int roll, int pitch, int yaw)
+{
+ _mavlink_angles.x = roll;
+ _mavlink_angles.y = pitch;
+ _mavlink_angles.z = yaw;
+}
+
+// used to tell the mount to track GPS location
+void AP_Mount::set_GPS_target_location(Location targetGPSLocation)
+{
+ _target_GPS_location=targetGPSLocation;
+}
+
+// This one should be called periodically
+void AP_Mount::update_mount_position()
+{
+ Matrix3f m; //holds 3 x 3 matrix, var is used as temp in calcs
+ Vector3f targ; //holds target vector, var is used as temp in calcs
+ Vector3f aux_vec; //holds target vector, var is used as temp in calcs
+
+ switch(_mount_mode)
+ {
+ case MAV_MOUNT_MODE_RETRACT:
+ roll_angle =100*_retract_angles.x;
+ pitch_angle=100*_retract_angles.y;
+ yaw_angle =100*_retract_angles.z;
+ break;
+
+ case MAV_MOUNT_MODE_NEUTRAL:
+ roll_angle =100*_neutral_angles.x;
+ pitch_angle=100*_neutral_angles.y;
+ yaw_angle =100*_neutral_angles.z;
+ break;
+
+ case MAV_MOUNT_MODE_MAVLINK_TARGETING:
+ {
+ aux_vec.x = _mavlink_angles.x;
+ aux_vec.y = _mavlink_angles.y;
+ aux_vec.z = _mavlink_angles.z;
+ m = _dcm?_dcm->get_dcm_transposed():_dcm_hil->get_dcm_transposed();
+ //rotate vector
+ targ = m*aux_vec;
+ // TODO The next three lines are probably not correct yet
+ roll_angle = _stab_roll? degrees(atan2( targ.y,targ.z))*100:_mavlink_angles.y; //roll
+ pitch_angle = _stab_pitch?degrees(atan2(-targ.x,targ.z))*100:_neutral_angles.x; //pitch
+ yaw_angle = _stab_yaw? degrees(atan2(-targ.x,targ.y))*100:_neutral_angles.z; //yaw
+ break;
+ }
+
+ case MAV_MOUNT_MODE_RC_TARGETING: // radio manual control
+ {
+ // TODO It does work, but maybe is a good idea to replace this simplified implementation with a proper one
+ if (_dcm)
+ {
+ roll_angle = -_dcm->roll_sensor;
+ pitch_angle = -_dcm->pitch_sensor;
+ yaw_angle = -_dcm->yaw_sensor;
+ }
+ if (_dcm_hil)
+ {
+ roll_angle = -_dcm_hil->roll_sensor;
+ pitch_angle = -_dcm_hil->pitch_sensor;
+ yaw_angle = -_dcm_hil->yaw_sensor;
+ }
+ if (g_rc_function[RC_Channel_aux::k_mount_roll])
+ roll_angle = rc_map(g_rc_function[RC_Channel_aux::k_mount_roll]);
+ if (g_rc_function[RC_Channel_aux::k_mount_pitch])
+ pitch_angle = rc_map(g_rc_function[RC_Channel_aux::k_mount_pitch]);
+ if (g_rc_function[RC_Channel_aux::k_mount_yaw])
+ yaw_angle = rc_map(g_rc_function[RC_Channel_aux::k_mount_yaw]);
+ break;
+ }
+
+ case MAV_MOUNT_MODE_GPS_POINT:
+ {
+ if(_gps->fix)
+ {
+ calc_GPS_target_vector(&_target_GPS_location);
+ }
+ m = (_dcm)?_dcm->get_dcm_transposed():_dcm_hil->get_dcm_transposed();
+ targ = m*_GPS_vector;
+ /* disable stabilization for now, this will help debug */
+ _stab_roll = 0;_stab_pitch=0;_stab_yaw=0;
+ /**/
+ // TODO The next three lines are probably not correct yet
+ roll_angle = _stab_roll? degrees(atan2( targ.y,targ.z))*100:_GPS_vector.y; //roll
+ pitch_angle = _stab_pitch?degrees(atan2(-targ.x,targ.z))*100:0; //pitch
+ yaw_angle = _stab_yaw? degrees(atan2(-targ.x,targ.y))*100:degrees(atan2(-_GPS_vector.x,_GPS_vector.y))*100; //yaw
+ break;
+ }
+ default:
+ //do nothing
+ break;
+ }
+
+ // write the results to the servos
+ // Change scaling to 0.1 degrees in order to avoid overflows in the angle arithmetic
+ G_RC_AUX(k_mount_roll)->closest_limit(roll_angle/10);
+ G_RC_AUX(k_mount_pitch)->closest_limit(pitch_angle/10);
+ G_RC_AUX(k_mount_yaw)->closest_limit(yaw_angle/10);
+}
+
+void AP_Mount::set_mode(enum MAV_MOUNT_MODE mode)
+{
+ _mount_mode=mode;
+}
+
+void AP_Mount::configure_msg(mavlink_message_t* msg)
+{
+ __mavlink_mount_configure_t packet;
+ mavlink_msg_mount_configure_decode(msg, &packet);
+ if (mavlink_check_target(packet.target_system, packet.target_component)) {
+ // not for us
+ return;
+ }
+ set_mode((enum MAV_MOUNT_MODE)packet.mount_mode);
+ _stab_pitch = packet.stab_pitch;
+ _stab_roll = packet.stab_roll;
+ _stab_yaw = packet.stab_yaw;
+}
+
+void AP_Mount::control_msg(mavlink_message_t *msg)
+{
+ __mavlink_mount_control_t packet;
+ mavlink_msg_mount_control_decode(msg, &packet);
+ if (mavlink_check_target(packet.target_system, packet.target_component)) {
+ // not for us
+ return;
+ }
+
+ switch (_mount_mode)
+ {
+ case MAV_MOUNT_MODE_RETRACT: // Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization
+ set_retract_angles(packet.input_b, packet.input_a, packet.input_c);
+ if (packet.save_position)
+ {
+ // TODO: Save current trimmed position on EEPROM
+ }
+ break;
+
+ case MAV_MOUNT_MODE_NEUTRAL: // Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM
+ set_neutral_angles(packet.input_b, packet.input_a, packet.input_c);
+ if (packet.save_position)
+ {
+ // TODO: Save current trimmed position on EEPROM
+ }
+ break;
+
+ case MAV_MOUNT_MODE_MAVLINK_TARGETING: // Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization
+ set_mavlink_angles(packet.input_b, packet.input_a, packet.input_c);
+ break;
+
+ case MAV_MOUNT_MODE_RC_TARGETING: // Load neutral position and start RC Roll,Pitch,Yaw control with stabilization
+ break;
+
+ case MAV_MOUNT_MODE_GPS_POINT: // Load neutral position and start to point to Lat,Lon,Alt
+ Location targetGPSLocation;
+ targetGPSLocation.lat = packet.input_a;
+ targetGPSLocation.lng = packet.input_b;
+ targetGPSLocation.alt = packet.input_c;
+ set_GPS_target_location(targetGPSLocation);
+ break;
+ }
+}
+
+void AP_Mount::status_msg(mavlink_message_t *msg)
+{
+ __mavlink_mount_status_t packet;
+ mavlink_msg_mount_status_decode(msg, &packet);
+ if (mavlink_check_target(packet.target_system, packet.target_component)) {
+ // not for us
+ return;
+ }
+
+ switch (_mount_mode)
+ {
+ case MAV_MOUNT_MODE_RETRACT: // safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization
+ case MAV_MOUNT_MODE_NEUTRAL: // neutral position (Roll,Pitch,Yaw) from EEPROM
+ case MAV_MOUNT_MODE_MAVLINK_TARGETING: // neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization
+ case MAV_MOUNT_MODE_RC_TARGETING: // neutral position and start RC Roll,Pitch,Yaw control with stabilization
+ packet.pointing_b = roll_angle; ///< degrees*100
+ packet.pointing_a = pitch_angle; ///< degrees*100
+ packet.pointing_c = yaw_angle; ///< degrees*100
+ break;
+ case MAV_MOUNT_MODE_GPS_POINT: // neutral position and start to point to Lat,Lon,Alt
+ packet.pointing_a = _target_GPS_location.lat; ///< latitude
+ packet.pointing_b = _target_GPS_location.lng; ///< longitude
+ packet.pointing_c = _target_GPS_location.alt; ///< altitude
+ break;
+ }
+
+ // status reply
+ // TODO: is COMM_3 correct ?
+ mavlink_msg_mount_status_send(MAVLINK_COMM_3, packet.target_system, packet.target_component,
+ packet.pointing_a, packet.pointing_b, packet.pointing_c);
+}
+
+void AP_Mount::set_roi_cmd()
+{
+ // TODO get the information out of the mission command and use it
+}
+
+void AP_Mount::configure_cmd()
+{
+ // TODO get the information out of the mission command and use it
+}
+
+void AP_Mount::control_cmd()
+{
+ // TODO get the information out of the mission command and use it
+}
+
+
+void AP_Mount::calc_GPS_target_vector(struct Location *target)
+{
+ _GPS_vector.x = (target->lng-_gps->longitude) * cos((_gps->latitude+target->lat)/2)*.01113195;
+ _GPS_vector.y = (target->lat-_gps->latitude)*.01113195;
+ _GPS_vector.z = (_gps->altitude-target->alt);
+}
+
+void
+AP_Mount::update_mount_type()
+{
+ // Auto-detect the mount gimbal type depending on the functions assigned to the servos
+ if ((g_rc_function[RC_Channel_aux::k_mount_roll] == NULL) && (g_rc_function[RC_Channel_aux::k_mount_pitch] != NULL) && (g_rc_function[RC_Channel_aux::k_mount_yaw] != NULL))
+ {
+ _mount_type = k_pan_tilt;
+ }
+ if ((g_rc_function[RC_Channel_aux::k_mount_roll] != NULL) && (g_rc_function[RC_Channel_aux::k_mount_pitch] != NULL) && (g_rc_function[RC_Channel_aux::k_mount_yaw] == NULL))
+ {
+ _mount_type = k_tilt_roll;
+ }
+ if ((g_rc_function[RC_Channel_aux::k_mount_roll] != NULL) && (g_rc_function[RC_Channel_aux::k_mount_pitch] != NULL) && (g_rc_function[RC_Channel_aux::k_mount_yaw] != NULL))
+ {
+ _mount_type = k_pan_tilt_roll;
+ }
+}
+
+// This function is needed to let the HIL code compile
+long
+AP_Mount::rc_map(RC_Channel_aux* rc_ch)
+{
+ return (rc_ch->radio_in - rc_ch->radio_min) * (rc_ch->angle_max - rc_ch->angle_min) / (rc_ch->radio_max - rc_ch->radio_min) + rc_ch->angle_min;
+}
+
diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h
new file mode 100644
index 0000000000..89c576a729
--- /dev/null
+++ b/libraries/AP_Mount/AP_Mount.h
@@ -0,0 +1,96 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
+
+/************************************************************
+* AP_mount -- library to control a 2 or 3 axis mount. *
+* *
+* Author: Joe Holdsworth; *
+* Ritchie Wilson; *
+* Amilcar Lucas; *
+* *
+* Purpose: Move a 2 or 3 axis mount attached to vehicle, *
+* Used for mount to track targets or stabilise *
+* camera plus other modes. *
+* *
+* Usage: Use in main code to control mounts attached to *
+* vehicle. *
+* *
+*Comments: All angles in degrees * 100, distances in meters*
+* unless otherwise stated. *
+ ************************************************************/
+#ifndef AP_Mount_H
+#define AP_Mount_H
+
+//#include
+#include
+#include
+#include
+#include
+#include <../RC_Channel/RC_Channel_aux.h>
+
+class AP_Mount
+{
+public:
+ //Constructors
+ AP_Mount(GPS *gps, AP_DCM *dcm);
+ AP_Mount(GPS *gps, AP_DCM_HIL *dcm); // constructor for HIL usage
+
+ //enums
+ enum MountType{
+ k_pan_tilt = 0, ///< yaw-pitch
+ k_tilt_roll = 1, ///< pitch-roll
+ k_pan_tilt_roll = 2, ///< yaw-pitch-roll
+ };
+
+ // MAVLink methods
+ void configure_msg(mavlink_message_t* msg);
+ void control_msg(mavlink_message_t* msg);
+ void status_msg(mavlink_message_t* msg);
+ void set_roi_cmd();
+ void configure_cmd();
+ void control_cmd();
+
+ // should be called periodically
+ void update_mount_position();
+ void update_mount_type(); ///< Auto-detect the mount gimbal type depending on the functions assigned to the servos
+
+ // Accessors
+ enum MountType get_mount_type();
+
+private:
+
+ //methods
+ void set_mode(enum MAV_MOUNT_MODE mode);
+
+ void set_retract_angles(int roll, int pitch, int yaw); ///< set mount retracted position
+ void set_neutral_angles(int roll, int pitch, int yaw);
+ void set_mavlink_angles(int roll, int pitch, int yaw);
+ void set_GPS_target_location(Location targetGPSLocation); ///< used to tell the mount to track GPS location
+
+ // internal methods
+ void calc_GPS_target_vector(struct Location *target);
+ long rc_map(RC_Channel_aux* rc_ch);
+
+ //members
+ AP_DCM *_dcm;
+ AP_DCM_HIL *_dcm_hil;
+ GPS *_gps;
+
+ int roll_angle; ///< degrees*100
+ int pitch_angle; ///< degrees*100
+ int yaw_angle; ///< degrees*100
+
+ uint8_t _stab_roll; ///< (1 = yes, 0 = no)
+ uint8_t _stab_pitch; ///< (1 = yes, 0 = no)
+ uint8_t _stab_yaw; ///< (1 = yes, 0 = no)
+
+ enum MAV_MOUNT_MODE _mount_mode;
+ MountType _mount_type;
+
+ struct Location _target_GPS_location;
+
+ Vector3i _retract_angles; ///< retracted position for mount, vector.x = roll vector.y = pitch, vector.z=yaw
+ Vector3i _neutral_angles; ///< neutral position for mount, vector.x = roll vector.y = pitch, vector.z=yaw
+ Vector3i _mavlink_angles; ///< mavlink position for mount, vector.x = roll vector.y = pitch, vector.z=yaw
+ Vector3f _GPS_vector; ///< target vector calculated stored in meters
+};
+#endif
diff --git a/libraries/Desktop/README b/libraries/Desktop/README
index a1d5b2b1d9..531688ab73 100644
--- a/libraries/Desktop/README
+++ b/libraries/Desktop/README
@@ -2,17 +2,32 @@ This provides some support files for building APM on normal desktop
systems. This makes it possible to use debugging tools (such as gdb
and valgrind) on the APM code
-To build it do this:
+The code can then run on the PC instead of on the Arduino board and
+simulate the behaviour of the real system by integrating it with
+X-Plane of FlightGear to build a Software-In-the-Loop (SIL) simulator.
- cd ArduPlane
- make -f ../libraries/Desktop/Makefile.desktop hil
+It will use TCP sockets to communicate between the several software
+components (ArduPilot, GCS and Flight simulator). All the ArduPilot
+serial ports that get initialised map to separate TCP ports, which
+means you can separately test the telemetry port and the main serial
+port. It also makes using a debugger easier, as the debugger can use
+stdin/stdout.
-currently only 'hil' builds work.
+So the new usage is:
-It currently runs with the first serial port mapped to
-stdin/stdout. To test it, you can use mavproxy like this:
+ 1) build with "make -f ../libraries/Desktop/Makefile.desktop hil"
- mavproxy.py --master=/tmp/ArduPlane/ArduPlane.elf
+ 2) start in a terminal like this: /tmp/ArduPlane.build/ArduPlane.elf
+ it will say something like this:
-that will run ArduPlane as a child process, and will give you the
-ability to control ArduPlane over MAVLink.
+ Serial port 0 on TCP port 5760
+ Waiting for connection ....
+
+ 3) start a GCS, pointing it at localhost:5760. For the current
+ mavproxy, you would use:
+
+ mavproxy.py --master=tcp:localhost:5760
+
+ MichaelO has also added support in the GCS mission planner for TCP.
+ You will see a TCP option in the drop down for the serial port, then
+ choose port 5760.
diff --git a/libraries/Desktop/support/FastSerial.cpp b/libraries/Desktop/support/FastSerial.cpp
index fb66de60af..04623fa8d0 100644
--- a/libraries/Desktop/support/FastSerial.cpp
+++ b/libraries/Desktop/support/FastSerial.cpp
@@ -45,6 +45,7 @@
#include
#include
#include
+#include "desktop.h"
#define LISTEN_BASE_PORT 5760
#define BUFFER_SIZE 128
@@ -305,3 +306,19 @@ void FastSerial::_freeBuffer(Buffer *buffer)
{
}
+/*
+ return true if any bytes are pending
+ */
+void desktop_serial_select_setup(fd_set *fds, int *fd_high)
+{
+ int i;
+
+ for (i=0; i *fd_high) {
+ *fd_high = tcp_state[i].fd;
+ }
+ }
+ }
+}
diff --git a/libraries/Desktop/support/desktop.h b/libraries/Desktop/support/desktop.h
new file mode 100644
index 0000000000..f34b93f895
--- /dev/null
+++ b/libraries/Desktop/support/desktop.h
@@ -0,0 +1,2 @@
+void desktop_serial_select_setup(fd_set *fds, int *fd_high);
+
diff --git a/libraries/Desktop/support/main.cpp b/libraries/Desktop/support/main.cpp
index b6eef2e63b..9e16c1ff70 100644
--- a/libraries/Desktop/support/main.cpp
+++ b/libraries/Desktop/support/main.cpp
@@ -4,6 +4,7 @@
#include
#include
#include
+#include "desktop.h"
void setup(void);
void loop(void);
@@ -16,15 +17,17 @@ int main(void)
setup();
while (true) {
struct timeval tv;
- unsigned long t1, t2;
- t1 = micros();
+ fd_set fds;
+ int fd_high = 0;
+
+ FD_ZERO(&fds);
loop();
- t2 = micros();
- if (t2 - t1 < 2) {
- tv.tv_sec = 0;
- tv.tv_usec = 1;
- select(0, NULL, NULL, NULL, &tv);
- }
+
+ desktop_serial_select_setup(&fds, &fd_high);
+ tv.tv_sec = 0;
+ tv.tv_usec = 100;
+
+ select(fd_high+1, &fds, NULL, NULL, &tv);
}
return 0;
}
diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp
index d290dd01cd..96da440698 100644
--- a/libraries/RC_Channel/RC_Channel.cpp
+++ b/libraries/RC_Channel/RC_Channel.cpp
@@ -190,6 +190,10 @@ RC_Channel::pwm_to_angle()
{
int radio_trim_high = radio_trim + _dead_zone;
int radio_trim_low = radio_trim - _dead_zone;
+
+ // prevent div by 0
+ if ((radio_trim_low - radio_min) == 0 || (radio_max - radio_trim_high) == 0)
+ return 0;
if(radio_in > radio_trim_high){
return _reverse * ((long)_high * (long)(radio_in - radio_trim_high)) / (long)(radio_max - radio_trim_high);
diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp
index 79de67e375..bf73492351 100644
--- a/libraries/RC_Channel/RC_Channel_aux.cpp
+++ b/libraries/RC_Channel/RC_Channel_aux.cpp
@@ -5,6 +5,42 @@
RC_Channel_aux* g_rc_function[RC_Channel_aux::k_nr_aux_servo_functions]; // the aux. servo ch. assigned to each function
+int16_t
+RC_Channel_aux::closest_limit(int16_t angle)
+{
+ // Change scaling to 0.1 degrees in order to avoid overflows in the angle arithmetic
+ int16_t min = angle_min / 10;
+ int16_t max = angle_max / 10;
+
+ // Make sure the angle lies in the interval [-180 .. 180[ degrees
+ while (angle < -1800) angle += 3600;
+ while (angle >= 1800) angle -= 3600;
+
+ // Make sure the angle limits lie in the interval [-180 .. 180[ degrees
+ while (min < -1800) min += 3600;
+ while (min >= 1800) min -= 3600;
+ while (max < -1800) max += 3600;
+ while (max >= 1800) max -= 3600;
+ // This is done every time because the user might change the min, max values on the fly
+ set_range(min, max);
+
+ // If the angle is outside servo limits, saturate the angle to the closest limit
+ // On a circle the closest angular position must be carefully calculated to account for wrap-around
+ if ((angle < min) && (angle > max)){
+ // angle error if min limit is used
+ int16_t err_min = min - angle + (anglemax?0:3600); // add 360 degrees if on the "wrong side"
+ angle = err_minset_range(0,100);
G_RC_AUX(k_aileron)->set_angle(4500);
G_RC_AUX(k_flaperon)->set_range(0,100);
+ G_RC_AUX(k_mount_yaw)->set_range(
+ g_rc_function[RC_Channel_aux::k_mount_yaw]->angle_min / 10,
+ g_rc_function[RC_Channel_aux::k_mount_yaw]->angle_max / 10);
+ G_RC_AUX(k_mount_pitch)->set_range(
+ g_rc_function[RC_Channel_aux::k_mount_pitch]->angle_min / 10,
+ g_rc_function[RC_Channel_aux::k_mount_pitch]->angle_max / 10);
+ G_RC_AUX(k_mount_roll)->set_range(
+ g_rc_function[RC_Channel_aux::k_mount_roll]->angle_min / 10,
+ g_rc_function[RC_Channel_aux::k_mount_roll]->angle_max / 10);
+ G_RC_AUX(k_mount_open)->set_range(0,100);
}
diff --git a/libraries/RC_Channel/RC_Channel_aux.h b/libraries/RC_Channel/RC_Channel_aux.h
index 2b7b2724cc..f34db6aada 100644
--- a/libraries/RC_Channel/RC_Channel_aux.h
+++ b/libraries/RC_Channel/RC_Channel_aux.h
@@ -14,6 +14,7 @@
/// @class RC_Channel_aux
/// @brief Object managing one aux. RC channel (CH5-8), with information about its function
+/// Also contains physical min,max angular deflection, to allow calibrating open-loop servo movements
class RC_Channel_aux : public RC_Channel{
public:
/// Constructor
@@ -23,7 +24,9 @@ public:
///
RC_Channel_aux(AP_Var::Key key, const prog_char_t *name) :
RC_Channel(key, name),
- function (&_group, 4, k_none, name ? PSTR("FUNCTION") : 0) // suppress name if group has no name
+ function (&_group, 4, k_none, name ? PSTR("FUNCTION") : 0), // suppress name if group has no name
+ angle_min (&_group, 5, -4500, name ? PSTR("ANGLE_MIN") : 0), // assume -45 degrees min deflection
+ angle_max (&_group, 6, 4500, name ? PSTR("ANGLE_MAX") : 0) // assume 45 degrees max deflection
{}
typedef enum
@@ -34,10 +37,18 @@ public:
k_flap_auto = 3, // flap automated
k_aileron = 4, // aileron
k_flaperon = 5, // flaperon (flaps and aileron combined, needs two independent servos one for each wing)
+ k_mount_yaw = 6, // mount yaw (pan)
+ k_mount_pitch = 7, // mount pitch (tilt)
+ k_mount_roll = 8, // mount roll
+ k_mount_open = 9, // mount open (deploy) / close (retract)
k_nr_aux_servo_functions // This must be the last enum value (only add new values _before_ this one)
} Aux_servo_function_t;
AP_Int8 function; // 0=disabled, 1=manual, 2=flap, 3=flap auto, 4=aileron, 5=flaperon, 6=mount yaw (pan), 7=mount pitch (tilt), 8=mount roll, 9=camera trigger, 10=camera open, 11=egg drop
+ AP_Int16 angle_min; // min angle limit of actuated surface in 0.01 degree units
+ AP_Int16 angle_max; // max angle limit of actuated surface in 0.01 degree units
+
+ int16_t closest_limit(int16_t angle); // saturate to the closest angle limit if outside of min max angle interval
void output_ch(unsigned char ch_nr); // map a function to a servo channel and output it