AP_Motors6DOF.cpp 35 KB

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