mirror of https://github.com/ArduPilot/ardupilot
TradHeli - change throttle range back to 0~1000 (was temporarily changed to be 1250~850 which limited the range of the swash plate's vertical movements)
This commit is contained in:
parent
6cf7f45f2e
commit
9fabdb5797
|
@ -22,7 +22,12 @@ static void init_rc_in()
|
||||||
// set rc channel ranges
|
// set rc channel ranges
|
||||||
g.rc_1.set_angle(4500);
|
g.rc_1.set_angle(4500);
|
||||||
g.rc_2.set_angle(4500);
|
g.rc_2.set_angle(4500);
|
||||||
g.rc_3.set_range(MINIMUM_THROTTLE, MAXIMUM_THROTTLE);
|
#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(MINIMUM_THROTTLE, MAXIMUM_THROTTLE);
|
||||||
|
#endif
|
||||||
g.rc_4.set_angle(4500);
|
g.rc_4.set_angle(4500);
|
||||||
|
|
||||||
// reverse: CW = left
|
// reverse: CW = left
|
||||||
|
@ -32,13 +37,6 @@ static void init_rc_in()
|
||||||
g.rc_2.set_type(RC_CHANNEL_ANGLE_RAW);
|
g.rc_2.set_type(RC_CHANNEL_ANGLE_RAW);
|
||||||
g.rc_4.set_type(RC_CHANNEL_ANGLE_RAW);
|
g.rc_4.set_type(RC_CHANNEL_ANGLE_RAW);
|
||||||
|
|
||||||
// set rc dead zones
|
|
||||||
/*g.rc_1.dead_zone = 60;
|
|
||||||
g.rc_2.dead_zone = 60;
|
|
||||||
g.rc_3.dead_zone = 60;
|
|
||||||
g.rc_4.dead_zone = 300;
|
|
||||||
*/
|
|
||||||
|
|
||||||
//set auxiliary ranges
|
//set auxiliary ranges
|
||||||
g.rc_5.set_range(0,1000);
|
g.rc_5.set_range(0,1000);
|
||||||
g.rc_6.set_range(0,1000);
|
g.rc_6.set_range(0,1000);
|
||||||
|
|
Loading…
Reference in New Issue