From ae77029c9892dc9c4686b0183ad816caa926406d Mon Sep 17 00:00:00 2001 From: Mike Smith Date: Sun, 11 Sep 2011 22:20:54 -0700 Subject: [PATCH 1/7] Reinstate a Cygwin workround that was backed out by the previous changes. Not all platforms support (or require) the -r argument to sed. --- config.mk | 2 ++ libraries/AP_Common/Arduino.mk | 7 ++++++- 2 files changed, 8 insertions(+), 1 deletion(-) create mode 100644 config.mk diff --git a/config.mk b/config.mk new file mode 100644 index 0000000000..8375e45334 --- /dev/null +++ b/config.mk @@ -0,0 +1,2 @@ +BOARD=mega +PORT=/dev/null diff --git a/libraries/AP_Common/Arduino.mk b/libraries/AP_Common/Arduino.mk index ae3f3e572e..287684a060 100644 --- a/libraries/AP_Common/Arduino.mk +++ b/libraries/AP_Common/Arduino.mk @@ -259,7 +259,12 @@ SKETCHCPP_SRC := $(SKETCHPDE) $(sort $(filter-out $(SKETCHPDE),$(SKETCHPDESRCS) # make. # SEXPR = 's/^[[:space:]]*\#include[[:space:]][<\"]([^>\"./]+).*$$/\1/p' -LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nre $(SEXPR))) +ifneq ($(findstring CYGWIN, $(SYSTYPE)),) + # Workaround a cygwin issue + LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nre $(SEXPR))) +else + LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nEe $(SEXPR))) +endif # # Find sketchbook libraries referenced by the sketch. From 2a0912b867c19456b65bf4a962f3cb49c6258cdd Mon Sep 17 00:00:00 2001 From: Doug Weibel Date: Mon, 12 Sep 2011 07:24:52 -0600 Subject: [PATCH 2/7] Change default setting for auto_trim to disabled per user (JB) request. --- ArduPlane/APM_Config.h.reference | 4 ++-- ArduPlane/config.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/APM_Config.h.reference b/ArduPlane/APM_Config.h.reference index 3786839dc6..4c560ef062 100644 --- a/ArduPlane/APM_Config.h.reference +++ b/ArduPlane/APM_Config.h.reference @@ -398,9 +398,9 @@ // also means that you should avoid switching out of MANUAL while you have // any control stick deflection. // -// The default is to enable AUTO_TRIM. +// The default is to disable AUTO_TRIM. // -//#define AUTO_TRIM ENABLED +//#define AUTO_TRIM DISABLED // ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduPlane/config.h b/ArduPlane/config.h index f5fac05daa..d48b4cb73d 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -300,7 +300,7 @@ // AUTO_TRIM // #ifndef AUTO_TRIM -# define AUTO_TRIM ENABLED +# define AUTO_TRIM DISABLED #endif From 5a14d546bb003bf765ac45058f9fe602413e1534 Mon Sep 17 00:00:00 2001 From: Doug Weibel Date: Sun, 11 Sep 2011 17:37:42 -0600 Subject: [PATCH 3/7] Correct bug in initialization of auxiliary channels The value of aux_servo_function[CH_x] was not being set before the radio init_rc_in() function was setting channel angle/range. --- ArduPlane/radio.pde | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index ed3d1782b2..5b26479ce6 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -23,6 +23,7 @@ static void init_rc_in() g.channel_throttle.dead_zone = 6; //set auxiliary ranges + update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8); G_RC_AUX(k_flap)->set_range(0,100); G_RC_AUX(k_flap_auto)->set_range(0,100); G_RC_AUX(k_aileron)->set_angle(SERVO_MAX); From f7f745055dc3de38b6ec24da9c62f4c43cb75b90 Mon Sep 17 00:00:00 2001 From: Amilcar Lucas Date: Mon, 12 Sep 2011 20:03:44 +0200 Subject: [PATCH 4/7] Use the G_RC_AUX macro when possible. Added more comments. Remove unused code --- ArduPlane/ArduPlane.pde | 1 - ArduPlane/Attitude.pde | 12 ++++++------ libraries/RC_Channel/RC_Channel_aux.cpp | 20 +++++--------------- 3 files changed, 11 insertions(+), 22 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 3b62fe925a..a01fd6501f 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -39,7 +39,6 @@ version 2.1 of the License, or (at your option) any later version. #include // ArduPilot Mega DCM Library #include // PID library #include // RC Channel Library -//#include // Auxiliary RC Channel Library (Channels 5..8) #include // Range finder library #include #include // Photo or video camera diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 63eefb30f5..4847f86e76 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -274,14 +274,14 @@ static void set_servos(void) } g.channel_throttle.radio_out = g.channel_throttle.radio_in; g.channel_rudder.radio_out = g.channel_rudder.radio_in; - if (g_rc_function[RC_Channel_aux::k_aileron] != NULL) g_rc_function[RC_Channel_aux::k_aileron]->radio_out = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; + G_RC_AUX(k_aileron)->radio_out = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; } else { if (g.mix_mode == 0) { g.channel_roll.calc_pwm(); g.channel_pitch.calc_pwm(); g.channel_rudder.calc_pwm(); - if (g_rc_function[RC_Channel_aux::k_aileron] != NULL) { + if (g_rc_function[RC_Channel_aux::k_aileron]) { g_rc_function[RC_Channel_aux::k_aileron]->servo_out = g.channel_roll.servo_out; g_rc_function[RC_Channel_aux::k_aileron]->calc_pwm(); } @@ -315,7 +315,7 @@ static void set_servos(void) } if(control_mode <= FLY_BY_WIRE_B) { - if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) g_rc_function[RC_Channel_aux::k_flap_auto]->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_in; + G_RC_AUX(k_flap_auto)->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_in; } else if (control_mode >= FLY_BY_WIRE_C) { if (g.airspeed_enabled == true) { flapSpeedSource = g.airspeed_cruise; @@ -323,11 +323,11 @@ static void set_servos(void) flapSpeedSource = g.throttle_cruise; } if ( flapSpeedSource > g.flap_1_speed) { - if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = 0; + G_RC_AUX(k_flap_auto)->servo_out = 0; } else if (flapSpeedSource > g.flap_2_speed) { - if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = g.flap_1_percent; + G_RC_AUX(k_flap_auto)->servo_out = g.flap_1_percent; } else { - if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = g.flap_2_percent; + G_RC_AUX(k_flap_auto)->servo_out = g.flap_2_percent; } } diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index caa7affb61..55ed6819af 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -21,6 +21,7 @@ RC_Channel_aux::closest_limit(int16_t angle) 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 @@ -44,6 +45,7 @@ RC_Channel_aux::closest_limit(int16_t angle) void RC_Channel_aux::output_ch(unsigned char ch_nr) { + // take care or two corner cases switch(function) { case k_none: // disabled @@ -52,26 +54,14 @@ RC_Channel_aux::output_ch(unsigned char ch_nr) case k_manual: // manual radio_out = radio_in; break; - case k_flap: // flaps - case k_flap_auto: // flaps automated - case k_aileron: // aileron - case k_flaperon: // flaperon (flaps and aileron combined, needs two independent servos one for each wing) - case k_mount_yaw: // mount yaw (pan) - case k_mount_pitch: // mount pitch (tilt) - case k_mount_roll: // mount roll - case k_cam_trigger: // camera trigger - case k_cam_open: // camera open - case k_egg_drop: // egg drop - case k_nr_aux_servo_functions: // dummy, just to avoid a compiler warning - default: - break; } APM_RC.OutputCh(ch_nr, radio_out); } -// update the g_rc_function array from pointers to rc_x channels -// This should be done periodically because the user might change the configuration and +// Update the g_rc_function array of pointers to rc_x channels +// This is to be done before rc_init so that the channels get correctly initialized. +// It also should be called periodically because the user might change the configuration and // expects the changes to take effect instantly void update_aux_servo_function(RC_Channel_aux* rc_5, RC_Channel_aux* rc_6, RC_Channel_aux* rc_7, RC_Channel_aux* rc_8) { From e84a422bd4f31f3861345e19cc15f52ab2ea7046 Mon Sep 17 00:00:00 2001 From: DrZiplok Date: Mon, 12 Sep 2011 18:43:31 +0000 Subject: [PATCH 5/7] GNU sed wants -r, Darwin/BSD sed wants -E. --- libraries/AP_Common/Arduino.mk | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Common/Arduino.mk b/libraries/AP_Common/Arduino.mk index 287684a060..f84f06a237 100644 --- a/libraries/AP_Common/Arduino.mk +++ b/libraries/AP_Common/Arduino.mk @@ -259,11 +259,10 @@ SKETCHCPP_SRC := $(SKETCHPDE) $(sort $(filter-out $(SKETCHPDE),$(SKETCHPDESRCS) # make. # SEXPR = 's/^[[:space:]]*\#include[[:space:]][<\"]([^>\"./]+).*$$/\1/p' -ifneq ($(findstring CYGWIN, $(SYSTYPE)),) - # Workaround a cygwin issue - LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nre $(SEXPR))) -else +ifeq ($(SYSTYPE),Darwin) LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nEe $(SEXPR))) +else + LIBTOKENS := $(sort $(shell cat $(SKETCHPDESRCS) $(SKETCHSRCS) | sed -nre $(SEXPR))) endif # From e78d6dc046cd63c7ff779b2469855ddefd137b49 Mon Sep 17 00:00:00 2001 From: Amilcar Lucas Date: Mon, 12 Sep 2011 21:24:54 +0200 Subject: [PATCH 6/7] Remove file added by accident --- config.mk | 2 -- 1 file changed, 2 deletions(-) delete mode 100644 config.mk diff --git a/config.mk b/config.mk deleted file mode 100644 index 8375e45334..0000000000 --- a/config.mk +++ /dev/null @@ -1,2 +0,0 @@ -BOARD=mega -PORT=/dev/null From 49b31299efd39d4ac9af07ecb986d078c833c016 Mon Sep 17 00:00:00 2001 From: Amilcar Lucas Date: Mon, 12 Sep 2011 21:32:05 +0200 Subject: [PATCH 7/7] These defines got moved to the library --- ArduCopter/defines.h | 8 -------- 1 file changed, 8 deletions(-) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 5a0dcbfd91..9bd0fb9f88 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -87,14 +87,6 @@ // Note channels are from 0! // // XXX these should be CH_n defines from RC.h at some point. -#define CH_1 0 -#define CH_2 1 -#define CH_3 2 -#define CH_4 3 -#define CH_5 4 -#define CH_6 5 -#define CH_7 6 -#define CH_8 7 #define CH_10 9 //PB5 #define CH_11 10 //PE3