control_clean.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659
  1. #include "Sub.h"
  2. //目标姿态
  3. float maxspeed = 51.0;
  4. int16_t minspeed = 31;
  5. int16_t maxerrorspeed = 31;
  6. //float turnspeed = maxspeed - maxerror_f;
  7. Quaternion _attitude_target_quat;
  8. extern mavlink_rov_state_monitoring_t rov_message;
  9. bool Sub::clean_init()
  10. {
  11. pos_control.set_alt_target(0);
  12. hal.rcout->write(10,1500);//毛刷停止
  13. motor1_speed_target =startval;//1500;
  14. motor2_speed_target =startval;//
  15. float _head =0;
  16. _head = (float)ahrs.yaw_sensor/100;
  17. //track
  18. track_head_gd = constrain_float(_head,0.0,360.0);
  19. last_roll = 0;
  20. last_pitch = 0;
  21. last_yaw = ahrs.yaw_sensor;
  22. //记录进入stable的YAW的当前值
  23. yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  24. last_input_ms = AP_HAL::millis();
  25. track_reset();
  26. return true;
  27. }
  28. void Sub::track_reset(void){
  29. autoclean_command = FALSE;//自动刷网
  30. clean_bottom_command =FALSE;
  31. clean_bottom_flag = FALSE;
  32. autoclean_flag = FALSE;
  33. handclean = TRUE;
  34. turn_angle = 16.0;//20210622
  35. //----------------------
  36. track_motor_arm = 1;//履带停机标志
  37. //履带的初始方向位置 默认为水平方向的yaw值
  38. track_head_gd = 0;
  39. //履带停
  40. motor1_speed_target =startval;
  41. motor2_speed_target =startval;
  42. clean_mode =0;
  43. attitude_control.relax_attitude_controllers();//外置九轴YAW更新四元数
  44. last_roll = 0;
  45. last_pitch = 0;
  46. last_yaw = ahrs.yaw_sensor;
  47. yaw_press = (int16_t)ahrs.yaw_sensor/100;//记住方位
  48. ahrs.get_quat_body_to_ned(_attitude_target_quat);
  49. }
  50. extern mavlink_data64_t rov_message2;
  51. extern mavlink_rov_control_t rov_control;
  52. void Sub::clean_run()
  53. {
  54. // if not armed set throttle to zero and exit immediately
  55. if (!motors.armed()) {
  56. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  57. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  58. attitude_control.relax_attitude_controllers();//---------------------20210623
  59. PressLevel_f =5.0;//压力为0
  60. PressLevel = no;
  61. //-------------
  62. track_reset();
  63. return;
  64. }
  65. //推进器-------------------
  66. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  67. motors.set_throttle(1.0-(float)PressLevel_f*0.1);//压力等级
  68. rov_message.pressure_level = int(PressLevel);
  69. motors.set_forward(0.0); //右侧摇杆,前推为+,后推为- 右履带的前进后退
  70. motors.set_lateral(0.0);//右侧摇杆 左推-,右推+
  71. motors.set_yaw(0.0);//左侧摇杆左推- 右推+
  72. motors.set_roll(0.0);
  73. motors.set_pitch(0.0);
  74. //motors.set_roll(channel_lateral->norm_input());//(channel_roll->norm_input());//左右移动改为roll
  75. //motors.set_pitch((0.5-channel_throttle->norm_input())*2);//(channel_pitch->norm_input());//上升下潜改为pitch
  76. motors.set_yaw(0.0);
  77. static int j = 0;
  78. j++;
  79. if(j>800)
  80. {
  81. // gcs().send_text(MAV_SEVERITY_INFO, " track_limit %f\n",(float)rov_control.track_limit);
  82. j=0;
  83. }
  84. maxspeed = (float)rov_control.track_limit;
  85. if (maxspeed<31.0)
  86. {
  87. maxspeed = 31.0;
  88. }
  89. if(maxspeed>91.0)
  90. {
  91. maxspeed = 91.0;
  92. }
  93. //turnspeed = maxspeed - maxerror_f;
  94. autoclean_flag_chose();//自动洗网的状态切换
  95. clean_net_joystick();//默认手动洗网
  96. clean_sidenet_auto();//按一下自动洗网使能,再按一下失能,回到手动洗网状态
  97. }
  98. void Sub::autoclean_flag_chose(void){
  99. if (autoclean_command == TRUE)
  100. {
  101. autoclean_flag = TRUE;
  102. }
  103. else{
  104. autoclean_flag = FALSE;
  105. }
  106. if (autoclean_flag == FALSE && clean_bottom_flag == FALSE)
  107. {
  108. handclean = TRUE;
  109. ahrs.get_quat_body_to_ned(_attitude_target_quat);
  110. }
  111. else{
  112. handclean = FALSE;
  113. }
  114. }
  115. int16_t maxspeed_up=50;
  116. void Sub::clean_net_joystick(void)
  117. {
  118. //左右履带和左右电机 左右反了
  119. float left =startval;
  120. float _turn =startval;
  121. int16_t motors1 =startval;
  122. int16_t motors2 =startval;
  123. minspeed =SRV_Channels::srv_channel(11)->get_output_min()/100;// 暂时用来做最小速度 -----最小水深
  124. maxerrorspeed =SRV_Channels::srv_channel(11)->get_output_max()/100;//两个履带最大差速 ----------最深距离 厘米
  125. maxspeed_up = SRV_Channels::srv_channel(15)->get_trim()/100;
  126. if(maxspeed_up<maxspeed)
  127. {
  128. maxspeed = maxspeed_up;
  129. }
  130. if(handclean == TRUE ){
  131. //计算电机的 手动转速
  132. /*left = Constrate1(channel_forward->norm_input());// 新仓 - //履带右摇杆 -1.0~1.0
  133. _turn = Constrate1(channel_yaw->norm_input());//新仓 - //转向 右+左-,+右转 左履带增,-左转 右lvdai+
  134. //motors1 = (int16_t)((left*Speedmax_hand_f -_turn*maxerror_f));//右履带
  135. //motors2 = (int16_t)((left*Speedmax_hand_f +_turn*maxerror_f));//左履带
  136. //motors1 = (int16_t)((left*maxspeed -_turn*maxerror_f));//右履带 注意上位机传过来的是左1 右2 这里变成了右1左2 这需要今后改
  137. //motors2 = (int16_t)((left*maxspeed +_turn*maxerror_f));//左履带*/
  138. left = Constrate1(channel_forward->norm_input());//
  139. _turn = Constrate1(channel_yaw->norm_input());//转向 右+左-,+右转 左履带增,-左转 右lvdai+
  140. motors1 = (int16_t)((left*maxspeed +_turn*maxerrorspeed));//右履带 //第一台高压电机
  141. motors2 = (int16_t)((left*maxspeed -_turn*maxerrorspeed));//左履带
  142. if(_turn>0.1)
  143. {
  144. _turn =1.0;
  145. rov_message.turn = 3;
  146. }else if(_turn<-0.1){
  147. _turn =-1.0;
  148. rov_message.turn = 2;
  149. }else{
  150. rov_message.turn = 1;
  151. }
  152. if (left>0.1)
  153. {
  154. //前进
  155. if (motors1<minspeed)
  156. {
  157. motors1 =minspeed;
  158. }
  159. if (motors2<minspeed)
  160. {
  161. motors2 =minspeed;
  162. }
  163. }
  164. else if (left<-0.1)
  165. {
  166. //后退
  167. if (motors1>-minspeed)
  168. {
  169. motors1 =-minspeed;
  170. }
  171. if (motors2>-minspeed)
  172. {
  173. motors2 =-minspeed;
  174. }
  175. }
  176. else{
  177. if(fabsf(_turn)<0.1)
  178. {
  179. motors1 =0;
  180. motors2 =0;
  181. }
  182. else{
  183. //motors1 = -_turn*maxerror_f;//
  184. //motors2 = _turn*maxerror_f;//
  185. motors1 = _turn*maxerrorspeed;////第一台高压电机
  186. motors2 = -_turn*maxerrorspeed;//
  187. }
  188. }
  189. //motors1=constrain_int16(motors1,-(Speedmax_hand+maxerror),(int16_t)(Speedmax_hand+maxerror));
  190. //motors2=constrain_int16(motors2,-(Speedmax_hand+maxerror),(int16_t)(Speedmax_hand+maxerror));//做履带
  191. //motors1=constrain_int16(motors1,-((int16_t)maxspeed+maxerror),(int16_t)((int16_t)maxspeed+maxerror));
  192. //motors2=constrain_int16(motors2,-((int16_t)maxspeed+maxerror),(int16_t)((int16_t)maxspeed+maxerror));//做履带
  193. //motors1=constrain_int16(motors1,-((int16_t)(maxspeed)/2),(int16_t)((int16_t)maxspeed+maxerror));
  194. //motors2=constrain_int16(motors2,-((int16_t)(maxspeed)/2),(int16_t)((int16_t)maxspeed+maxerror));//做履带
  195. int16_t minspeedlimit =(int16_t)(maxspeed*0.5);
  196. motors1=constrain_int16(motors1,-(int16_t)minspeedlimit,(int16_t)((int16_t)maxspeed+maxerror));
  197. motors2=constrain_int16(motors2,-(int16_t)minspeedlimit,(int16_t)((int16_t)maxspeed+maxerror));//做履带
  198. static int f = 0;
  199. f++;
  200. if(f>800)
  201. {
  202. gcs().send_text(MAV_SEVERITY_INFO, "minspeed %d %d,%d,%d",(int)minspeed,(int)maxerrorspeed,(int)maxspeed,(int)minspeedlimit);
  203. f=0;
  204. }
  205. //左摇杆前进后退的指示---------------
  206. if(left>0.1){
  207. track_motor_arm = 2;//前进
  208. }
  209. else if(left<-0.1){
  210. track_motor_arm = 0;
  211. }
  212. else{
  213. track_motor_arm=1;
  214. }
  215. rov_message.forward = track_motor_arm;
  216. //---------------------------
  217. //右摇杆 转向的控制
  218. if(fabsf(_turn)>0.1 )// 防抖
  219. {
  220. //转弯中 手动控制
  221. track_head_gd = (float)ahrs.yaw_sensor/100;//to show 20210611
  222. slowly_speed1(motor1_speed_target,motors1,1,3);
  223. slowly_speed2(motor2_speed_target,motors2,1,3);
  224. track_motor_arm =3;//left or right
  225. }
  226. else{
  227. //纯手动控制
  228. if(clean_mode == 0){
  229. slowly_speed1(motor1_speed_target,motors1,1,3);
  230. slowly_speed2(motor2_speed_target,motors2,1,3);
  231. static int kn1 = 0;
  232. kn1++;
  233. if(kn1>800)
  234. {
  235. //gcs().send_text(MAV_SEVERITY_WARNING, "left %f, turn %f %f %f\n",left,_turn,left*Speedmax_hand,_turn*maxerror);
  236. gcs().send_text(MAV_SEVERITY_WARNING, " speed_target %f %d %d ",left,motor2_speed_target,motor1_speed_target);
  237. kn1=0;
  238. }
  239. }else {
  240. }
  241. }
  242. }
  243. }
  244. void Sub::slowly_speed2(int16_t &p1, int16_t p2,int16_t step,int16_t per)
  245. {
  246. static int16_t countper = 0;
  247. countper++;
  248. if(countper>per){
  249. countper = 0;
  250. if (p1 > p2)
  251. {
  252. p1 -=step;
  253. }else if(p1 < p2){
  254. p1 +=step;
  255. }
  256. if (p2==startval && fabsf(p1-p2)<=step )
  257. {
  258. p1 =startval;
  259. }
  260. }
  261. else{
  262. }
  263. //p1 = constrain_int16(p1, -(Speedmax_hand+maxerror), Speedmax_hand+maxerror);
  264. p1 = constrain_int16(p1, -((int16_t)maxspeed+maxerror), (int16_t)maxspeed+maxerror);
  265. static int j = 0;
  266. j++;
  267. if(j>800)
  268. {
  269. // gcs().send_text(MAV_SEVERITY_WARNING, " thrust%d %f ,%d,%d\n",i,thrust_in,thrust,last_thrust_pwm[i]);
  270. j=0;
  271. }
  272. }
  273. void Sub::slowly_speed1(int16_t &p1, int16_t p2,int16_t step,int16_t per)
  274. {
  275. static int16_t countper = 0;
  276. countper++;
  277. if(countper>per){
  278. countper = 0;
  279. if (p1 > p2)
  280. {
  281. p1 -=step;
  282. }else if(p1 < p2){
  283. p1 +=step;
  284. }
  285. if (p2==startval && fabsf(p1-p2)<=step )
  286. {
  287. p1 =startval;
  288. }
  289. }
  290. else{
  291. }
  292. //p1 = constrain_int16(p1, -(Speedmax_hand+maxerror), Speedmax_hand+maxerror);
  293. p1 = constrain_int16(p1, -((int16_t)maxspeed+maxerror), (int16_t)maxspeed+maxerror);
  294. static int j = 0;
  295. j++;
  296. if(j>800)
  297. {
  298. // gcs().send_text(MAV_SEVERITY_WARNING, " thrust%d %f ,%d,%d\n",i,thrust_in,thrust,last_thrust_pwm[i]);
  299. j=0;
  300. }
  301. }
  302. float Sub::Constrate1(float d1)
  303. {//摇杆死区设置 0.06= 30/500
  304. if (fabsf(d1)*100<6)
  305. {
  306. return 0.0;
  307. }
  308. else{
  309. return d1;
  310. }
  311. }
  312. //extern mavlink_motor_feedback_t motor_feedback;
  313. extern mavlink_motor_speed_t mav_motor_speed;
  314. extern mavlink_rov_state_monitoring_t rov_message;
  315. void Sub::motor_toCan(void)
  316. {
  317. if(mav_motor_speed.motorTest == 1)//电机测试模式
  318. {
  319. motors.motor_to_can[8] = mav_motor_speed.Ltrack;//切换成上位机控制 左履带
  320. motors.motor_to_can[9] = mav_motor_speed.Rtrack;//右履带
  321. }else{
  322. if(control_mode == CLEAN){
  323. motors.motor_to_can[8] = motor1_speed_target;//飞控自己的履带
  324. motors.motor_to_can[9] = motor2_speed_target;
  325. }else{//非ARCO模式履带不工作
  326. motors.motor_to_can[8] = 0;
  327. motors.motor_to_can[9] = 0;
  328. }
  329. }
  330. static int j = 0;
  331. j++;
  332. if(j>400)
  333. {
  334. // gcs().send_text(MAV_SEVERITY_INFO, " motor_to_can %d %d ,%d,%d\n",motors.motor_to_can[8],motors.motor_to_can[9]);
  335. j=0;
  336. }
  337. }
  338. void Sub::clean_sidenet_auto(void)
  339. {
  340. }
  341. //提取朝向误差并返回
  342. float Sub::get_yaw_error(float yaw_heading){
  343. //目标四元数
  344. Quaternion error_head;
  345. error_head.from_axis_angle(Vector3f(0, 0, yaw_heading*RAD_TO_DEG));
  346. _attitude_target_quat = _attitude_target_quat*error_head;
  347. //当前姿态
  348. Quaternion attitude_vehicle_quat;
  349. ahrs.get_quat_body_to_ned(attitude_vehicle_quat);
  350. //当前姿态Z轴
  351. Matrix3f att_to_rot_matrix; // rotation from the target body frame to the inertial frame.
  352. attitude_vehicle_quat.rotation_matrix(att_to_rot_matrix);
  353. Vector3f att_to_thrust_vec = att_to_rot_matrix * Vector3f(0.0f, 0.0f, 1.0f);
  354. //目标姿态Z轴
  355. Matrix3f att_from_rot_matrix; // rotation from the current body frame to the inertial frame.
  356. _attitude_target_quat.rotation_matrix(att_from_rot_matrix);
  357. Vector3f att_from_thrust_vec = att_from_rot_matrix * Vector3f(0.0f, 0.0f, 1.0f);
  358. Vector3f thrust_vec_cross = att_from_thrust_vec % att_to_thrust_vec;//得到轴
  359. float thrust_vec_dot = acosf(constrain_float(att_from_thrust_vec * att_to_thrust_vec, -1.0f, 1.0f));//得到角
  360. float thrust_vector_length = thrust_vec_cross.length();
  361. if (is_zero(thrust_vector_length) || is_zero(thrust_vec_dot)) {
  362. thrust_vec_cross = Vector3f(0, 0, 1);
  363. thrust_vec_dot = 0.0f;
  364. } else {
  365. thrust_vec_cross /= thrust_vector_length;
  366. }
  367. Quaternion error_lean;
  368. error_lean.from_axis_angle(thrust_vec_cross, thrust_vec_dot);// 地系下的从obj到half态的误差四元数
  369. Quaternion error_lean_body= attitude_vehicle_quat.inverse() * error_lean * attitude_vehicle_quat;//b系下的从obj到half态的误差四元数
  370. Quaternion lean_earth= attitude_vehicle_quat * error_lean_body ;//half态下的四元数
  371. Quaternion error_yaw= lean_earth.inverse() * _attitude_target_quat ;//yaw误差四元数
  372. Vector3f rotation;
  373. error_yaw.to_axis_angle(rotation);//得到轴角
  374. float yaw_error = rotation.z*RAD_TO_DEG;//得到yaw方位的误差
  375. return yaw_error;
  376. }
  377. void Sub::clean_sidenet_state(void){
  378. //-------------机器人头朝上-自动洗网-
  379. min_depth =SRV_Channels::srv_channel(11)->get_output_min();// 上端距离 厘米
  380. max_depth = SRV_Channels::srv_channel(11)->get_output_max();//最深距离 厘米
  381. int16_t depth_now =fabsf((int16_t)barometer.get_altitude())*100;
  382. if(autoclean_flag == FALSE)
  383. {//没有自动洗网 保存深度值
  384. autoclean_orgin =depth_now;
  385. autoclean_step = Orign;
  386. }else{
  387. int16_t depth_down=min_depth;
  388. static int8_t delayCnt = 0;
  389. int16_t depth_up = max_depth;
  390. static int8_t delayCnt2 = 0;
  391. switch(autoclean_step){
  392. case Orign:
  393. track_head_gd = 0;
  394. //起始位置位于中上部,先往下走,如果起始位置在中下部 先往上走 假设头向上
  395. if(fabsf(autoclean_orgin-min_depth)>fabsf(autoclean_orgin-max_depth)){
  396. track_motor_arm =2;//向前走
  397. autoclean_step = foward;
  398. }else{
  399. track_motor_arm =0;//向后走
  400. autoclean_step = backward;
  401. }
  402. break;
  403. case foward:
  404. //向前走 2
  405. if (track_motor_arm !=0 && depth_now<=min_depth)
  406. {//转折处 前走 或者 停 但深度小于设置值
  407. track_head_gd = turn_angle;//10度 转10度
  408. track_motor_arm = 1;//先停
  409. delayCnt++;
  410. if (delayCnt>100)//停后延时,400 HZ 理论是0.25秒
  411. {
  412. track_motor_arm = 0;
  413. delayCnt =0;
  414. }
  415. }else{
  416. }
  417. if (track_motor_arm == 0 && depth_now -depth_down>100)//相反方向走了xx cm
  418. {//切换到向后走
  419. track_head_gd = 0.0;//0度
  420. autoclean_step =backward;
  421. }
  422. break;
  423. case backward:
  424. //向后走kk
  425. if (track_motor_arm !=2 && depth_now>=max_depth)
  426. {//转折处 向前走或者停 深度大于设置的最大深度
  427. track_head_gd = -turn_angle;//-10度
  428. track_motor_arm = 1;//2;
  429. delayCnt2++;
  430. if (delayCnt2>100)
  431. {
  432. delayCnt2=0;
  433. track_motor_arm=2;
  434. }
  435. }
  436. else{
  437. }
  438. if (track_motor_arm == 2 && depth_up-depth_now>100)////相反方向走了xx cm
  439. {//切换到向前走
  440. track_head_gd = 0.0;
  441. autoclean_step =foward;//切换状态
  442. }
  443. break;
  444. default:
  445. track_motor_arm =1;
  446. track_head_gd=0.0;
  447. break;
  448. }
  449. }
  450. }
  451. void Sub::clean_sidenet_run(void)//自动洗测网
  452. {
  453. //水平方向还没有自动洗网,没有测试
  454. static int16_t motors1=0;
  455. static int16_t motors2=0;
  456. if (autoclean_flag == FALSE)
  457. {//没有自动洗网返回
  458. motors1=0;
  459. motors2=0;
  460. return;
  461. }
  462. //PID设置
  463. trackpid.p1 = attitude_control._thr_mix_man;
  464. trackpid.p2 = attitude_control._thr_mix_man;
  465. trackpid.i1 = attitude_control._thr_mix_max;
  466. trackpid.i2 = attitude_control._thr_mix_max;
  467. trackpid.d1 = attitude_control._thr_mix_min;
  468. trackpid.d2 = attitude_control._thr_mix_min;
  469. //1000-1500向前走,左履带1,右履带2,方向 右歪增大
  470. static int8_t per = 0;//分频数
  471. if (per >3)
  472. {//50HZ控制频率
  473. per = 0;
  474. track_pidcontrol(track_head_gd,motors1,motors2);
  475. }
  476. per++;
  477. slowly_speed1(motor1_speed_target,motors1,1,3);
  478. slowly_speed2(motor2_speed_target,motors2,1,3);
  479. }
  480. // 不同方向上的履带的PID调用 以及缓加缓减
  481. void Sub::track_pidcontrol(float _targethead,int16_t &_motor1,int16_t &_motor2){
  482. int16_t motors1=startval;
  483. int16_t motors2 =startval;
  484. uint32_t nowtime=AP_HAL::micros();
  485. static uint32_t lasttime = nowtime;//用于换向延时防止抱死
  486. float error = get_yaw_error(_targethead);
  487. if (track_motor_arm ==0)
  488. {//后走
  489. if (nowtime - lasttime <500000)//500ms T1
  490. {//防抱死
  491. motors1 = startval;
  492. motors2 = startval;
  493. }
  494. else{
  495. motors1 = constrain_int16(-Speedmax+trackpid.updatePID1(0,0,error,(float)Speedmax),-Speedmax,Speedmax);
  496. motors2 = constrain_int16(-Speedmax+trackpid.updatePID2(0,0,error,(float)Speedmax),-Speedmax,Speedmax);
  497. }
  498. }
  499. else if (track_motor_arm ==1)
  500. {//停
  501. lasttime = AP_HAL::micros();
  502. motors1 = startval;
  503. motors2 =startval;
  504. }
  505. else if (track_motor_arm ==2)
  506. {//前走
  507. if (nowtime - lasttime <500000)//500ms T1
  508. {//防抱死
  509. motors1 =startval;
  510. motors2 = startval;
  511. }
  512. else{
  513. motors1 = constrain_int16(Speedmax+trackpid.updatePID1(0,0,error,(float)Speedmax),-Speedmax,Speedmax);
  514. motors2 = constrain_int16(Speedmax+trackpid.updatePID2(0,0,error,(float)Speedmax),-Speedmax,Speedmax);
  515. }
  516. }
  517. _motor1 = motors1;
  518. _motor2 = motors2;
  519. }