AP_MotorsOctaQuad: call normalise_rpy_factors in motor setup
This commit is contained in:
parent
e182c10625
commit
7ac4fc5569
@ -70,4 +70,7 @@ void AP_MotorsOctaQuad::setup_motors()
|
||||
add_motor(AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
|
||||
add_motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6);
|
||||
}
|
||||
|
||||
// normalise factors to magnitude 0.5
|
||||
normalise_rpy_factors();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user