sakuraclamp / arducopter

Automatically exported from code.google.com/p/arducopter
0 stars 0 forks source link

CH7 Set Home & Disarm motors #481

Closed GoogleCodeExporter closed 8 years ago

GoogleCodeExporter commented 8 years ago
I updated the attached 2.7.3 files to include a CH7 option for setting the home 
location but only if the ground speed is < 1 this might need to be adjusted.  
I'm not sure if the g_gps->ground_speed is cm or m/s and I also created an 
option to disarm the motors.  

Original issue reported on code.google.com by KSchumac...@gmail.com on 7 Sep 2012 at 3:38

GoogleCodeExporter commented 8 years ago
I do have one question for the developers, what is the proper method of 
submitting a revision / modification to the existing code?

Original comment by KSchumac...@gmail.com on 7 Sep 2012 at 3:39

GoogleCodeExporter commented 8 years ago
Best thing to do is make a clone and add your patch. Document it with each 
commit. Break up your commits ino small pieces they can be reviewed 
individually. 

Original comment by jasonshort on 7 Sep 2012 at 5:11

GoogleCodeExporter commented 8 years ago
Thanks for the info Jason.  First time using GIT, and I still don't know all 
the functions.  Here's my CH7_Patch file.

ArduCopter/APM_Config.h      |  2 ++
 ArduCopter/control_modes.pde | 10 ++++++++++
 ArduCopter/defines.h         |  2 ++
 ArduCopter/options.cmake     |  4 +++-
 4 files changed, 17 insertions(+), 1 deletion(-)

diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h
index 6ea70a6..2f8bfdc 100644
--- a/ArduCopter/APM_Config.h
+++ b/ArduCopter/APM_Config.h
@@ -41,6 +41,8 @@
  *  CH7_ADC_FILTER (experimental)
  *  CH7_SAVE_WP
  *  CH7_MULTI_MODE
+ *  CH7_SET_HOME
+ *  CH7_DISARM_MOTORS
  */

 //#define TOY_EDF  ENABLED
diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde
index 501abc5..30fcb8d 100644
--- a/ArduCopter/control_modes.pde
+++ b/ArduCopter/control_modes.pde
@@ -151,6 +151,16 @@ static void read_trim_switch()
         if (g.rc_7.radio_in > CH_7_PWM_TRIGGER) {
             auto_level_counter = 10;
         }
+    }else if (option == CH7_SET_HOME) {
+        if (g.rc_7.radio_in > CH_7_PWM_TRIGGER) {
+            if(g_gps->ground_speed < 1){                        // Check the 
ground speed before setting home
+                init_home();
+            }
+        }
+    }else if (option == CH7_DISARM_MOTORS) {
+        if (g.rc_7.radio_in > CH_7_PWM_TRIGGER) {
+            init_disarm_motors();
+        }
     }
 }

diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h
index 51ff7fd..4a531e4 100644
--- a/ArduCopter/defines.h
+++ b/ArduCopter/defines.h
@@ -50,6 +50,8 @@
 #define CH7_ADC_FILTER 6
 #define CH7_SAVE_WP 7
 #define CH7_MULTI_MODE 8
+#define CH7_SET_HOME 9
+#define CH7_DISARM_MOTORS 10

 // Frame types
diff --git a/ArduCopter/options.cmake b/ArduCopter/options.cmake
index ba6ea08..e71dc23 100644
--- a/ArduCopter/options.cmake
+++ b/ArduCopter/options.cmake
@@ -156,7 +156,9 @@ apm_option("CH7_OPTION" TYPE STRING
         "CH7_RTL"
         "CH7_AUTO_TRIM"
         "CH7_ADC_FILTER"
-        "CH7_SAVE_WP")
+        "CH7_SAVE_WP"
+        "CH7_SET_HOME"
+        "CH7_DISARM_MOTORS")

 apm_option("ACCEL_ALT_HOLD" TYPE BOOL ADVANCED
     DESCRIPTION "Disabled by default, work in progress."

Original comment by KSchumac...@gmail.com on 7 Sep 2012 at 1:45

GoogleCodeExporter commented 8 years ago
Hi there KS,

I have been looking for this function. Thank you.

I would like to implement your patch but am unsure of how to go about it. 

Could someone please help me to do so safely.

Many thanks

Original comment by fouriebrad@gmail.com on 8 Nov 2012 at 5:37

GoogleCodeExporter commented 8 years ago
Closing all issues on the old issues list by marking them WontFix.

If this is still a valid issue please re-raise it on the new GitHub issues 
list: https://github.com/diydrones/ardupilot/issues

Thanks!

Original comment by rmackay...@gmail.com on 21 Jul 2013 at 2:14