From 8fcebbc8b1219dee9f6913903c7371271b8497b9 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Tue, 17 Sep 2019 15:42:00 -0300 Subject: [PATCH] APMotors6DOF: add roll factor for motors 4 and 5 for SIMPLEROV_4 and SIMPLEROV_5 --- libraries/AP_Motors/AP_Motors6DOF.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Motors/AP_Motors6DOF.cpp b/libraries/AP_Motors/AP_Motors6DOF.cpp index 386e7d1c70..3f7acdd47a 100644 --- a/libraries/AP_Motors/AP_Motors6DOF.cpp +++ b/libraries/AP_Motors/AP_Motors6DOF.cpp @@ -181,8 +181,8 @@ void AP_Motors6DOF::setup_motors(motor_frame_class frame_class, motor_frame_type default: add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, -1.0f, 0, 1.0f, 0, 1); add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, 1.0f, 0, 1.0f, 0, 2); - add_motor_raw_6dof(AP_MOTORS_MOT_3, 0, 0, 0, -1.0f, 0, 0, 3); - add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 0, -1.0f, 0, 0, 4); + add_motor_raw_6dof(AP_MOTORS_MOT_3, 1.0f, 0, 0, -1.0f, 0, 0, 3); + add_motor_raw_6dof(AP_MOTORS_MOT_4, -1.0f, 0, 0, -1.0f, 0, 0, 4); add_motor_raw_6dof(AP_MOTORS_MOT_5, 0, 0, 0, 0, 0, 1.0f, 5); break; }