AP_Motors6DOF.cpp 32 KB

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