ACM: Allow for user defined roll and pitch input max
This commit is contained in:
parent
f68523b39b
commit
9735a0eff1
@ -715,6 +715,13 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Stabilize Rate Control
|
||||
//
|
||||
|
||||
#ifndef MAX_INPUT_ROLL_ANGLE
|
||||
# define MAX_INPUT_ROLL_ANGLE 4500
|
||||
#endif
|
||||
#ifndef MAX_INPUT_PITCH_ANGLE
|
||||
# define MAX_INPUT_PITCH_ANGLE 4500
|
||||
#endif
|
||||
#ifndef RATE_ROLL_P
|
||||
# define RATE_ROLL_P 0.175
|
||||
#endif
|
||||
|
@ -21,8 +21,8 @@ static void default_dead_zones()
|
||||
static void init_rc_in()
|
||||
{
|
||||
// set rc channel ranges
|
||||
g.rc_1.set_angle(4500);
|
||||
g.rc_2.set_angle(4500);
|
||||
g.rc_1.set_angle(MAX_INPUT_ROLL_ANGLE);
|
||||
g.rc_2.set_angle(MAX_INPUT_PITCH_ANGLE);
|
||||
#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);
|
||||
|
Loading…
Reference in New Issue
Block a user