AP_Motors6DOF.cpp 33 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * AP_Motors6DOF.cpp - ArduSub motors library
  15. */
  16. #include <AP_BattMonitor/AP_BattMonitor.h>
  17. #include <AP_HAL/AP_HAL.h>
  18. #include "AP_Motors6DOF.h"
  19. #include <GCS_MAVLink/GCS.h>
  20. #include <AP_UAVCAN/AP_UAVCAN.h>
  21. #include "../../ArduSub/Sub.h"
  22. extern const AP_HAL::HAL& hal;
  23. // parameters for the motor class
  24. const AP_Param::GroupInfo AP_Motors6DOF::var_info[] = {
  25. AP_NESTEDGROUPINFO(AP_MotorsMulticopter, 0),
  26. // @Param: 1_DIRECTION
  27. // @DisplayName: Motor normal or reverse
  28. // @Description: Used to change motor rotation directions without changing wires
  29. // @Values: 1:normal,-1:reverse
  30. // @User: Standard
  31. AP_GROUPINFO("1_DIRECTION", 1, AP_Motors6DOF, _motor_reverse[0], 1),
  32. // @Param: 2_DIRECTION
  33. // @DisplayName: Motor normal or reverse
  34. // @Description: Used to change motor rotation directions without changing wires
  35. // @Values: 1:normal,-1:reverse
  36. // @User: Standard
  37. AP_GROUPINFO("2_DIRECTION", 2, AP_Motors6DOF, _motor_reverse[1], 1),
  38. // @Param: 3_DIRECTION
  39. // @DisplayName: Motor normal or reverse
  40. // @Description: Used to change motor rotation directions without changing wires
  41. // @Values: 1:normal,-1:reverse
  42. // @User: Standard
  43. AP_GROUPINFO("3_DIRECTION", 3, AP_Motors6DOF, _motor_reverse[2], 1),
  44. // @Param: 4_DIRECTION
  45. // @DisplayName: Motor normal or reverse
  46. // @Description: Used to change motor rotation directions without changing wires
  47. // @Values: 1:normal,-1:reverse
  48. // @User: Standard
  49. AP_GROUPINFO("4_DIRECTION", 4, AP_Motors6DOF, _motor_reverse[3], 1),
  50. // @Param: 5_DIRECTION
  51. // @DisplayName: Motor normal or reverse
  52. // @Description: Used to change motor rotation directions without changing wires
  53. // @Values: 1:normal,-1:reverse
  54. // @User: Standard
  55. AP_GROUPINFO("5_DIRECTION", 5, AP_Motors6DOF, _motor_reverse[4], 1),
  56. // @Param: 6_DIRECTION
  57. // @DisplayName: Motor normal or reverse
  58. // @Description: Used to change motor rotation directions without changing wires
  59. // @Values: 1:normal,-1:reverse
  60. // @User: Standard
  61. AP_GROUPINFO("6_DIRECTION", 6, AP_Motors6DOF, _motor_reverse[5], 1),
  62. // @Param: 7_DIRECTION
  63. // @DisplayName: Motor normal or reverse
  64. // @Description: Used to change motor rotation directions without changing wires
  65. // @Values: 1:normal,-1:reverse
  66. // @User: Standard
  67. AP_GROUPINFO("7_DIRECTION", 7, AP_Motors6DOF, _motor_reverse[6], 1),
  68. // @Param: 8_DIRECTION
  69. // @DisplayName: Motor normal or reverse
  70. // @Description: Used to change motor rotation directions without changing wires
  71. // @Values: 1:normal,-1:reverse
  72. // @User: Standard
  73. AP_GROUPINFO("8_DIRECTION", 8, AP_Motors6DOF, _motor_reverse[7], 1),
  74. // @Param: FV_CPLNG_K
  75. // @DisplayName: Forward/vertical to pitch decoupling factor
  76. // @Description: Used to decouple pitch from forward/vertical motion. 0 to disable, 1.2 normal
  77. // @Range: 0.0 1.5
  78. // @Increment: 0.1
  79. // @User: Standard
  80. AP_GROUPINFO("FV_CPLNG_K", 9, AP_Motors6DOF, _forwardVerticalCouplingFactor, 1.0),
  81. // @Param: 9_DIRECTION
  82. // @DisplayName: Motor normal or reverse
  83. // @Description: Used to change motor rotation directions without changing wires
  84. // @Values: 1:normal,-1:reverse
  85. // @User: Standard
  86. AP_GROUPINFO("9_DIRECTION", 10, AP_Motors6DOF, _motor_reverse[8], 1),
  87. // @Param: 10_DIRECTION
  88. // @DisplayName: Motor normal or reverse
  89. // @Description: Used to change motor rotation directions without changing wires
  90. // @Values: 1:normal,-1:reverse
  91. // @User: Standard
  92. AP_GROUPINFO("10_DIRECTION", 11, AP_Motors6DOF, _motor_reverse[9], 1),
  93. // @Param: 11_DIRECTION
  94. // @DisplayName: Motor normal or reverse
  95. // @Description: Used to change motor rotation directions without changing wires
  96. // @Values: 1:normal,-1:reverse
  97. // @User: Standard
  98. AP_GROUPINFO("11_DIRECTION", 12, AP_Motors6DOF, _motor_reverse[10], 1),
  99. // @Param: 12_DIRECTION
  100. // @DisplayName: Motor normal or reverse
  101. // @Description: Used to change motor rotation directions without changing wires
  102. // @Values: 1:normal,-1:reverse
  103. // @User: Standard
  104. AP_GROUPINFO("12_DIRECTION", 13, AP_Motors6DOF, _motor_reverse[11], 1),
  105. AP_GROUPEND
  106. };
  107. void AP_Motors6DOF::setup_motors(motor_frame_class frame_class, motor_frame_type frame_type)
  108. {
  109. // remove existing motors
  110. for (int8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  111. remove_motor(i);
  112. }
  113. // hard coded config for supported frames
  114. switch ((sub_frame_t)frame_class) {
  115. // Motor # Roll Factor Pitch Factor Yaw Factor Throttle Factor Forward Factor Lateral Factor Testing Order
  116. case SUB_FRAME_BLUEROV1:
  117. add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, -1.0f, 0, 1.0f, 0, 1);
  118. add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, 1.0f, 0, 1.0f, 0, 2);
  119. add_motor_raw_6dof(AP_MOTORS_MOT_3, 0.5f, -0.5f, 0, -1.0f, 0, 0, 3);
  120. add_motor_raw_6dof(AP_MOTORS_MOT_4, -0.5f, -0.5f, 0, -1.0f, 0, 0, 4);
  121. add_motor_raw_6dof(AP_MOTORS_MOT_5, 0, 1.0f, 0, -1.0f, 0, 0, 5);
  122. add_motor_raw_6dof(AP_MOTORS_MOT_6, -0.25f, 0, 0, 0, 0, 1.0f, 6);
  123. break;
  124. case SUB_FRAME_VECTORED_6DOF_90DEG:
  125. add_motor_raw_6dof(AP_MOTORS_MOT_1, 1.0f, 1.0f, 0, 1.0f, 0, 0, 1);
  126. add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, 1.0f, 0, 1.0f, 0, 2);
  127. add_motor_raw_6dof(AP_MOTORS_MOT_3, 1.0f, -1.0f, 0, 1.0f, 0, 0, 3);
  128. add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 0, 0, 0, 1.0f, 4);
  129. add_motor_raw_6dof(AP_MOTORS_MOT_5, 0, 0, 0, 0, 0, 1.0f, 5);
  130. add_motor_raw_6dof(AP_MOTORS_MOT_6, -1.0f, 1.0f, 0, 1.0f, 0, 0, 6);
  131. add_motor_raw_6dof(AP_MOTORS_MOT_7, 0, 0, -1.0f, 0, 1.0f, 0, 7);
  132. add_motor_raw_6dof(AP_MOTORS_MOT_8, -1.0f, -1.0f, 0, 1.0f, 0, 0, 8);
  133. break;
  134. case SUB_FRAME_VECTORED_6DOF:
  135. add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, 1.0f, 0, -1.0f, 1.0f, 1);
  136. add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, -1.0f, 0, -1.0f, -1.0f, 2);
  137. add_motor_raw_6dof(AP_MOTORS_MOT_3, 0, 0, -1.0f, 0, 1.0f, 1.0f, 3);
  138. add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 1.0f, 0, 1.0f, -1.0f, 4);
  139. add_motor_raw_6dof(AP_MOTORS_MOT_5, 1.0f, -1.0f, 0, -1.0f, 0, 0, 5);
  140. add_motor_raw_6dof(AP_MOTORS_MOT_6, -1.0f, -1.0f, 0, -1.0f, 0, 0, 6);
  141. add_motor_raw_6dof(AP_MOTORS_MOT_7, 1.0f, 1.0f, 0, -1.0f, 0, 0, 7);
  142. add_motor_raw_6dof(AP_MOTORS_MOT_8, -1.0f, 1.0f, 0, -1.0f, 0, 0, 8);
  143. break;
  144. case SUB_FRAME_VECTORED:
  145. add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, 1.0f, 0, -1.0f, 1.0f, 1);
  146. add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, -1.0f, 0, -1.0f, -1.0f, 2);
  147. add_motor_raw_6dof(AP_MOTORS_MOT_3, 0, 0, -1.0f, 0, 1.0f, 1.0f, 3);
  148. add_motor_raw_6dof(AP_MOTORS_MOT_4, 0, 0, 1.0f, 0, 1.0f, -1.0f, 4);
  149. add_motor_raw_6dof(AP_MOTORS_MOT_5, 1.0f, 0, 0, -1.0f, 0, 0, 5);
  150. add_motor_raw_6dof(AP_MOTORS_MOT_6, -1.0f, 0, 0, -1.0f, 0, 0, 6);
  151. break;
  152. case SUB_FRAME_CUSTOM:
  153. // Put your custom motor setup here
  154. //break;
  155. case SUB_FRAME_SIMPLEROV_3:
  156. add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, -1.0f, 0, 1.0f, 0, 1);
  157. add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, 1.0f, 0, 1.0f, 0, 2);
  158. add_motor_raw_6dof(AP_MOTORS_MOT_3, 0, 0, 0, -1.0f, 0, 0, 3);
  159. break;
  160. case SUB_FRAME_SIMPLEROV_4:
  161. case SUB_FRAME_SIMPLEROV_5:
  162. default:
  163. add_motor_raw_6dof(AP_MOTORS_MOT_1, 0, 0, -1.0f, 0, 1.0f, 0, 1);
  164. add_motor_raw_6dof(AP_MOTORS_MOT_2, 0, 0, 1.0f, 0, 1.0f, 0, 2);
  165. add_motor_raw_6dof(AP_MOTORS_MOT_3, 1.0f, 0, 0, -1.0f, 0, 0, 3);
  166. add_motor_raw_6dof(AP_MOTORS_MOT_4, -1.0f, 0, 0, -1.0f, 0, 0, 4);
  167. add_motor_raw_6dof(AP_MOTORS_MOT_5, 0, 0, 0, 0, 0, 1.0f, 5);
  168. break;
  169. }
  170. }
  171. 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)
  172. {
  173. //Parent takes care of enabling output and setting up masks
  174. add_motor_raw(motor_num, roll_fac, pitch_fac, yaw_fac, testing_order);
  175. //These are additional parameters for an ROV
  176. _throttle_factor[motor_num] = throttle_fac;
  177. _forward_factor[motor_num] = forward_fac;
  178. _lateral_factor[motor_num] = lat_fac;
  179. }
  180. // output_min - sends minimum values out to the motors
  181. void AP_Motors6DOF::output_min()
  182. {
  183. int8_t i;
  184. // set limits flags
  185. limit.roll = true;
  186. limit.pitch = true;
  187. limit.yaw = true;
  188. limit.throttle_lower = false;
  189. limit.throttle_upper = false;
  190. // fill the motor_out[] array for HIL use and send minimum value to each motor
  191. // ToDo find a field to store the minimum pwm instead of hard coding 1500
  192. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  193. if (motor_enabled[i]) {
  194. rc_write(i, 1500);
  195. }
  196. }
  197. }
  198. #define ThrustScale 100000
  199. #define hv_min 251
  200. #define hv_max 24100
  201. #define DutyScale 100000
  202. #define MAXDUTY 88000
  203. int32_t AP_Motors6DOF::calc_thrust_to_motor(float thrust_in,int8_t i)
  204. {
  205. int32_t thrust32b = 0;
  206. //int16_t stephv = 500;
  207. thrust32b = (int32_t)(thrust_in* ThrustScale);
  208. int32_t speedref = thrust32b;//last_thrust_Dhot[i];
  209. if (speedref>-10000 && speedref<10000)
  210. {
  211. speedref = 0;
  212. }
  213. return constrain_int32(speedref,-MAXDUTY, MAXDUTY);
  214. }
  215. extern mavlink_motor_speed_t mav_motor_speed;
  216. void AP_Motors6DOF::output_to_Dshot()
  217. {
  218. int8_t i;
  219. int32_t motor_out[AP_MOTORS_MAX_NUM_MOTORS]; // final pwm values sent to the motor
  220. switch (_spool_state) {
  221. case SpoolState::SHUT_DOWN:
  222. // sends minimum values out to the motors
  223. // set motor output based on thrust requests
  224. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  225. if (motor_enabled[i]) {
  226. motor_out[i] = 0;
  227. }
  228. }
  229. break;
  230. case SpoolState::GROUND_IDLE:
  231. // sends output to motors when armed but not flying
  232. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  233. if (motor_enabled[i]) {
  234. motor_out[i] = 0;
  235. }
  236. }
  237. break;
  238. case SpoolState::SPOOLING_UP:
  239. case SpoolState::THROTTLE_UNLIMITED:
  240. case SpoolState::SPOOLING_DOWN:
  241. {
  242. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  243. if (motor_enabled[i]) {
  244. //将油门比例转换成Dshot协议形式,增加了缓启动
  245. motor_out[i] = calc_thrust_to_motor(_thrust_rpyt_out[i],i);
  246. }
  247. }
  248. break;}
  249. }
  250. //const AP_UAVCAN &uavcan = AP::uavcan();//6自由度电机计算出来的PWM
  251. //将上位机转发过来的,转换成Dshot协议并使用CAN 转发
  252. if(mav_motor_speed.motorTest == 1)
  253. {//测试模式上位机直接控制 仅仅控制6个推进器
  254. motor_to_can[0] =(int32_t)(mav_motor_speed.motor1*ThrustScale);//230 才启动
  255. motor_to_can[1] =(int32_t)(mav_motor_speed.motor2*ThrustScale);
  256. motor_to_can[2] = (int32_t)mav_motor_speed.motor3*ThrustScale/2000;
  257. motor_to_can[3] = (int32_t)mav_motor_speed.motor4*ThrustScale/2000;//大于100能动
  258. motor_to_can[4] = (int32_t)mav_motor_speed.motor5*ThrustScale/2000;
  259. motor_to_can[5] = (int32_t)mav_motor_speed.motor6*ThrustScale/2000;
  260. // motor_to_can[6] = mav_motor_speed.motor7;
  261. // motor_to_can[7] = mav_motor_speed.motor8;
  262. }
  263. else
  264. {
  265. motor_to_can[0] = motor_out[0];//赋值给can
  266. motor_to_can[1] = motor_out[1];//赋值给can
  267. motor_to_can[2] = motor_out[2];//赋值给can
  268. motor_to_can[3] = motor_out[3];//赋值给can
  269. motor_to_can[4] = motor_out[4];//赋值给can
  270. motor_to_can[5] = motor_out[5];//赋值给can
  271. //motor_to_can[6] = motor_out[6];//赋值给can
  272. //motor_to_can[7] = motor_out[7];//赋值给can
  273. }
  274. output_motor8_and_motor9();
  275. static int k = 0;
  276. k++;
  277. if(k>400)
  278. {
  279. //gcs().send_text(MAV_SEVERITY_INFO, "motor_out1 %f %f %f \n", (float)motor_to_can[0],(float)motor_to_can[1],(float)motor_to_can[2]);
  280. //gcs().send_text(MAV_SEVERITY_INFO, "motor_out %f %f %d \f", (float)motor_to_can[3],(float)motor_to_can[4], (float)motor_to_can[5]);
  281. k=0;
  282. }
  283. }
  284. int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const
  285. {
  286. return constrain_int16(1500 + thrust_in * 500, _throttle_radio_min, _throttle_radio_max);
  287. }
  288. void AP_Motors6DOF::output_motor8_and_motor9(){
  289. if(mav_motor_speed.motorTest == 1)
  290. {
  291. rc_write(6, calc_thrust_to_pwm((float)mav_motor_speed.Ltrack/260));;//切换成上位机控制 左履带
  292. rc_write(7, calc_thrust_to_pwm((float)mav_motor_speed.Rtrack/260));;//切换成上位机控制 右履带
  293. }else{
  294. rc_write(6, pwm_track[0]);
  295. rc_write(7, pwm_track[1]);
  296. }
  297. static int k = 0;
  298. k++;
  299. if(k>400)
  300. {
  301. gcs().send_text(MAV_SEVERITY_INFO, "motor_speed %d %d \n", pwm_track[0],pwm_track[1]);
  302. gcs().send_text(MAV_SEVERITY_INFO, "motor_speed %d %d %d \n", (int)mav_motor_speed.motorTest,calc_thrust_to_pwm((float)mav_motor_speed.Ltrack/260),calc_thrust_to_pwm((float)mav_motor_speed.Rtrack/260));
  303. k=0;
  304. }
  305. }
  306. void AP_Motors6DOF::output_to_motors()
  307. {
  308. int8_t i;
  309. int16_t motor_out[AP_MOTORS_MAX_NUM_MOTORS]; // final pwm values sent to the motor
  310. switch (_spool_state) {
  311. case SpoolState::SHUT_DOWN:
  312. // sends minimum values out to the motors
  313. // set motor output based on thrust requests
  314. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  315. if (motor_enabled[i]) {
  316. motor_out[i] = 1500;
  317. }
  318. }
  319. break;
  320. case SpoolState::GROUND_IDLE:
  321. // sends output to motors when armed but not flying
  322. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  323. if (motor_enabled[i]) {
  324. motor_out[i] = 1500;
  325. }
  326. }
  327. break;
  328. case SpoolState::SPOOLING_UP:
  329. case SpoolState::THROTTLE_UNLIMITED:
  330. case SpoolState::SPOOLING_DOWN:
  331. // set motor output based on thrust requests
  332. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  333. if (motor_enabled[i]) {
  334. motor_out[i] = calc_thrust_to_pwm(_thrust_rpyt_out[i]);
  335. }
  336. }
  337. break;
  338. }
  339. // send output to each motor
  340. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  341. if (motor_enabled[i]) {
  342. rc_write(i, motor_out[i]);
  343. }
  344. }
  345. }
  346. float AP_Motors6DOF::get_current_limit_max_throttle()
  347. {
  348. return 1.0f;
  349. }
  350. // output_armed - sends commands to the motors
  351. // includes new scaling stability patch
  352. // TODO pull code that is common to output_armed_not_stabilizing into helper functions
  353. // ToDo calculate headroom for rpy to be added for stabilization during full throttle/forward/lateral commands
  354. void AP_Motors6DOF::output_armed_stabilizing()
  355. {
  356. if ((sub_frame_t)_last_frame_class == SUB_FRAME_VECTORED) {
  357. output_armed_stabilizing_vectored();
  358. } else if ((sub_frame_t)_last_frame_class == SUB_FRAME_VECTORED_6DOF) {
  359. output_armed_stabilizing_vectored_6dof();
  360. } else if ((sub_frame_t)_last_frame_class == SUB_FRAME_BLUEROV1){
  361. uint8_t i; // general purpose counter
  362. float roll_thrust; // roll thrust input value, +/- 1.0
  363. float pitch_thrust; // pitch thrust input value, +/- 1.0
  364. float yaw_thrust; // yaw thrust input value, +/- 1.0
  365. float throttle_thrust; // throttle thrust input value, +/- 1.0
  366. float forward_thrust; // forward thrust input value, +/- 1.0
  367. float lateral_thrust; // lateral thrust input value, +/- 1.0
  368. roll_thrust = (_roll_in + _roll_in_ff);
  369. pitch_thrust = (_pitch_in + _pitch_in_ff);
  370. yaw_thrust = (_yaw_in + _yaw_in_ff);
  371. throttle_thrust = get_throttle_bidirectional();
  372. forward_thrust = _forward_in;
  373. lateral_thrust = _lateral_in;
  374. float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
  375. float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
  376. // initialize limits flags
  377. limit.roll = false;
  378. limit.pitch = false;
  379. limit.yaw = false;
  380. limit.throttle_lower = false;
  381. limit.throttle_upper = false;
  382. // sanity check throttle is above zero and below current limited throttle
  383. if (throttle_thrust <= -_throttle_thrust_max) {
  384. throttle_thrust = -_throttle_thrust_max;
  385. limit.throttle_lower = true;
  386. }
  387. if (throttle_thrust >= _throttle_thrust_max) {
  388. throttle_thrust = _throttle_thrust_max;
  389. limit.throttle_upper = true;
  390. }
  391. // calculate roll, pitch and yaw for each motor
  392. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  393. if (motor_enabled[i]) {
  394. rpy_out[i] = roll_thrust * _roll_factor[i] +
  395. pitch_thrust * _pitch_factor[i] +
  396. yaw_thrust * _yaw_factor[i];
  397. }
  398. }
  399. // calculate linear command for each motor
  400. // linear factors should be 0.0 or 1.0 for now
  401. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  402. if (motor_enabled[i]) {
  403. linear_out[i] = throttle_thrust * _throttle_factor[i] +
  404. forward_thrust * _forward_factor[i] +
  405. lateral_thrust * _lateral_factor[i];
  406. }
  407. }
  408. // Calculate final output for each motor
  409. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  410. if (motor_enabled[i]) {
  411. _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]),-1.0f,1.0f);
  412. }
  413. }
  414. }
  415. else{
  416. uint8_t i; // general purpose counter
  417. float roll_thrust; // roll thrust input value, +/- 1.0
  418. float pitch_thrust; // pitch thrust input value, +/- 1.0
  419. float yaw_thrust; // yaw thrust input value, +/- 1.0
  420. float throttle_thrust; // throttle thrust input value, +/- 1.0
  421. float forward_thrust; // forward thrust input value, +/- 1.0
  422. float lateral_thrust; // lateral thrust input value, +/- 1.0
  423. roll_thrust = (_roll_in + _roll_in_ff);
  424. pitch_thrust = (_pitch_in + _pitch_in_ff);
  425. yaw_thrust = (_yaw_in + _yaw_in_ff);
  426. throttle_thrust = get_throttle_bidirectional();
  427. forward_thrust = _forward_in;
  428. lateral_thrust = _lateral_in;
  429. float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
  430. float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
  431. // initialize limits flags
  432. limit.roll = false;
  433. limit.pitch = false;
  434. limit.yaw = false;
  435. limit.throttle_lower = false;
  436. limit.throttle_upper = false;
  437. // sanity check throttle is above zero and below current limited throttle
  438. if (throttle_thrust <= -_throttle_thrust_max) {
  439. throttle_thrust = -_throttle_thrust_max;
  440. limit.throttle_lower = true;
  441. }
  442. if (throttle_thrust >= _throttle_thrust_max) {
  443. throttle_thrust = _throttle_thrust_max;
  444. limit.throttle_upper = true;
  445. }
  446. // calculate roll, pitch and yaw for each motor
  447. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  448. if (motor_enabled[i]) {
  449. rpy_out[i] = roll_thrust * _roll_factor[i] +
  450. pitch_thrust * _pitch_factor[i] +
  451. yaw_thrust * _yaw_factor[i];
  452. }
  453. }
  454. // calculate linear command for each motor
  455. // linear factors should be 0.0 or 1.0 for now
  456. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  457. if (motor_enabled[i]) {
  458. linear_out[i] = throttle_thrust * _throttle_factor[i] +
  459. forward_thrust * _forward_factor[i] +
  460. lateral_thrust * _lateral_factor[i];
  461. }
  462. }
  463. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  464. if (motor_enabled[i]) {
  465. linear_out[i] = throttle_thrust * _throttle_factor[i] +
  466. forward_thrust * _forward_factor[i] +
  467. lateral_thrust * _lateral_factor[i];
  468. }
  469. }
  470. // Calculate final output for each motor
  471. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  472. if (motor_enabled[i]) {
  473. _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]),-1.0f,1.0f);
  474. }
  475. }
  476. }
  477. const AP_BattMonitor &battery = AP::battery();
  478. // Current limiting
  479. float _batt_current;
  480. if (_batt_current_max <= 0.0f || !battery.current_amps(_batt_current)) {
  481. return;
  482. }
  483. float _batt_current_delta = _batt_current - _batt_current_last;
  484. float loop_interval = 1.0f/_loop_rate;
  485. float _current_change_rate = _batt_current_delta / loop_interval;
  486. float predicted_current = _batt_current + (_current_change_rate * loop_interval * 5);
  487. float batt_current_ratio = _batt_current/_batt_current_max;
  488. float predicted_current_ratio = predicted_current/_batt_current_max;
  489. _batt_current_last = _batt_current;
  490. if (predicted_current > _batt_current_max * 1.5f) {
  491. batt_current_ratio = 2.5f;
  492. } else if (_batt_current < _batt_current_max && predicted_current > _batt_current_max) {
  493. batt_current_ratio = predicted_current_ratio;
  494. }
  495. _output_limited += (loop_interval/(loop_interval+_batt_current_time_constant)) * (1 - batt_current_ratio);
  496. _output_limited = constrain_float(_output_limited, 0.0f, 1.0f);
  497. for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  498. if (motor_enabled[i]) {
  499. _thrust_rpyt_out[i] *= _output_limited;
  500. }
  501. }
  502. }
  503. // output_armed - sends commands to the motors
  504. // includes new scaling stability patch
  505. // TODO pull code that is common to output_armed_not_stabilizing into helper functions
  506. // ToDo calculate headroom for rpy to be added for stabilization during full throttle/forward/lateral commands
  507. void AP_Motors6DOF::output_armed_stabilizing_vectored()
  508. {
  509. uint8_t i; // general purpose counter
  510. float roll_thrust; // roll thrust input value, +/- 1.0
  511. float pitch_thrust; // pitch thrust input value, +/- 1.0
  512. float yaw_thrust; // yaw thrust input value, +/- 1.0
  513. float throttle_thrust; // throttle thrust input value, +/- 1.0
  514. float forward_thrust; // forward thrust input value, +/- 1.0
  515. float lateral_thrust; // lateral thrust input value, +/- 1.0
  516. roll_thrust = (_roll_in + _roll_in_ff);
  517. pitch_thrust = (_pitch_in + _pitch_in_ff);
  518. yaw_thrust = (_yaw_in + _yaw_in_ff);
  519. throttle_thrust = get_throttle_bidirectional();
  520. forward_thrust = _forward_in;
  521. lateral_thrust = _lateral_in;
  522. float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
  523. float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
  524. // initialize limits flags
  525. limit.roll= false;
  526. limit.pitch = false;
  527. limit.yaw = false;
  528. limit.throttle_lower = false;
  529. limit.throttle_upper = false;
  530. // sanity check throttle is above zero and below current limited throttle
  531. if (throttle_thrust <= -_throttle_thrust_max) {
  532. throttle_thrust = -_throttle_thrust_max;
  533. limit.throttle_lower = true;
  534. }
  535. if (throttle_thrust >= _throttle_thrust_max) {
  536. throttle_thrust = _throttle_thrust_max;
  537. limit.throttle_upper = true;
  538. }
  539. // calculate roll, pitch and yaw for each motor
  540. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  541. if (motor_enabled[i]) {
  542. rpy_out[i] = roll_thrust * _roll_factor[i] +
  543. pitch_thrust * _pitch_factor[i] +
  544. yaw_thrust * _yaw_factor[i];
  545. }
  546. }
  547. float forward_coupling_limit = 1-_forwardVerticalCouplingFactor*float(fabsf(throttle_thrust));
  548. if (forward_coupling_limit < 0) {
  549. forward_coupling_limit = 0;
  550. }
  551. int8_t forward_coupling_direction[] = {-1,-1,1,1,0,0,0,0,0,0,0,0};
  552. // calculate linear command for each motor
  553. // linear factors should be 0.0 or 1.0 for now
  554. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  555. if (motor_enabled[i]) {
  556. float forward_thrust_limited = forward_thrust;
  557. // The following statements decouple forward/vertical hydrodynamic coupling on
  558. // vectored ROVs. This is done by limiting the maximum output of the "rear" vectored
  559. // thruster (where "rear" depends on direction of travel).
  560. if (!is_zero(forward_thrust_limited)) {
  561. if ((forward_thrust < 0) == (forward_coupling_direction[i] < 0) && forward_coupling_direction[i] != 0) {
  562. forward_thrust_limited = constrain_float(forward_thrust, -forward_coupling_limit, forward_coupling_limit);
  563. }
  564. }
  565. linear_out[i] = throttle_thrust * _throttle_factor[i] +
  566. forward_thrust_limited * _forward_factor[i] +
  567. lateral_thrust * _lateral_factor[i];
  568. }
  569. }
  570. // Calculate final output for each motor
  571. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  572. if (motor_enabled[i]) {
  573. _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]), -1.0f, 1.0f);
  574. }
  575. }
  576. }
  577. // Band Aid fix for motor normalization issues.
  578. // TODO: find a global solution for managing saturation that works for all vehicles
  579. void AP_Motors6DOF::output_armed_stabilizing_vectored_6dof()
  580. {
  581. uint8_t i; // general purpose counter
  582. float roll_thrust; // roll thrust input value, +/- 1.0
  583. float pitch_thrust; // pitch thrust input value, +/- 1.0
  584. float yaw_thrust; // yaw thrust input value, +/- 1.0
  585. float throttle_thrust; // throttle thrust input value, +/- 1.0
  586. float forward_thrust; // forward thrust input value, +/- 1.0
  587. float lateral_thrust; // lateral thrust input value, +/- 1.0
  588. roll_thrust = (_roll_in + _roll_in_ff);
  589. pitch_thrust = (_pitch_in + _pitch_in_ff);
  590. yaw_thrust = (_yaw_in + _yaw_in_ff);
  591. throttle_thrust = get_throttle_bidirectional();
  592. forward_thrust = _forward_in;
  593. lateral_thrust = _lateral_in;
  594. float rpt_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
  595. float yfl_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
  596. float rpt_max;
  597. float yfl_max;
  598. // initialize limits flags
  599. limit.roll = false;
  600. limit.pitch = false;
  601. limit.yaw = false;
  602. limit.throttle_lower = false;
  603. limit.throttle_upper = false;
  604. // sanity check throttle is above zero and below current limited throttle
  605. if (throttle_thrust <= -_throttle_thrust_max) {
  606. throttle_thrust = -_throttle_thrust_max;
  607. limit.throttle_lower = true;
  608. }
  609. if (throttle_thrust >= _throttle_thrust_max) {
  610. throttle_thrust = _throttle_thrust_max;
  611. limit.throttle_upper = true;
  612. }
  613. // calculate roll, pitch and Throttle for each motor (only used by vertical thrusters)
  614. rpt_max = 1; //Initialized to 1 so that normalization will only occur if value is saturated
  615. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  616. if (motor_enabled[i]) {
  617. rpt_out[i] = roll_thrust * _roll_factor[i] +
  618. pitch_thrust * _pitch_factor[i] +
  619. throttle_thrust * _throttle_factor[i];
  620. if (fabsf(rpt_out[i]) > rpt_max) {
  621. rpt_max = fabsf(rpt_out[i]);
  622. }
  623. }
  624. }
  625. // calculate linear/yaw command for each motor (only used for translational thrusters)
  626. // linear factors should be 0.0 or 1.0 for now
  627. yfl_max = 1; //Initialized to 1 so that normalization will only occur if value is saturated
  628. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  629. if (motor_enabled[i]) {
  630. yfl_out[i] = yaw_thrust * _yaw_factor[i] +
  631. forward_thrust * _forward_factor[i] +
  632. lateral_thrust * _lateral_factor[i];
  633. if (fabsf(yfl_out[i]) > yfl_max) {
  634. yfl_max = fabsf(yfl_out[i]);
  635. }
  636. }
  637. }
  638. // Calculate final output for each motor and normalize if necessary
  639. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  640. if (motor_enabled[i]) {
  641. _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpt_out[i]/rpt_max + yfl_out[i]/yfl_max),-1.0f,1.0f);
  642. }
  643. }
  644. }
  645. Vector3f AP_Motors6DOF::get_motor_angular_factors(int motor_number) {
  646. if (motor_number < 0 || motor_number >= AP_MOTORS_MAX_NUM_MOTORS) {
  647. return Vector3f(0,0,0);
  648. }
  649. return Vector3f(_roll_factor[motor_number], _pitch_factor[motor_number], _yaw_factor[motor_number]);
  650. }
  651. bool AP_Motors6DOF::motor_is_enabled(int motor_number) {
  652. if (motor_number < 0 || motor_number >= AP_MOTORS_MAX_NUM_MOTORS) {
  653. return false;
  654. }
  655. return motor_enabled[motor_number];
  656. }
  657. bool AP_Motors6DOF::set_reversed(int motor_number, bool reversed) {
  658. if (motor_number < 0 || motor_number >= AP_MOTORS_MAX_NUM_MOTORS) {
  659. return false;
  660. }
  661. if (reversed) {
  662. _motor_reverse[motor_number].set_and_save(-1);
  663. } else {
  664. _motor_reverse[motor_number].set_and_save(1);
  665. }
  666. return true;
  667. }
  668. //--------------wangdan--------
  669. AP_Motors6DOF *AP_Motors6DOF::_singleton;
  670. namespace AP {
  671. AP_Motors6DOF &motors6dof()
  672. {
  673. return *AP_Motors6DOF::get_singleton();
  674. }
  675. };