mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
SITL: swap rotation direciton of motor 2 for lower yaw offset
This commit is contained in:
parent
4988f72ee2
commit
6628fd2837
@ -236,7 +236,7 @@ static Motor deca_cw_x_motors[] =
|
||||
static Motor tri_motors[] =
|
||||
{
|
||||
Motor(AP_MOTORS_MOT_1, 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1),
|
||||
Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3),
|
||||
Motor(AP_MOTORS_MOT_2, -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3),
|
||||
Motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2, AP_MOTORS_MOT_7, 60, -60, -1, 0, 0),
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user