AP_Motors6DOF.cpp 33 KB

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