diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index cdc503b89c..42ca4ae449 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -1,10 +1,10 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
-#define THISFIRMWARE "ArduCopter V2.2 b6"
+#define THISFIRMWARE "ArduCopter V2.3"
/*
-ArduCopter Version 2.2
+ArduCopter Version 2.3
Authors: Jason Short
-Based on code and ideas from the Arducopter team: Jose Julio, Randy Mackay, Jani Hirvinen
+Based on code and ideas from the Arducopter team: Randy Mackay, Pat Hickey, Jose Julio, Jani Hirvinen
Thanks to: Chris Anderson, Mike Smith, Jordi Munoz, Doug Weibel, James Goppert, Benjamin Pelletier
This firmware is free software; you can redistribute it and/or
@@ -32,6 +32,9 @@ Oliver :Piezo support
Guntars :Arming safety suggestion
Igor van Airde :Control Law optimization
Jean-Louis Naudin :Auto Landing
+Sandro Benigno : Camera support
+Olivier Adler : PPM Encoder
+John Arne Birkeland: PPM Encoder
And much more so PLEASE PM me on DIYDRONES to add your contribution to the List
@@ -547,7 +550,7 @@ static bool low_batt = false;
static int32_t ground_pressure;
// The ground temperature at home location - calibrated at arming
static int16_t ground_temperature;
-// The cm we are off in altitude from next_WP.alt – Positive value means we are below the WP
+// The cm we are off in altitude from next_WP.alt – Positive value means we are below the WP
static int32_t altitude_error;
// The cm/s we are moving up or down - Positive = UP
static int16_t climb_rate;
diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde
index 26e12f3610..5942e69583 100644
--- a/ArduCopter/Attitude.pde
+++ b/ArduCopter/Attitude.pde
@@ -441,7 +441,7 @@ get_of_roll(int32_t control_roll)
// only stop roll if caller isn't modifying roll
if( control_roll == 0 && current_loc.alt < 1500) {
- //new_roll = g.pid_optflow_roll.get_pid(-tot_x_cm, 1.0, 1.0); // we could use the last update time to calculate the time change
+ new_roll = g.pid_optflow_roll.get_pid(-tot_x_cm, 1.0); // we could use the last update time to calculate the time change
}else{
g.pid_optflow_roll.reset_I();
tot_x_cm = 0;
@@ -475,7 +475,7 @@ get_of_pitch(int32_t control_pitch)
// only stop roll if caller isn't modifying pitch
if( control_pitch == 0 && current_loc.alt < 1500 ) {
- //new_pitch = g.pid_optflow_pitch.get_pid(tot_y_cm, 1.0, 1.0); // we could use the last update time to calculate the time change
+ new_pitch = g.pid_optflow_pitch.get_pid(tot_y_cm, 1.0); // we could use the last update time to calculate the time change
}else{
tot_y_cm = 0;
g.pid_optflow_pitch.reset_I();
diff --git a/ArduCopter/config.h b/ArduCopter/config.h
index 43abc0c984..2bf3a93d60 100644
--- a/ArduCopter/config.h
+++ b/ArduCopter/config.h
@@ -324,7 +324,7 @@
#define OPTFLOW_ROLL_P 2.5
#endif
#ifndef OPTFLOW_ROLL_I
- #define OPTFLOW_ROLL_I 6.2
+ #define OPTFLOW_ROLL_I 3.2
#endif
#ifndef OPTFLOW_ROLL_D
#define OPTFLOW_ROLL_D 0.12
@@ -333,7 +333,7 @@
#define OPTFLOW_PITCH_P 2.5
#endif
#ifndef OPTFLOW_PITCH_I
- #define OPTFLOW_PITCH_I 6.2
+ #define OPTFLOW_PITCH_I 3.2
#endif
#ifndef OPTFLOW_PITCH_D
#define OPTFLOW_PITCH_D 0.12
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
index ea468fde09..344ff72262 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
+++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
@@ -47,68 +47,68 @@
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex
- ArduCopter V2.2 b4 Quad
+ ArduCopter V2.3 Quad
#define FRAME_CONFIG QUAD_FRAME
- 114
+ 115
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex
- ArduCopter V2.2 b4 Tri
+ ArduCopter V2.3 Tri
#define FRAME_CONFIG TRI_FRAME
- 114
+ 115
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex
- ArduCopter V2.2 b4 Hexa X
+ ArduCopter V2.3 Hexa X
#define FRAME_CONFIG HEXA_FRAME
- 114
+ 115
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560-2.hex
- ArduCopter V2.2 b4 Y6
+ ArduCopter V2.3 Y6
#define FRAME_CONFIG Y6_FRAME
- 114
+ 115
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-2560.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-2560-2.hex
- ArduCopter V2.2 b4 Octa V
+ ArduCopter V2.3 Octa V
#define FRAME_CONFIG OCTA_FRAME
#define FRAME_ORIENTATION V_FRAME
- 114
+ 115
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-2560.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-2560-2.hex
- ArduCopter V2.2 b4 Octa X
+ ArduCopter V2.3 Octa X
#define FRAME_CONFIG OCTA_FRAME
- 114
+ 115
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.hex
@@ -162,7 +162,7 @@
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex
- ArduCopter V2.2 b4 Quad Hil
+ ArduCopter V2.3 Quad Hil
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION PLUS_FRAME
@@ -172,7 +172,7 @@
- 114
+ 115
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.hex