AP_Motors6DOF.cpp 35 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865
  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 1000
  199. #define hv_min 251
  200. #define hv_max 1850
  201. int16_t AP_Motors6DOF::calc_thrust_to_HV(float thrust_in,int8_t i)
  202. {
  203. int16_t thrust = 0;
  204. //float ratio= 0.02;//阶跃百分比
  205. // int16_t step = 4;//4;//步长 0加到1024需要320毫秒
  206. // int16_t step_thrust = 4;//4;//退出缓启动的条件
  207. int16_t stephv = 20;
  208. thrust = (int16_t)(thrust_in* ThrustScale);
  209. if(i<2)
  210. {
  211. last_thrust_Dhot[i] = thrust;
  212. return constrain_int16(last_thrust_Dhot[i],-1000, 1000);
  213. //输入比例与上次比例差 >ration
  214. /* if (fabsf(thrust_in - last_thrust_in[i]) > ratio)
  215. {//缓加缓减
  216. if (thrust >= last_thrust_Dhot[i] + step)
  217. {//新的Dshot >当前的Dshot + 步长
  218. last_thrust_Dhot[i] += step;
  219. }
  220. else if(thrust <= last_thrust_Dhot[i] -step)
  221. {//新的Dshot < 当前的Dshot -步长
  222. last_thrust_Dhot[i] -= step;
  223. }
  224. if (thrust>=last_thrust_Dhot[i] - step_thrust && thrust<=last_thrust_Dhot[i] + step_thrust){
  225. last_thrust_in[i] = thrust_in;
  226. last_thrust_Dhot[i] = thrust;
  227. }
  228. if ((last_thrust_Dhot[i]< step && last_thrust_Dhot[i]> -step) && thrust == 0)
  229. {
  230. last_thrust_Dhot[i] =0;
  231. }
  232. }
  233. else{
  234. //比例之差<ration 直接赋值
  235. last_thrust_Dhot[i] = thrust;
  236. last_thrust_in[i] = thrust_in;
  237. }
  238. return constrain_int16(last_thrust_Dhot[i],-1000, 1000);*/
  239. }
  240. else{
  241. if (thrust>=last_thrust_Dhot[i] - stephv && thrust<=last_thrust_Dhot[i] + stephv){
  242. last_thrust_Dhot[i] = thrust;
  243. }else if (thrust >= last_thrust_Dhot[i] + stephv)
  244. {//新的Dshot >当前的Dshot + 步长
  245. last_thrust_Dhot[i] += stephv;
  246. }
  247. else if(thrust <= last_thrust_Dhot[i] -stephv)
  248. {//新的Dshot < 当前的Dshot -步长
  249. last_thrust_Dhot[i] -= stephv;
  250. }
  251. if (last_thrust_Dhot[i]< stephv && last_thrust_Dhot[i]> -stephv)
  252. {
  253. last_thrust_Dhot[i] =0;
  254. }
  255. static int k = 0;
  256. k++;
  257. if(k>400)
  258. {
  259. //gcs().send_text(MAV_SEVERITY_INFO, "_thrust_rpyt_out %d %d ,%d \n",(int)last_thrust_Dhot[2],(int)last_thrust_Dhot[3],(int)last_thrust_Dhot[4]);
  260. }
  261. int16_t speedref = (int16_t)((int32_t)last_thrust_Dhot[i]*hv_max/1000);
  262. return constrain_int16(speedref,-hv_max, hv_max);
  263. }
  264. }
  265. int16_t AP_Motors6DOF::calc_thrust_to_Dshot(float thrust_in,int8_t i)
  266. {
  267. int16_t thrust = 0;
  268. float ratio= 0.02;//阶跃百分比
  269. int16_t step = 8;//4;//步长 0加到1024需要320毫秒
  270. int16_t step_thrust = 8;//4;//退出缓启动的条件
  271. thrust = (int16_t)(thrust_in* ThrustScale);
  272. //输入比例与上次比例差 >ration
  273. if (fabsf(thrust_in - last_thrust_in[i]) > ratio)
  274. {//缓加缓减
  275. if (thrust >= last_thrust_Dhot[i] + step)
  276. {//新的Dshot >当前的Dshot + 步长
  277. last_thrust_Dhot[i] += step;
  278. }
  279. else if(thrust <= last_thrust_Dhot[i] -step)
  280. {//新的Dshot < 当前的Dshot -步长
  281. last_thrust_Dhot[i] -= step;
  282. }
  283. if (thrust>=last_thrust_Dhot[i] - step_thrust && thrust<=last_thrust_Dhot[i] + step_thrust){
  284. last_thrust_in[i] = thrust_in;
  285. last_thrust_Dhot[i] = thrust;
  286. }
  287. if ((last_thrust_Dhot[i]< step && last_thrust_Dhot[i]> -step) && thrust == 0)
  288. {
  289. last_thrust_Dhot[i] =0;
  290. }
  291. }
  292. else{
  293. //比例之差<ration 直接赋值
  294. last_thrust_Dhot[i] = thrust;
  295. last_thrust_in[i] = thrust_in;
  296. }
  297. if (i<2)
  298. {
  299. return constrain_int16(last_thrust_Dhot[i],-1000, 1000);
  300. }
  301. else{
  302. return constrain_int16(last_thrust_Dhot[i],-910, 910);//ThrustScale -770, 810
  303. }
  304. }
  305. extern mavlink_motor_speed_t mav_motor_speed;
  306. void AP_Motors6DOF::output_to_Dshot()
  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] = 0;
  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] = 0;
  325. }
  326. }
  327. break;
  328. case SpoolState::SPOOLING_UP:
  329. case SpoolState::THROTTLE_UNLIMITED:
  330. case SpoolState::SPOOLING_DOWN:
  331. {
  332. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  333. if (motor_enabled[i]) {
  334. //将油门比例转换成Dshot协议形式,增加了缓启动
  335. //motor_out[i] = calc_thrust_to_Dshot(_thrust_rpyt_out[i],i);
  336. motor_out[i] = calc_thrust_to_HV(_thrust_rpyt_out[i],i);
  337. }
  338. }
  339. break;}
  340. }
  341. //const AP_UAVCAN &uavcan = AP::uavcan();//6自由度电机计算出来的PWM
  342. //将上位机转发过来的,转换成Dshot协议并使用CAN 转发
  343. if(mav_motor_speed.motorTest == 1)
  344. {//测试模式上位机直接控制 仅仅控制6个推进器
  345. motor_to_can[0] = mav_motor_speed.motor1*1000;
  346. motor_to_can[1] = mav_motor_speed.motor2*1000;
  347. motor_to_can[2] = mav_motor_speed.motor3;
  348. motor_to_can[3] = mav_motor_speed.motor4;
  349. motor_to_can[4] = mav_motor_speed.motor5;
  350. motor_to_can[5] = mav_motor_speed.motor6;
  351. motor_to_can[6] = mav_motor_speed.motor7;
  352. motor_to_can[7] = mav_motor_speed.motor8;
  353. }
  354. else
  355. {
  356. motor_to_can[0] = motor_out[0];//赋值给can
  357. motor_to_can[1] = motor_out[1];//赋值给can
  358. motor_to_can[2] = motor_out[2];//赋值给can
  359. motor_to_can[3] = motor_out[3];//赋值给can
  360. motor_to_can[4] = motor_out[4];//赋值给can
  361. motor_to_can[5] = motor_out[5];//赋值给can
  362. motor_to_can[6] = motor_out[6];//赋值给can
  363. motor_to_can[7] = motor_out[7];//赋值给can
  364. }
  365. }
  366. int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const
  367. {
  368. return constrain_int16(1500 + thrust_in * 400, _throttle_radio_min, _throttle_radio_max);
  369. }
  370. void AP_Motors6DOF::output_to_motors()
  371. {
  372. int8_t i;
  373. int16_t motor_out[AP_MOTORS_MAX_NUM_MOTORS]; // final pwm values sent to the motor
  374. switch (_spool_state) {
  375. case SpoolState::SHUT_DOWN:
  376. // sends minimum values out to the motors
  377. // set motor output based on thrust requests
  378. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  379. if (motor_enabled[i]) {
  380. motor_out[i] = 1500;
  381. }
  382. }
  383. break;
  384. case SpoolState::GROUND_IDLE:
  385. // sends output to motors when armed but not flying
  386. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  387. if (motor_enabled[i]) {
  388. motor_out[i] = 1500;
  389. }
  390. }
  391. break;
  392. case SpoolState::SPOOLING_UP:
  393. case SpoolState::THROTTLE_UNLIMITED:
  394. case SpoolState::SPOOLING_DOWN:
  395. // set motor output based on thrust requests
  396. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  397. if (motor_enabled[i]) {
  398. motor_out[i] = calc_thrust_to_pwm(_thrust_rpyt_out[i]);
  399. }
  400. }
  401. break;
  402. }
  403. // send output to each motor
  404. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  405. if (motor_enabled[i]) {
  406. rc_write(i, motor_out[i]);
  407. }
  408. }
  409. }
  410. float AP_Motors6DOF::get_current_limit_max_throttle()
  411. {
  412. return 1.0f;
  413. }
  414. // output_armed - sends commands to the motors
  415. // includes new scaling stability patch
  416. // TODO pull code that is common to output_armed_not_stabilizing into helper functions
  417. // ToDo calculate headroom for rpy to be added for stabilization during full throttle/forward/lateral commands
  418. void AP_Motors6DOF::output_armed_stabilizing()
  419. {
  420. if ((sub_frame_t)_last_frame_class == SUB_FRAME_VECTORED) {
  421. output_armed_stabilizing_vectored();
  422. } else if ((sub_frame_t)_last_frame_class == SUB_FRAME_VECTORED_6DOF) {
  423. output_armed_stabilizing_vectored_6dof();
  424. } else if ((sub_frame_t)_last_frame_class == SUB_FRAME_BLUEROV1){
  425. uint8_t i; // general purpose counter
  426. float roll_thrust; // roll thrust input value, +/- 1.0
  427. float pitch_thrust; // pitch thrust input value, +/- 1.0
  428. float yaw_thrust; // yaw thrust input value, +/- 1.0
  429. float throttle_thrust; // throttle thrust input value, +/- 1.0
  430. float forward_thrust; // forward thrust input value, +/- 1.0
  431. float lateral_thrust; // lateral thrust input value, +/- 1.0
  432. roll_thrust = (_roll_in + _roll_in_ff);
  433. pitch_thrust = (_pitch_in + _pitch_in_ff);
  434. yaw_thrust = (_yaw_in + _yaw_in_ff);
  435. throttle_thrust = get_throttle_bidirectional();
  436. forward_thrust = _forward_in;
  437. lateral_thrust = _lateral_in;
  438. float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
  439. float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
  440. // initialize limits flags
  441. limit.roll = false;
  442. limit.pitch = false;
  443. limit.yaw = false;
  444. limit.throttle_lower = false;
  445. limit.throttle_upper = false;
  446. // sanity check throttle is above zero and below current limited throttle
  447. if (throttle_thrust <= -_throttle_thrust_max) {
  448. throttle_thrust = -_throttle_thrust_max;
  449. limit.throttle_lower = true;
  450. }
  451. if (throttle_thrust >= _throttle_thrust_max) {
  452. throttle_thrust = _throttle_thrust_max;
  453. limit.throttle_upper = true;
  454. }
  455. // calculate roll, pitch and yaw for each motor
  456. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  457. if (motor_enabled[i]) {
  458. rpy_out[i] = roll_thrust * _roll_factor[i] +
  459. pitch_thrust * _pitch_factor[i] +
  460. yaw_thrust * _yaw_factor[i];
  461. }
  462. }
  463. // calculate linear command for each motor
  464. // linear factors should be 0.0 or 1.0 for now
  465. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  466. if (motor_enabled[i]) {
  467. linear_out[i] = throttle_thrust * _throttle_factor[i] +
  468. forward_thrust * _forward_factor[i] +
  469. lateral_thrust * _lateral_factor[i];
  470. }
  471. }
  472. // Calculate final output for each motor
  473. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  474. if (motor_enabled[i]) {
  475. _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]),-1.0f,1.0f);
  476. }
  477. }
  478. }
  479. else{
  480. uint8_t i; // general purpose counter
  481. float roll_thrust; // roll thrust input value, +/- 1.0
  482. float pitch_thrust; // pitch thrust input value, +/- 1.0
  483. float yaw_thrust; // yaw thrust input value, +/- 1.0
  484. float throttle_thrust; // throttle thrust input value, +/- 1.0
  485. float forward_thrust; // forward thrust input value, +/- 1.0
  486. float lateral_thrust; // lateral thrust input value, +/- 1.0
  487. roll_thrust = (_roll_in + _roll_in_ff);
  488. pitch_thrust = (_pitch_in + _pitch_in_ff);
  489. yaw_thrust = (_yaw_in + _yaw_in_ff);
  490. throttle_thrust = get_throttle_bidirectional();
  491. forward_thrust = _forward_in;
  492. lateral_thrust = _lateral_in;
  493. float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
  494. float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
  495. // initialize limits flags
  496. limit.roll = false;
  497. limit.pitch = false;
  498. limit.yaw = false;
  499. limit.throttle_lower = false;
  500. limit.throttle_upper = false;
  501. // sanity check throttle is above zero and below current limited throttle
  502. if (throttle_thrust <= -_throttle_thrust_max) {
  503. throttle_thrust = -_throttle_thrust_max;
  504. limit.throttle_lower = true;
  505. }
  506. if (throttle_thrust >= _throttle_thrust_max) {
  507. throttle_thrust = _throttle_thrust_max;
  508. limit.throttle_upper = true;
  509. }
  510. // calculate roll, pitch and yaw for each motor
  511. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  512. if (motor_enabled[i]) {
  513. rpy_out[i] = roll_thrust * _roll_factor[i] +
  514. pitch_thrust * _pitch_factor[i] +
  515. yaw_thrust * _yaw_factor[i];
  516. }
  517. }
  518. // calculate linear command for each motor
  519. // linear factors should be 0.0 or 1.0 for now
  520. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  521. if (motor_enabled[i]) {
  522. linear_out[i] = throttle_thrust * _throttle_factor[i] +
  523. forward_thrust * _forward_factor[i] +
  524. lateral_thrust * _lateral_factor[i];
  525. }
  526. }
  527. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  528. if (motor_enabled[i]) {
  529. linear_out[i] = throttle_thrust * _throttle_factor[i] +
  530. forward_thrust * _forward_factor[i] +
  531. lateral_thrust * _lateral_factor[i];
  532. }
  533. }
  534. // Calculate final output for each motor
  535. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  536. if (motor_enabled[i]) {
  537. _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]),-1.0f,1.0f);
  538. }
  539. }
  540. }
  541. const AP_BattMonitor &battery = AP::battery();
  542. // Current limiting
  543. float _batt_current;
  544. if (_batt_current_max <= 0.0f || !battery.current_amps(_batt_current)) {
  545. return;
  546. }
  547. float _batt_current_delta = _batt_current - _batt_current_last;
  548. float loop_interval = 1.0f/_loop_rate;
  549. float _current_change_rate = _batt_current_delta / loop_interval;
  550. float predicted_current = _batt_current + (_current_change_rate * loop_interval * 5);
  551. float batt_current_ratio = _batt_current/_batt_current_max;
  552. float predicted_current_ratio = predicted_current/_batt_current_max;
  553. _batt_current_last = _batt_current;
  554. if (predicted_current > _batt_current_max * 1.5f) {
  555. batt_current_ratio = 2.5f;
  556. } else if (_batt_current < _batt_current_max && predicted_current > _batt_current_max) {
  557. batt_current_ratio = predicted_current_ratio;
  558. }
  559. _output_limited += (loop_interval/(loop_interval+_batt_current_time_constant)) * (1 - batt_current_ratio);
  560. _output_limited = constrain_float(_output_limited, 0.0f, 1.0f);
  561. for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
  562. if (motor_enabled[i]) {
  563. _thrust_rpyt_out[i] *= _output_limited;
  564. }
  565. }
  566. }
  567. // output_armed - sends commands to the motors
  568. // includes new scaling stability patch
  569. // TODO pull code that is common to output_armed_not_stabilizing into helper functions
  570. // ToDo calculate headroom for rpy to be added for stabilization during full throttle/forward/lateral commands
  571. void AP_Motors6DOF::output_armed_stabilizing_vectored()
  572. {
  573. uint8_t i; // general purpose counter
  574. float roll_thrust; // roll thrust input value, +/- 1.0
  575. float pitch_thrust; // pitch thrust input value, +/- 1.0
  576. float yaw_thrust; // yaw thrust input value, +/- 1.0
  577. float throttle_thrust; // throttle thrust input value, +/- 1.0
  578. float forward_thrust; // forward thrust input value, +/- 1.0
  579. float lateral_thrust; // lateral thrust input value, +/- 1.0
  580. roll_thrust = (_roll_in + _roll_in_ff);
  581. pitch_thrust = (_pitch_in + _pitch_in_ff);
  582. yaw_thrust = (_yaw_in + _yaw_in_ff);
  583. throttle_thrust = get_throttle_bidirectional();
  584. forward_thrust = _forward_in;
  585. lateral_thrust = _lateral_in;
  586. float rpy_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
  587. float linear_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
  588. // initialize limits flags
  589. limit.roll= false;
  590. limit.pitch = false;
  591. limit.yaw = false;
  592. limit.throttle_lower = false;
  593. limit.throttle_upper = false;
  594. // sanity check throttle is above zero and below current limited throttle
  595. if (throttle_thrust <= -_throttle_thrust_max) {
  596. throttle_thrust = -_throttle_thrust_max;
  597. limit.throttle_lower = true;
  598. }
  599. if (throttle_thrust >= _throttle_thrust_max) {
  600. throttle_thrust = _throttle_thrust_max;
  601. limit.throttle_upper = true;
  602. }
  603. // calculate roll, pitch and yaw for each motor
  604. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  605. if (motor_enabled[i]) {
  606. rpy_out[i] = roll_thrust * _roll_factor[i] +
  607. pitch_thrust * _pitch_factor[i] +
  608. yaw_thrust * _yaw_factor[i];
  609. }
  610. }
  611. float forward_coupling_limit = 1-_forwardVerticalCouplingFactor*float(fabsf(throttle_thrust));
  612. if (forward_coupling_limit < 0) {
  613. forward_coupling_limit = 0;
  614. }
  615. int8_t forward_coupling_direction[] = {-1,-1,1,1,0,0,0,0,0,0,0,0};
  616. // calculate linear command for each motor
  617. // linear factors should be 0.0 or 1.0 for now
  618. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  619. if (motor_enabled[i]) {
  620. float forward_thrust_limited = forward_thrust;
  621. // The following statements decouple forward/vertical hydrodynamic coupling on
  622. // vectored ROVs. This is done by limiting the maximum output of the "rear" vectored
  623. // thruster (where "rear" depends on direction of travel).
  624. if (!is_zero(forward_thrust_limited)) {
  625. if ((forward_thrust < 0) == (forward_coupling_direction[i] < 0) && forward_coupling_direction[i] != 0) {
  626. forward_thrust_limited = constrain_float(forward_thrust, -forward_coupling_limit, forward_coupling_limit);
  627. }
  628. }
  629. linear_out[i] = throttle_thrust * _throttle_factor[i] +
  630. forward_thrust_limited * _forward_factor[i] +
  631. lateral_thrust * _lateral_factor[i];
  632. }
  633. }
  634. // Calculate final output for each motor
  635. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  636. if (motor_enabled[i]) {
  637. _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpy_out[i] + linear_out[i]), -1.0f, 1.0f);
  638. }
  639. }
  640. }
  641. // Band Aid fix for motor normalization issues.
  642. // TODO: find a global solution for managing saturation that works for all vehicles
  643. void AP_Motors6DOF::output_armed_stabilizing_vectored_6dof()
  644. {
  645. uint8_t i; // general purpose counter
  646. float roll_thrust; // roll thrust input value, +/- 1.0
  647. float pitch_thrust; // pitch thrust input value, +/- 1.0
  648. float yaw_thrust; // yaw thrust input value, +/- 1.0
  649. float throttle_thrust; // throttle thrust input value, +/- 1.0
  650. float forward_thrust; // forward thrust input value, +/- 1.0
  651. float lateral_thrust; // lateral thrust input value, +/- 1.0
  652. roll_thrust = (_roll_in + _roll_in_ff);
  653. pitch_thrust = (_pitch_in + _pitch_in_ff);
  654. yaw_thrust = (_yaw_in + _yaw_in_ff);
  655. throttle_thrust = get_throttle_bidirectional();
  656. forward_thrust = _forward_in;
  657. lateral_thrust = _lateral_in;
  658. float rpt_out[AP_MOTORS_MAX_NUM_MOTORS]; // buffer so we don't have to multiply coefficients multiple times.
  659. float yfl_out[AP_MOTORS_MAX_NUM_MOTORS]; // 3 linear DOF mix for each motor
  660. float rpt_max;
  661. float yfl_max;
  662. // initialize limits flags
  663. limit.roll = false;
  664. limit.pitch = false;
  665. limit.yaw = false;
  666. limit.throttle_lower = false;
  667. limit.throttle_upper = false;
  668. // sanity check throttle is above zero and below current limited throttle
  669. if (throttle_thrust <= -_throttle_thrust_max) {
  670. throttle_thrust = -_throttle_thrust_max;
  671. limit.throttle_lower = true;
  672. }
  673. if (throttle_thrust >= _throttle_thrust_max) {
  674. throttle_thrust = _throttle_thrust_max;
  675. limit.throttle_upper = true;
  676. }
  677. // calculate roll, pitch and Throttle for each motor (only used by vertical thrusters)
  678. rpt_max = 1; //Initialized to 1 so that normalization will only occur if value is saturated
  679. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  680. if (motor_enabled[i]) {
  681. rpt_out[i] = roll_thrust * _roll_factor[i] +
  682. pitch_thrust * _pitch_factor[i] +
  683. throttle_thrust * _throttle_factor[i];
  684. if (fabsf(rpt_out[i]) > rpt_max) {
  685. rpt_max = fabsf(rpt_out[i]);
  686. }
  687. }
  688. }
  689. // calculate linear/yaw command for each motor (only used for translational thrusters)
  690. // linear factors should be 0.0 or 1.0 for now
  691. yfl_max = 1; //Initialized to 1 so that normalization will only occur if value is saturated
  692. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  693. if (motor_enabled[i]) {
  694. yfl_out[i] = yaw_thrust * _yaw_factor[i] +
  695. forward_thrust * _forward_factor[i] +
  696. lateral_thrust * _lateral_factor[i];
  697. if (fabsf(yfl_out[i]) > yfl_max) {
  698. yfl_max = fabsf(yfl_out[i]);
  699. }
  700. }
  701. }
  702. // Calculate final output for each motor and normalize if necessary
  703. for (i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  704. if (motor_enabled[i]) {
  705. _thrust_rpyt_out[i] = constrain_float(_motor_reverse[i]*(rpt_out[i]/rpt_max + yfl_out[i]/yfl_max),-1.0f,1.0f);
  706. }
  707. }
  708. }
  709. Vector3f AP_Motors6DOF::get_motor_angular_factors(int motor_number) {
  710. if (motor_number < 0 || motor_number >= AP_MOTORS_MAX_NUM_MOTORS) {
  711. return Vector3f(0,0,0);
  712. }
  713. return Vector3f(_roll_factor[motor_number], _pitch_factor[motor_number], _yaw_factor[motor_number]);
  714. }
  715. bool AP_Motors6DOF::motor_is_enabled(int motor_number) {
  716. if (motor_number < 0 || motor_number >= AP_MOTORS_MAX_NUM_MOTORS) {
  717. return false;
  718. }
  719. return motor_enabled[motor_number];
  720. }
  721. bool AP_Motors6DOF::set_reversed(int motor_number, bool reversed) {
  722. if (motor_number < 0 || motor_number >= AP_MOTORS_MAX_NUM_MOTORS) {
  723. return false;
  724. }
  725. if (reversed) {
  726. _motor_reverse[motor_number].set_and_save(-1);
  727. } else {
  728. _motor_reverse[motor_number].set_and_save(1);
  729. }
  730. return true;
  731. }
  732. //--------------wangdan--------
  733. AP_Motors6DOF *AP_Motors6DOF::_singleton;
  734. namespace AP {
  735. AP_Motors6DOF &motors6dof()
  736. {
  737. return *AP_Motors6DOF::get_singleton();
  738. }
  739. };