Gathiyo / arducopter

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

Failsafe fix #300

Closed GoogleCodeExporter closed 8 years ago

GoogleCodeExporter commented 8 years ago
As I commented on the Arducopter 2.0.55 post 
(http://diydrones.com/forum/topics/arducopter-2-0-55), failsafe doesn't work 
with my receiver. When ArduCopter detects a failsafe the motors always stop 
because motor_auto_armed variable is false.
I use a Corona RP8D1 receiver, when it looses contact with TX outputs plain 
signal to APM. Maybe falsafe works with other receivers if they outputs a fixed 
throttle value (lower than THROTTLE_FS_VALUE) on failsafe.

Here is the fix:

system.pde -> set_mode()

change
  motor_auto_armed = (g.rc_3.control_in > 0);
to 
  motor_auto_armed = (g.rc_3.control_in > 0) || failsafe;

ArduCopter.pde -> adjust_altitude()

change 
  if(g.rc_3.control_in <= 180){
to
  if(g.rc_3.control_in <= 180 && !failsafe){

and change
  }else if  (g.rc_3.control_in >= 650){
to
  }else if  (g.rc_3.control_in >= 650 && !failsafe){

I've tested it on the ground and it works.

Original issue reported on code.google.com by modc...@gmail.com on 9 Dec 2011 at 2:08

GoogleCodeExporter commented 8 years ago
Has anyone seen this? Today I have tested it in the air and finally failsafe 
worked :) alleluia!

Original comment by modc...@gmail.com on 10 Dec 2011 at 7:07

GoogleCodeExporter commented 8 years ago
Thanks, added to 2.1

Original comment by jasonshort on 13 Dec 2011 at 7:35