123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861 |
- /*
- 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 <http://www.gnu.org/licenses/>.
- */
- /*
- * AP_Motors6DOF.cpp - ArduSub motors library
- */
- #include <AP_BattMonitor/AP_BattMonitor.h>
- #include <AP_HAL/AP_HAL.h>
- #include "AP_Motors6DOF.h"
- #include <GCS_MAVLink/GCS.h>
- #include <AP_UAVCAN/AP_UAVCAN.h>
- #include "../../ArduSub/Sub.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<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- remove_motor(i);
- }
- // hard coded config for supported frames
- switch ((sub_frame_t)frame_class) {
- // Motor # Roll Factor Pitch Factor Yaw Factor Throttle Factor Forward Factor Lateral Factor Testing Order
- case SUB_FRAME_BLUEROV1:
- 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.5f, -0.5f, 0, -1.0f, 0, 0, 3);
- add_motor_raw_6dof(AP_MOTORS_MOT_4, -0.5f, -0.5f, 0, -1.0f, 0, 0, 4);
- add_motor_raw_6dof(AP_MOTORS_MOT_5, 0, 1.0f, 0, -1.0f, 0, 0, 5);
- add_motor_raw_6dof(AP_MOTORS_MOT_6, -0.25f, 0, 0, 0, 0, 1.0f, 6);
- break;
- case SUB_FRAME_VECTORED_6DOF_90DEG:
- add_motor_raw_6dof(AP_MOTORS_MOT_1, 1.0f, 1.0f, 0, 1.0f, 0, 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, 1.0f, -1.0f, 0, 1.0f, 0, 0, 3);
- add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 0, 0, 0, 1.0f, 4);
- add_motor_raw_6dof(AP_MOTORS_MOT_5, 0, 0, 0, 0, 0, 1.0f, 5);
- add_motor_raw_6dof(AP_MOTORS_MOT_6, -1.0f, 1.0f, 0, 1.0f, 0, 0, 6);
- add_motor_raw_6dof(AP_MOTORS_MOT_7, 0, 0, -1.0f, 0, 1.0f, 0, 7);
- add_motor_raw_6dof(AP_MOTORS_MOT_8, -1.0f, -1.0f, 0, 1.0f, 0, 0, 8);
- break;
- case SUB_FRAME_VECTORED_6DOF:
- add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, 1.0f, 0, -1.0f, 1.0f, 1);
- add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, -1.0f, 0, -1.0f, -1.0f, 2);
- add_motor_raw_6dof(AP_MOTORS_MOT_3, 0, 0, -1.0f, 0, 1.0f, 1.0f, 3);
- add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 1.0f, 0, 1.0f, -1.0f, 4);
- add_motor_raw_6dof(AP_MOTORS_MOT_5, 1.0f, -1.0f, 0, -1.0f, 0, 0, 5);
- add_motor_raw_6dof(AP_MOTORS_MOT_6, -1.0f, -1.0f, 0, -1.0f, 0, 0, 6);
- add_motor_raw_6dof(AP_MOTORS_MOT_7, 1.0f, 1.0f, 0, -1.0f, 0, 0, 7);
- add_motor_raw_6dof(AP_MOTORS_MOT_8, -1.0f, 1.0f, 0, -1.0f, 0, 0, 8);
- break;
- case SUB_FRAME_VECTORED:
- add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, 1.0f, 0, -1.0f, 1.0f, 1);
- add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, -1.0f, 0, -1.0f, -1.0f, 2);
- add_motor_raw_6dof(AP_MOTORS_MOT_3, 0, 0, -1.0f, 0, 1.0f, 1.0f, 3);
- add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 1.0f, 0, 1.0f, -1.0f, 4);
- add_motor_raw_6dof(AP_MOTORS_MOT_5, 1.0f, 0, 0, -1.0f, 0, 0, 5);
- add_motor_raw_6dof(AP_MOTORS_MOT_6, -1.0f, 0, 0, -1.0f, 0, 0, 6);
- break;
- case SUB_FRAME_CUSTOM:
- // Put your custom motor setup here
- //break;
- case SUB_FRAME_SIMPLEROV_3:
- 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);
- break;
- case SUB_FRAME_SIMPLEROV_4:
- case SUB_FRAME_SIMPLEROV_5:
- 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, 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;
- }
- }
- void AP_Motors6DOF::add_motor_raw_6dof(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, float throttle_fac, float forward_fac, float lat_fac, uint8_t testing_order)
- {
- //Parent takes care of enabling output and setting up masks
- add_motor_raw(motor_num, roll_fac, pitch_fac, yaw_fac, testing_order);
- //These are additional parameters for an ROV
- _throttle_factor[motor_num] = throttle_fac;
- _forward_factor[motor_num] = forward_fac;
- _lateral_factor[motor_num] = lat_fac;
- }
- // output_min - sends minimum values out to the motors
- void AP_Motors6DOF::output_min()
- {
- int8_t i;
- // set limits flags
- limit.roll = true;
- limit.pitch = true;
- limit.yaw = true;
- limit.throttle_lower = false;
- limit.throttle_upper = false;
- // fill the motor_out[] array for HIL use and send minimum value to each motor
- // ToDo find a field to store the minimum pwm instead of hard coding 1500
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- rc_write(i, 1500);
- }
- }
- }
- #define ThrustScale 1000
- #define hv_min 251
- #define hv_max 2200
- int16_t AP_Motors6DOF::calc_thrust_to_HV(float thrust_in,int8_t i)
- {
- int16_t thrust = 0;
- //float ratio= 0.02;//阶跃百分比
- // int16_t step = 4;//4;//步长 0加到1024需要320毫秒
- // int16_t step_thrust = 4;//4;//退出缓启动的条件
- int16_t stephv = 20;
- thrust = (int16_t)(thrust_in* ThrustScale);
- if(i<2)
- {
- last_thrust_Dhot[i] = thrust;
- return constrain_int16(last_thrust_Dhot[i],-1000, 1000);
- //输入比例与上次比例差 >ration
- /* if (fabsf(thrust_in - last_thrust_in[i]) > ratio)
- {//缓加缓减
- if (thrust >= last_thrust_Dhot[i] + step)
- {//新的Dshot >当前的Dshot + 步长
- last_thrust_Dhot[i] += step;
- }
- else if(thrust <= last_thrust_Dhot[i] -step)
- {//新的Dshot < 当前的Dshot -步长
- last_thrust_Dhot[i] -= step;
- }
- if (thrust>=last_thrust_Dhot[i] - step_thrust && thrust<=last_thrust_Dhot[i] + step_thrust){
- last_thrust_in[i] = thrust_in;
- last_thrust_Dhot[i] = thrust;
- }
- if ((last_thrust_Dhot[i]< step && last_thrust_Dhot[i]> -step) && thrust == 0)
- {
- last_thrust_Dhot[i] =0;
- }
- }
- else{
- //比例之差<ration 直接赋值
- last_thrust_Dhot[i] = thrust;
- last_thrust_in[i] = thrust_in;
- }
- return constrain_int16(last_thrust_Dhot[i],-1000, 1000);*/
-
- }
- else{
-
- if (thrust>=last_thrust_Dhot[i] - stephv && thrust<=last_thrust_Dhot[i] + stephv){
-
- last_thrust_Dhot[i] = thrust;
- }else if (thrust >= last_thrust_Dhot[i] + stephv)
- {//新的Dshot >当前的Dshot + 步长
- last_thrust_Dhot[i] += stephv;
- }
- else if(thrust <= last_thrust_Dhot[i] -stephv)
- {//新的Dshot < 当前的Dshot -步长
- last_thrust_Dhot[i] -= stephv;
- }
- if (last_thrust_Dhot[i]< stephv && last_thrust_Dhot[i]> -stephv)
- {
- last_thrust_Dhot[i] =0;
- }
-
-
- int16_t speedref = (int16_t)((int32_t)last_thrust_Dhot[i]*hv_max/1000);
- return constrain_int16(speedref,-hv_max, hv_max);
- }
- }
- int16_t AP_Motors6DOF::calc_thrust_to_Dshot(float thrust_in,int8_t i)
- {
- int16_t thrust = 0;
- float ratio= 0.02;//阶跃百分比
- int16_t step = 8;//4;//步长 0加到1024需要320毫秒
- int16_t step_thrust = 8;//4;//退出缓启动的条件
- thrust = (int16_t)(thrust_in* ThrustScale);
- //输入比例与上次比例差 >ration
- if (fabsf(thrust_in - last_thrust_in[i]) > ratio)
- {//缓加缓减
- if (thrust >= last_thrust_Dhot[i] + step)
- {//新的Dshot >当前的Dshot + 步长
- last_thrust_Dhot[i] += step;
- }
- else if(thrust <= last_thrust_Dhot[i] -step)
- {//新的Dshot < 当前的Dshot -步长
- last_thrust_Dhot[i] -= step;
- }
- if (thrust>=last_thrust_Dhot[i] - step_thrust && thrust<=last_thrust_Dhot[i] + step_thrust){
- last_thrust_in[i] = thrust_in;
- last_thrust_Dhot[i] = thrust;
- }
- if ((last_thrust_Dhot[i]< step && last_thrust_Dhot[i]> -step) && thrust == 0)
- {
- last_thrust_Dhot[i] =0;
- }
- }
- else{
- //比例之差<ration 直接赋值
- last_thrust_Dhot[i] = thrust;
- last_thrust_in[i] = thrust_in;
- }
- if (i<2)
- {
- return constrain_int16(last_thrust_Dhot[i],-1000, 1000);
- }
- else{
- return constrain_int16(last_thrust_Dhot[i],-910, 910);//ThrustScale -770, 810
- }
- }
- extern mavlink_motor_speed_t mav_motor_speed;
- void AP_Motors6DOF::output_to_Dshot()
- {
- int8_t i;
- int16_t motor_out[AP_MOTORS_MAX_NUM_MOTORS]; // final pwm values sent to the motor
- switch (_spool_state) {
- case SpoolState::SHUT_DOWN:
- // sends minimum values out to the motors
- // set motor output based on thrust requests
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- motor_out[i] = 0;
- }
- }
- break;
- case SpoolState::GROUND_IDLE:
- // sends output to motors when armed but not flying
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- motor_out[i] = 0;
- }
- }
- break;
- case SpoolState::SPOOLING_UP:
- case SpoolState::THROTTLE_UNLIMITED:
- case SpoolState::SPOOLING_DOWN:
- {
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- //将油门比例转换成Dshot协议形式,增加了缓启动
- //motor_out[i] = calc_thrust_to_Dshot(_thrust_rpyt_out[i],i);
-
- motor_out[i] = calc_thrust_to_HV(_thrust_rpyt_out[i],i);
- }
- }
- break;}
- }
-
- //const AP_UAVCAN &uavcan = AP::uavcan();//6自由度电机计算出来的PWM
- //将上位机转发过来的,转换成Dshot协议并使用CAN 转发
- if(mav_motor_speed.motorTest == 1)
- {//测试模式上位机直接控制 仅仅控制6个推进器
- motor_to_can[0] = (int16_t)(mav_motor_speed.motor1*1000);
- motor_to_can[1] = (int16_t)(mav_motor_speed.motor2*1000);
- motor_to_can[2] = mav_motor_speed.motor3;
- motor_to_can[3] = mav_motor_speed.motor4;
- motor_to_can[4] = mav_motor_speed.motor5;
- motor_to_can[5] = mav_motor_speed.motor6;
- motor_to_can[6] = mav_motor_speed.motor7;
- motor_to_can[7] = mav_motor_speed.motor8;
-
-
- }
- else
- {
- motor_to_can[0] = motor_out[0];//赋值给can
- motor_to_can[1] = motor_out[1];//赋值给can
- motor_to_can[2] = motor_out[2];//赋值给can
- motor_to_can[3] = motor_out[3];//赋值给can
- motor_to_can[4] = motor_out[4];//赋值给can
- motor_to_can[5] = motor_out[5];//赋值给can
- motor_to_can[6] = motor_out[6];//赋值给can
- motor_to_can[7] = motor_out[7];//赋值给can
- }
- }
- int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const
- {
- return constrain_int16(1500 + thrust_in * 400, _throttle_radio_min, _throttle_radio_max);
- }
- void AP_Motors6DOF::output_to_motors()
- {
- int8_t i;
- int16_t motor_out[AP_MOTORS_MAX_NUM_MOTORS]; // final pwm values sent to the motor
- switch (_spool_state) {
- case SpoolState::SHUT_DOWN:
- // sends minimum values out to the motors
- // set motor output based on thrust requests
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- motor_out[i] = 1500;
- }
- }
- break;
- case SpoolState::GROUND_IDLE:
- // sends output to motors when armed but not flying
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- motor_out[i] = 1500;
- }
- }
- break;
- case SpoolState::SPOOLING_UP:
- case SpoolState::THROTTLE_UNLIMITED:
- case SpoolState::SPOOLING_DOWN:
- // set motor output based on thrust requests
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- motor_out[i] = calc_thrust_to_pwm(_thrust_rpyt_out[i]);
- }
- }
- break;
- }
- // send output to each motor
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- rc_write(i, motor_out[i]);
- }
- }
- }
- float AP_Motors6DOF::get_current_limit_max_throttle()
- {
- return 1.0f;
- }
- // output_armed - sends commands to the motors
- // includes new scaling stability patch
- // TODO pull code that is common to output_armed_not_stabilizing into helper functions
- // ToDo calculate headroom for rpy to be added for stabilization during full throttle/forward/lateral commands
- void AP_Motors6DOF::output_armed_stabilizing()
- {
- if ((sub_frame_t)_last_frame_class == SUB_FRAME_VECTORED) {
- output_armed_stabilizing_vectored();
- } else if ((sub_frame_t)_last_frame_class == SUB_FRAME_VECTORED_6DOF) {
- output_armed_stabilizing_vectored_6dof();
- } else if ((sub_frame_t)_last_frame_class == SUB_FRAME_BLUEROV1){
- uint8_t i; // general purpose counter
- float roll_thrust; // roll thrust input value, +/- 1.0
- float pitch_thrust; // pitch thrust input value, +/- 1.0
- float yaw_thrust; // yaw thrust input value, +/- 1.0
- float throttle_thrust; // throttle thrust input value, +/- 1.0
- float forward_thrust; // forward thrust input value, +/- 1.0
- float lateral_thrust; // lateral thrust input value, +/- 1.0
- roll_thrust = (_roll_in + _roll_in_ff);
- pitch_thrust = (_pitch_in + _pitch_in_ff);
- yaw_thrust = (_yaw_in + _yaw_in_ff);
- throttle_thrust = get_throttle_bidirectional();
- forward_thrust = _forward_in;
- lateral_thrust = _lateral_in;
- float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
- float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
- // initialize limits flags
- limit.roll = false;
- limit.pitch = false;
- limit.yaw = false;
- limit.throttle_lower = false;
- limit.throttle_upper = false;
- // sanity check throttle is above zero and below current limited throttle
- if (throttle_thrust <= -_throttle_thrust_max) {
- throttle_thrust = -_throttle_thrust_max;
- limit.throttle_lower = true;
- }
- if (throttle_thrust >= _throttle_thrust_max) {
- throttle_thrust = _throttle_thrust_max;
- limit.throttle_upper = true;
- }
- // calculate roll, pitch and yaw for each motor
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- rpy_out[i] = roll_thrust * _roll_factor[i] +
- pitch_thrust * _pitch_factor[i] +
- yaw_thrust * _yaw_factor[i];
- }
- }
- // calculate linear command for each motor
- // linear factors should be 0.0 or 1.0 for now
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- linear_out[i] = throttle_thrust * _throttle_factor[i] +
- forward_thrust * _forward_factor[i] +
- lateral_thrust * _lateral_factor[i];
- }
- }
- // Calculate final output for each motor
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]),-1.0f,1.0f);
- }
- }
- }
- else{
- uint8_t i; // general purpose counter
- float roll_thrust; // roll thrust input value, +/- 1.0
- float pitch_thrust; // pitch thrust input value, +/- 1.0
- float yaw_thrust; // yaw thrust input value, +/- 1.0
- float throttle_thrust; // throttle thrust input value, +/- 1.0
- float forward_thrust; // forward thrust input value, +/- 1.0
- float lateral_thrust; // lateral thrust input value, +/- 1.0
- roll_thrust = (_roll_in + _roll_in_ff);
- pitch_thrust = (_pitch_in + _pitch_in_ff);
- yaw_thrust = (_yaw_in + _yaw_in_ff);
- throttle_thrust = get_throttle_bidirectional();
- forward_thrust = _forward_in;
- lateral_thrust = _lateral_in;
- float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
- float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
- // initialize limits flags
- limit.roll = false;
- limit.pitch = false;
- limit.yaw = false;
- limit.throttle_lower = false;
- limit.throttle_upper = false;
- // sanity check throttle is above zero and below current limited throttle
- if (throttle_thrust <= -_throttle_thrust_max) {
- throttle_thrust = -_throttle_thrust_max;
- limit.throttle_lower = true;
- }
- if (throttle_thrust >= _throttle_thrust_max) {
- throttle_thrust = _throttle_thrust_max;
- limit.throttle_upper = true;
- }
- // calculate roll, pitch and yaw for each motor
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- rpy_out[i] = roll_thrust * _roll_factor[i] +
- pitch_thrust * _pitch_factor[i] +
- yaw_thrust * _yaw_factor[i];
- }
- }
- // calculate linear command for each motor
- // linear factors should be 0.0 or 1.0 for now
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- linear_out[i] = throttle_thrust * _throttle_factor[i] +
- forward_thrust * _forward_factor[i] +
- lateral_thrust * _lateral_factor[i];
- }
- }
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- linear_out[i] = throttle_thrust * _throttle_factor[i] +
- forward_thrust * _forward_factor[i] +
- lateral_thrust * _lateral_factor[i];
- }
- }
-
- // Calculate final output for each motor
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]),-1.0f,1.0f);
- }
- }
- }
- const AP_BattMonitor &battery = AP::battery();
- // Current limiting
- float _batt_current;
- if (_batt_current_max <= 0.0f || !battery.current_amps(_batt_current)) {
- return;
- }
- float _batt_current_delta = _batt_current - _batt_current_last;
- float loop_interval = 1.0f/_loop_rate;
- float _current_change_rate = _batt_current_delta / loop_interval;
- float predicted_current = _batt_current + (_current_change_rate * loop_interval * 5);
- float batt_current_ratio = _batt_current/_batt_current_max;
- float predicted_current_ratio = predicted_current/_batt_current_max;
- _batt_current_last = _batt_current;
- if (predicted_current > _batt_current_max * 1.5f) {
- batt_current_ratio = 2.5f;
- } else if (_batt_current < _batt_current_max && predicted_current > _batt_current_max) {
- batt_current_ratio = predicted_current_ratio;
- }
- _output_limited += (loop_interval/(loop_interval+_batt_current_time_constant)) * (1 - batt_current_ratio);
- _output_limited = constrain_float(_output_limited, 0.0f, 1.0f);
- for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- _thrust_rpyt_out[i] *= _output_limited;
- }
- }
- }
- // output_armed - sends commands to the motors
- // includes new scaling stability patch
- // TODO pull code that is common to output_armed_not_stabilizing into helper functions
- // ToDo calculate headroom for rpy to be added for stabilization during full throttle/forward/lateral commands
- void AP_Motors6DOF::output_armed_stabilizing_vectored()
- {
- uint8_t i; // general purpose counter
- float roll_thrust; // roll thrust input value, +/- 1.0
- float pitch_thrust; // pitch thrust input value, +/- 1.0
- float yaw_thrust; // yaw thrust input value, +/- 1.0
- float throttle_thrust; // throttle thrust input value, +/- 1.0
- float forward_thrust; // forward thrust input value, +/- 1.0
- float lateral_thrust; // lateral thrust input value, +/- 1.0
- roll_thrust = (_roll_in + _roll_in_ff);
- pitch_thrust = (_pitch_in + _pitch_in_ff);
- yaw_thrust = (_yaw_in + _yaw_in_ff);
- throttle_thrust = get_throttle_bidirectional();
- forward_thrust = _forward_in;
- lateral_thrust = _lateral_in;
- float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
- float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
- // initialize limits flags
- limit.roll= false;
- limit.pitch = false;
- limit.yaw = false;
- limit.throttle_lower = false;
- limit.throttle_upper = false;
- // sanity check throttle is above zero and below current limited throttle
- if (throttle_thrust <= -_throttle_thrust_max) {
- throttle_thrust = -_throttle_thrust_max;
- limit.throttle_lower = true;
- }
- if (throttle_thrust >= _throttle_thrust_max) {
- throttle_thrust = _throttle_thrust_max;
- limit.throttle_upper = true;
- }
- // calculate roll, pitch and yaw for each motor
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- rpy_out[i] = roll_thrust * _roll_factor[i] +
- pitch_thrust * _pitch_factor[i] +
- yaw_thrust * _yaw_factor[i];
- }
- }
- float forward_coupling_limit = 1-_forwardVerticalCouplingFactor*float(fabsf(throttle_thrust));
- if (forward_coupling_limit < 0) {
- forward_coupling_limit = 0;
- }
- int8_t forward_coupling_direction[] = {-1,-1,1,1,0,0,0,0,0,0,0,0};
- // calculate linear command for each motor
- // linear factors should be 0.0 or 1.0 for now
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- float forward_thrust_limited = forward_thrust;
- // The following statements decouple forward/vertical hydrodynamic coupling on
- // vectored ROVs. This is done by limiting the maximum output of the "rear" vectored
- // thruster (where "rear" depends on direction of travel).
- if (!is_zero(forward_thrust_limited)) {
- if ((forward_thrust < 0) == (forward_coupling_direction[i] < 0) && forward_coupling_direction[i] != 0) {
- forward_thrust_limited = constrain_float(forward_thrust, -forward_coupling_limit, forward_coupling_limit);
- }
- }
- linear_out[i] = throttle_thrust * _throttle_factor[i] +
- forward_thrust_limited * _forward_factor[i] +
- lateral_thrust * _lateral_factor[i];
- }
- }
- // Calculate final output for each motor
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]), -1.0f, 1.0f);
- }
- }
- }
- // Band Aid fix for motor normalization issues.
- // TODO: find a global solution for managing saturation that works for all vehicles
- void AP_Motors6DOF::output_armed_stabilizing_vectored_6dof()
- {
- uint8_t i; // general purpose counter
- float roll_thrust; // roll thrust input value, +/- 1.0
- float pitch_thrust; // pitch thrust input value, +/- 1.0
- float yaw_thrust; // yaw thrust input value, +/- 1.0
- float throttle_thrust; // throttle thrust input value, +/- 1.0
- float forward_thrust; // forward thrust input value, +/- 1.0
- float lateral_thrust; // lateral thrust input value, +/- 1.0
- roll_thrust = (_roll_in + _roll_in_ff);
- pitch_thrust = (_pitch_in + _pitch_in_ff);
- yaw_thrust = (_yaw_in + _yaw_in_ff);
- throttle_thrust = get_throttle_bidirectional();
- forward_thrust = _forward_in;
- lateral_thrust = _lateral_in;
- float rpt_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
- float yfl_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
- float rpt_max;
- float yfl_max;
- // initialize limits flags
- limit.roll = false;
- limit.pitch = false;
- limit.yaw = false;
- limit.throttle_lower = false;
- limit.throttle_upper = false;
- // sanity check throttle is above zero and below current limited throttle
- if (throttle_thrust <= -_throttle_thrust_max) {
- throttle_thrust = -_throttle_thrust_max;
- limit.throttle_lower = true;
- }
- if (throttle_thrust >= _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<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- rpt_out[i] = roll_thrust * _roll_factor[i] +
- pitch_thrust * _pitch_factor[i] +
- throttle_thrust * _throttle_factor[i];
- if (fabsf(rpt_out[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<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- yfl_out[i] = yaw_thrust * _yaw_factor[i] +
- forward_thrust * _forward_factor[i] +
- lateral_thrust * _lateral_factor[i];
- if (fabsf(yfl_out[i]) > yfl_max) {
- yfl_max = fabsf(yfl_out[i]);
- }
- }
- }
- // Calculate final output for each motor and normalize if necessary
- for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
- if (motor_enabled[i]) {
- _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpt_out[i]/rpt_max + yfl_out[i]/yfl_max),-1.0f,1.0f);
- }
- }
- }
- Vector3f AP_Motors6DOF::get_motor_angular_factors(int motor_number) {
- if (motor_number < 0 || motor_number >= AP_MOTORS_MAX_NUM_MOTORS) {
- return Vector3f(0,0,0);
- }
- return Vector3f(_roll_factor[motor_number], _pitch_factor[motor_number], _yaw_factor[motor_number]);
- }
- bool AP_Motors6DOF::motor_is_enabled(int motor_number) {
- if (motor_number < 0 || motor_number >= AP_MOTORS_MAX_NUM_MOTORS) {
- return false;
- }
- return motor_enabled[motor_number];
- }
- bool AP_Motors6DOF::set_reversed(int motor_number, bool reversed) {
- if (motor_number < 0 || motor_number >= AP_MOTORS_MAX_NUM_MOTORS) {
- return false;
- }
- if (reversed) {
- _motor_reverse[motor_number].set_and_save(-1);
- } else {
- _motor_reverse[motor_number].set_and_save(1);
- }
- return true;
- }
- //--------------wangdan--------
- AP_Motors6DOF *AP_Motors6DOF::_singleton;
- namespace AP {
- AP_Motors6DOF &motors6dof()
- {
- return *AP_Motors6DOF::get_singleton();
- }
- };
|