AP_Motors6DOF.cpp 32 KB

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