/* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ /* * AP_Motors6DOF.cpp - ArduSub motors library */ #include #include "AP_Motors6DOF.h" extern const AP_HAL::HAL& hal; // parameters for the motor class const AP_Param::GroupInfo AP_Motors6DOF::var_info[] = { AP_NESTEDGROUPINFO(AP_MotorsMulticopter, 0), // @Param: 1_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("1_DIRECTION", 1, AP_Motors6DOF, _motor_reverse[0], 1), // @Param: 2_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("2_DIRECTION", 2, AP_Motors6DOF, _motor_reverse[1], 1), // @Param: 3_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("3_DIRECTION", 3, AP_Motors6DOF, _motor_reverse[2], 1), // @Param: 4_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("4_DIRECTION", 4, AP_Motors6DOF, _motor_reverse[3], 1), // @Param: 5_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("5_DIRECTION", 5, AP_Motors6DOF, _motor_reverse[4], 1), // @Param: 6_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("6_DIRECTION", 6, AP_Motors6DOF, _motor_reverse[5], 1), // @Param: 7_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("7_DIRECTION", 7, AP_Motors6DOF, _motor_reverse[6], 1), // @Param: 8_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("8_DIRECTION", 8, AP_Motors6DOF, _motor_reverse[7], 1), // @Param: FV_CPLNG_K // @DisplayName: Forward/vertical to pitch decoupling factor // @Description: Used to decouple pitch from forward/vertical motion. 0 to disable, 1.2 normal // @Range: 0.0 1.5 // @Increment: 0.1 // @User: Standard AP_GROUPINFO("FV_CPLNG_K", 9, AP_Motors6DOF, _forwardVerticalCouplingFactor, 1.0), // @Param: 9_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("9_DIRECTION", 10, AP_Motors6DOF, _motor_reverse[8], 1), // @Param: 10_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("10_DIRECTION", 11, AP_Motors6DOF, _motor_reverse[9], 1), // @Param: 11_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("11_DIRECTION", 12, AP_Motors6DOF, _motor_reverse[10], 1), // @Param: 12_DIRECTION // @DisplayName: Motor normal or reverse // @Description: Used to change motor rotation directions without changing wires // @Values: 1:normal,-1:reverse // @User: Standard AP_GROUPINFO("12_DIRECTION", 13, AP_Motors6DOF, _motor_reverse[11], 1), AP_GROUPEND }; void AP_Motors6DOF::setup_motors(motor_frame_class frame_class, motor_frame_type frame_type) { // remove existing motors for (int8_t i=0; i= _throttle_thrust_max) { throttle_thrust = _throttle_thrust_max; limit.throttle_upper = true; } // calculate roll, pitch and yaw for each motor for (i=0; i= _throttle_thrust_max) { throttle_thrust = _throttle_thrust_max; limit.throttle_upper = true; } // calculate roll, pitch and yaw for each motor for (i=0; i= _throttle_thrust_max) { throttle_thrust = _throttle_thrust_max; limit.throttle_upper = true; } // calculate roll, pitch and Throttle for each motor (only used by vertical thrusters) rpt_max = 1; //Initialized to 1 so that normalization will only occur if value is saturated for (i=0; i rpt_max) { rpt_max = fabsf(rpt_out[i]); } } } // calculate linear/yaw command for each motor (only used for translational thrusters) // linear factors should be 0.0 or 1.0 for now yfl_max = 1; //Initialized to 1 so that normalization will only occur if value is saturated for (i=0; i yfl_max) { yfl_max = fabsf(yfl_out[i]); } } } // Calculate final output for each motor and normalize if necessary for (i=0; i