Browse Source

TradHeli: set throttle_min to zero by default

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
0f67e25d37
  1. 1
      ArduCopter/config.h
  2. 5
      ArduCopter/radio.pde

1
ArduCopter/config.h

@ -115,6 +115,7 @@ @@ -115,6 +115,7 @@
# define MPU6K_FILTER 10
# define HELI_STAB_COLLECTIVE_MIN_DEFAULT 0
# define HELI_STAB_COLLECTIVE_MAX_DEFAULT 1000
# define THR_MIN_DEFAULT 0
#endif
/////////////////////////////////////////////////////////////////////////////////

5
ArduCopter/radio.pde

@ -23,12 +23,7 @@ static void init_rc_in() @@ -23,12 +23,7 @@ static void init_rc_in()
// set rc channel ranges
g.rc_1.set_angle(ROLL_PITCH_INPUT_MAX);
g.rc_2.set_angle(ROLL_PITCH_INPUT_MAX);
#if FRAME_CONFIG == HELI_FRAME
// we do not want to limit the movment of the heli's swash plate
g.rc_3.set_range(0, 1000);
#else
g.rc_3.set_range(g.throttle_min, g.throttle_max);
#endif
g.rc_4.set_angle(4500);
g.rc_1.set_type(RC_CHANNEL_TYPE_ANGLE_RAW);

Loading…
Cancel
Save