vehicle_manager_node_ori.cpp 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080
  1. #include <memory>
  2. #include <signal.h>
  3. #include <fstream>
  4. #include <stdio.h>
  5. #include "vehicle_manager/sensor_socket.h"
  6. #include "vehicle_manager/vehicle_manager_node.h"
  7. #include "vehicle_manager/iobuffer.h"
  8. #include "vehicle_manager/message.h"
  9. #include "vehicle_manager/rapidcsv.h"
  10. #include <geometry_msgs/PoseStamped.h>
  11. #include <assert.h>
  12. VehicleManager::VehicleManager():nh_(""), pnh_("~")
  13. {
  14. pub_cmd_ = nh_.advertise<geometry_msgs::PoseStamped>("move_base_simple/goal", 1);
  15. // pub_driver_=nh_.advertise<vehicle_msg::vehicle_state>("/goal_start", 1);
  16. pub_goal_=nh_.advertise<vehicle_msg::vehicle_state>("/goal_finish", 1);
  17. sub_goal_ = nh_.subscribe("/goal_finish", 1, &VehicleManager::callbackGoalFinish, this);
  18. sub_ndt_pos_=nh_.subscribe("/ndt_pose",1,&VehicleManager::callbackNdtPos,this);
  19. sub_vehiclecmd_= nh_.subscribe("/vehicle_cmd", 1, &VehicleManager::callbackVehicleCmd, this);
  20. pnh_.param<std::string>("ip", ip_, std::string(""));
  21. assert(ip_.empty()==false);
  22. pnh_.param<int32_t>("port", port_, 23001);
  23. pnh_.param<std::string>("launch_data", file_, std::string("empty"));
  24. pnh_.param<std::string>("work_area",_areafile,std::string("empty"));
  25. pnh_.param<bool>("increment",_throttle_increment,false);
  26. // pnh_.param<int32_t>("throttle_value",max_throttle_value,80);
  27. pnh_.param<int32_t>("throttle_value",max_throttle_value,60);
  28. // assert(max_throttle_value<=80);
  29. pnh_.param<float>("steer_ratio",_steer_ratio,2.5);
  30. }
  31. bool VehicleManager::Setup()
  32. {
  33. // std::cout<<ip_.c_str()<<std::endl;
  34. std::ifstream ifile(file_);
  35. if(ifile.is_open()==false)
  36. {
  37. std::cout<<file_<<std::endl;
  38. return false;
  39. }
  40. std::string str;
  41. bool bPreDynamic=true;
  42. bool bPostDynamic=false;
  43. bool bStatic=false;
  44. std::vector<std::string> bootproc;
  45. while(std::getline(ifile,str))
  46. {
  47. //进入
  48. if(str.find("*****")!=-1)
  49. {
  50. bPreDynamic=false;
  51. bPostDynamic=true;
  52. continue;
  53. }
  54. else if(str.find("-----")!=-1)
  55. {
  56. bPreDynamic=false;
  57. bPostDynamic=false;
  58. bStatic=true;
  59. continue;
  60. }
  61. if(bPreDynamic)
  62. {
  63. ROS_INFO(" pre %s",str.c_str());
  64. proc_info info;
  65. info.cmd=str;
  66. info.pid=-1;
  67. prev_.push_back(info);
  68. }
  69. else if(bPostDynamic)
  70. {
  71. proc_info info;
  72. ROS_INFO(" post %s",str.c_str());
  73. info.cmd=str;
  74. info.pid=-1;
  75. post_.push_back(info);
  76. }
  77. else{
  78. ROS_INFO(" boot %s",str.c_str());
  79. bootproc.push_back(str);
  80. }
  81. }
  82. /* for(int i=0;i<bootproc.size();i++)
  83. {
  84. auto& node=bootproc[i];
  85. int32_t pid=fork();
  86. if(pid==0)
  87. {
  88. ROS_INFO("%s",node.c_str());
  89. system(node.c_str());
  90. exit(0);
  91. }
  92. }
  93. */
  94. //ROS_INFO("procName size %d",procName_.size());
  95. rapidcsv::Document doc(_areafile.c_str());
  96. int32_t count= doc.GetRowCount();
  97. std::vector < std::string > name= doc.GetColumn<std::string>(0); //A1 *** K14
  98. std::vector<float> x = doc.GetColumn<float>(1); //x
  99. std::vector<float> y = doc.GetColumn<float>(2); //y
  100. std::cout << "count="<<count<<std::endl;
  101. for (int32_t i = 0; i < count; i++)
  102. {
  103. // std::cout<<i<<std::endl;
  104. //std::cout << name[i] << "," << x[i] << "," << y[i] << std::endl;
  105. const char* str = name[i].c_str() + 1;
  106. int32_t index = std::stoi(str)-1;
  107. // std::cout<<i<<","<<index<<","<<name[i].c_str()[0] - 'A'<<std::endl;
  108. AreaPos[name[i].c_str()[0] - 'A'][index].x = x[i];
  109. AreaPos[name[i].c_str()[0] - 'A'][index].y = y[i];
  110. // std::cout<<"OK"<<std::endl;
  111. }
  112. for(auto i=0;i<=WorkArea::Area_H;i++)
  113. {
  114. Forward[i].x=AreaPos[i][0].x-AreaPos[i][49].x;
  115. BackWard[i].x=AreaPos[i][49].x-AreaPos[i][0].x;
  116. Forward[i].y=AreaPos[i][0].y-AreaPos[i][49].y;
  117. BackWard[i].y=AreaPos[i][49].y-AreaPos[i][0].y;
  118. float len=sqrt(Forward[i].x*Forward[i].x+Forward[i].y*Forward[i].y);
  119. Forward[i].x/=len;
  120. Forward[i].y/=len;
  121. len=sqrt(BackWard[i].x*BackWard[i].x+BackWard[i].y*BackWard[i].y);
  122. BackWard[i].x/=len;
  123. BackWard[i].y/=len;
  124. }
  125. /*
  126. xMin=AreaPos[WorkArea::Area_A][49].x;
  127. for(int32_t i=0;i<WorkArea::Area_H;i++)
  128. {
  129. }
  130. */
  131. /*
  132. while(true)
  133. {
  134. std::this_thread::sleep_for(std::chrono::seconds(3));
  135. OnBootAuto();
  136. std::this_thread::sleep_for(std::chrono::seconds(10));
  137. OnStopAuto();
  138. }
  139. */
  140. _socket=std::make_unique<SensorSocket>(this,ip_.c_str());
  141. if(_socket->Start()==false) return false;
  142. _topic_recved=false;
  143. _startup=false;
  144. return true;
  145. }
  146. void VehicleManager::Shutdown()
  147. {
  148. _topic_recved=false;
  149. OnStopAuto();
  150. }
  151. inline int8_t hi_byte(int16_t value)
  152. {
  153. int8_t hi =(int8_t)((value & 0xFF00) >> 8);
  154. return hi;
  155. }
  156. inline int8_t lo_byte(int16_t value)
  157. {
  158. int8_t lo = (int8_t)(value & 0xff);
  159. return lo;
  160. }
  161. void VehicleManager::Notify(int8_t * buffer,int32_t size)
  162. {
  163. MessageHead Head;
  164. Head.Deserialize(buffer);
  165. auto ptr=buffer+MessageHead::Size();
  166. switch(Head.Command)
  167. {
  168. /* case RA::RA_Boot:
  169. {
  170. OnBootAuto();
  171. }
  172. break;
  173. case RA::RA_Stop:
  174. {
  175. OnStopAuto();
  176. }
  177. break;
  178. */
  179. case RA::RA_Goal:
  180. {
  181. ARMoveGoal* node=(ARMoveGoal *)ptr;
  182. ROS_INFO("received move to area %d,%d",node->area,node->no);
  183. OnAutoMove(node->area,node->no, MoveType::Forward);
  184. }
  185. break;
  186. case RA::RA_Encode:
  187. {
  188. cannet_frame * frame=(cannet_frame *)ptr;
  189. int32_t l0=frame->data[0]&0x000000ff;
  190. int32_t l1=frame->data[1]&0x000000ff;
  191. // for (int i = 0; i < 8; i++) {
  192. // printf(" 0x%02X", frame->data[i]);
  193. // }
  194. _steer_angle= /*(l3<<24)|(l2<<16)|*/(l1<<8)|l0;
  195. }
  196. break;
  197. case RA::RA_Stop:
  198. {
  199. OnStopAuto();
  200. IsActiveStop = true;
  201. }
  202. break;
  203. }
  204. }
  205. void VehicleManager::OnBootPrev()
  206. {
  207. ROS_INFO("proc account %d",prev_.size());
  208. for(int32_t i=0;i<prev_.size();i++)
  209. {
  210. ROS_INFO("%s",prev_[i].cmd);
  211. }
  212. for(int i=0;i<prev_.size();i++)
  213. {
  214. auto& node=prev_[i];
  215. if(node.pid==-1)
  216. {
  217. int32_t pid=fork();
  218. if(pid==0)
  219. {
  220. ROS_INFO("%s",node.cmd.c_str());
  221. system(node.cmd.c_str());
  222. exit(0);
  223. }
  224. else{
  225. node.pid=pid;
  226. }
  227. }
  228. // std::this_thread::sleep_for(std::chrono::seconds(1));
  229. }
  230. }
  231. void VehicleManager::OnBootPost()
  232. {
  233. ROS_INFO("post proc account %d",post_.size());
  234. for(int i=0;i<post_.size();i++)
  235. {
  236. auto& node=post_[i];
  237. if(node.pid==-1)
  238. {
  239. int32_t pid=fork();
  240. if(pid==0)
  241. {
  242. ROS_INFO("%s",node.cmd.c_str());
  243. system(node.cmd.c_str());
  244. exit(0);
  245. }
  246. else{
  247. node.pid=pid;
  248. }
  249. }
  250. std::this_thread::sleep_for(std::chrono::seconds(2));
  251. }
  252. }
  253. /*
  254. void VehicleManager::OnBootAuto()
  255. {
  256. ROS_INFO("proc account %d",proc_.size());
  257. for(int i=0;i<proc_.size();i++)
  258. {
  259. auto& node=proc_[i];
  260. if(node.pid==-1)
  261. {
  262. int32_t pid=fork();
  263. if(pid==0)
  264. {
  265. ROS_INFO("%s",node.cmd.c_str());
  266. system(node.cmd.c_str());
  267. exit(0);
  268. }
  269. else{
  270. node.pid=pid;
  271. }
  272. }
  273. std::this_thread::sleep_for(std::chrono::seconds(4));
  274. }
  275. }
  276. */
  277. /// @brief
  278. /// @param x
  279. /// @param y
  280. /// @param z
  281. //#define OFFSET 18.8f C,D
  282. #define GLOBAL_OFFSET 19.0f;
  283. void VehicleManager::OnAutoMove(int32_t area, int32_t no,MoveType type)
  284. {
  285. if (IsActiveStop)
  286. {
  287. OnBootPrev();
  288. }
  289. float OFFSET=GLOBAL_OFFSET;
  290. std::lock_guard<std::mutex> l(_pos_lock);
  291. // if(_start==true) return;
  292. // OnStopAuto();
  293. float cx=_curPos.pose.position.x;
  294. float cy=_curPos.pose.position.y;
  295. //float cz=curPos.pose.postion.z;
  296. float dx=AreaPos[area][no].x;
  297. float dy=AreaPos[area][no].y;
  298. float lx=dx-cx;
  299. float ly=dy-cy;
  300. Eigen::Vector3d v(lx,ly,0);
  301. ROS_INFO("%d,%d",cx,cy);
  302. if(v.norm()<10) return;
  303. _moveType=type;
  304. area_=area;
  305. no_=no;
  306. // OnBootPrev();//临时
  307. // Direction curDir=GetCarDirection(_curPos.pose.orientation.z,_curPos.pose.orientation.w);
  308. Quaternion dir;
  309. geometry_msgs::PoseStamped pose;
  310. if(area==WorkArea::Area_J)
  311. {
  312. Direction d=Direction::South;
  313. if(no==0||no==1)
  314. {
  315. d=Direction::South;
  316. }
  317. else if(no==12||no==13)
  318. {
  319. d=Direction::North;
  320. }
  321. else{
  322. d=dy>cy?Direction::North:Direction::South;
  323. }
  324. dir=qarray[d];
  325. if(d==Direction::South)
  326. {
  327. dx=AreaPos[area+1][no].x;
  328. dy=AreaPos[area+1][no].y;
  329. }
  330. if ( no == 0 || no ==1 || no == 12 || no == 13)
  331. {
  332. dy+=(d==Direction::South?-25:25);
  333. } else {
  334. dy+=(d==Direction::South?-16:16);
  335. }
  336. }
  337. else if(area==WorkArea::Area_I)
  338. {
  339. dir=qarray[Direction::South];
  340. }
  341. else
  342. {
  343. //v.normalize();
  344. Eigen::AngleAxisd axis;
  345. axis=Eigen::Quaterniond(_curPos.pose.orientation.w,_curPos.pose.orientation.x,_curPos.pose.orientation.y,_curPos.pose.orientation.z);
  346. //auto e=_curPos.pose.orientation.matrix().eulerAngles(0,1,2);
  347. double cur_angle=axis.angle();
  348. auto v=axis.axis();
  349. if(v[2]==-1)
  350. {
  351. cur_angle=EIGEN_PI*2-cur_angle;
  352. }
  353. const auto epilson=(30/160)*EIGEN_PI;
  354. if(dy-cy>20)
  355. {
  356. if(cx>AreaPos[area_][0].x)
  357. {
  358. if(cur_angle>EIGEN_PI*3/4 && cur_angle<EIGEN_PI*5/4)
  359. {
  360. dir=qarray[Direction::East];
  361. dx-=OffsetWest(area_);
  362. }
  363. else if(cur_angle>EIGEN_PI/4&& cur_angle<EIGEN_PI*5/4)
  364. {
  365. dir=qarray[Direction::West];
  366. dx-=OffsetWest(area_);
  367. //dy-=Forward[area].y*10;
  368. }
  369. else //if(cur_angle>EIGEN_PI*5/4&& cur_angle<EIGEN_PI*7/4)
  370. {
  371. dir=qarray[Direction::East];
  372. dx+=OffsetEast(area_) ;
  373. //dy+=Forward[area].y* 10 ;
  374. }
  375. }
  376. else if(cx<AreaPos[area_][49].x)
  377. {
  378. if(cur_angle>0&&cur_angle<EIGEN_PI)
  379. {
  380. dir=qarray[Direction::East];
  381. dx+= OffsetEast(area_) ;
  382. //dy+=Forward[area].y* 10 ;
  383. }
  384. else
  385. {
  386. dir=qarray[Direction::West];
  387. dx-=OffsetWest(area_);
  388. //dy-=Forward[area].y*10;
  389. }
  390. }
  391. else
  392. {
  393. if(cur_angle<EIGEN_PI/4||cur_angle>EIGEN_PI*7/4)
  394. {
  395. dir=qarray[Direction::West];
  396. dx-=OffsetWest(area_);
  397. //dy-=Forward[area].y*10;
  398. }
  399. else
  400. {
  401. dir=qarray[Direction::East];
  402. dx+=OffsetEast(area_) ;
  403. //dy+=Forward[area].y* 10 ;
  404. }
  405. }
  406. }
  407. else if(cy-dy>20)
  408. {
  409. if(cx>AreaPos[area_][0].x)
  410. {
  411. if(cur_angle>EIGEN_PI/4&& cur_angle<EIGEN_PI*5/4)
  412. {
  413. dir=qarray[Direction::East];
  414. dx+=OffsetEast(area_) ;
  415. //dy+=Forward[area].y* 10 ;
  416. }
  417. else //if(cur_angle>EIGEN_PI*5/4&& cur_angle<EIGEN_PI*7/4)
  418. {
  419. dir=qarray[Direction::West];
  420. dx-=OffsetWest(area_);
  421. //dy-=Forward[area].y*10;
  422. }
  423. }
  424. else if(cx<AreaPos[area_][49].x)
  425. {
  426. if(cur_angle>0&&cur_angle<EIGEN_PI)
  427. {
  428. dir=qarray[Direction::West];
  429. dx-=OffsetWest(area_);
  430. }
  431. else
  432. {
  433. dir=qarray[Direction::East];
  434. dx+=OffsetEast(area_) ;
  435. }
  436. }
  437. else
  438. {
  439. if(cur_angle<EIGEN_PI/4||cur_angle>EIGEN_PI*7/4)
  440. {
  441. dir=qarray[Direction::West];
  442. dx-=OffsetWest(area_);
  443. }
  444. else
  445. {
  446. dir=qarray[Direction::East];
  447. dx+=OffsetEast(area_) ;
  448. }
  449. }
  450. }
  451. else{
  452. if(cx>AreaPos[area_][0].x)
  453. {
  454. if(dy>cy)
  455. {
  456. if(cur_angle>EIGEN_PI/4&& cur_angle<EIGEN_PI*3/4)
  457. {
  458. dir=qarray[Direction::West];
  459. dx-=OffsetWest(area_);
  460. //dy-=Forward[area].y*10;
  461. }
  462. else if (cur_angle>EIGEN_PI*3/4&& cur_angle<EIGEN_PI*5/4)
  463. {
  464. dir=qarray[Direction::West];
  465. dx-=OffsetWest(area_);
  466. //dy-=Forward[area].y*10;
  467. }
  468. else //if(cur_angle>EIGEN_PI*5/4&& cur_angle<EIGEN_PI*7/4)
  469. {
  470. //dy+=Forward[area].y* 10 ;
  471. dir=qarray[Direction::East];
  472. dx+=OffsetEast(area_) ;
  473. }
  474. }
  475. else
  476. {
  477. if(cur_angle>EIGEN_PI/4&& cur_angle<EIGEN_PI*3/4)
  478. {
  479. dir=qarray[Direction::East];
  480. dx+=OffsetEast(area_) ;
  481. //dy-=Forward[area].y*10;
  482. }
  483. else //if(cur_angle>EIGEN_PI*5/4&& cur_angle<EIGEN_PI*7/4)
  484. {
  485. //dy+=Forward[area].y* 10 ;
  486. dir=qarray[Direction::West];
  487. dx-=OffsetWest(area_);
  488. }
  489. }
  490. }
  491. else if(cx<AreaPos[area_][49].x)
  492. {
  493. if(dy>cy)
  494. {
  495. if(cur_angle>0&&cur_angle<EIGEN_PI)
  496. {
  497. dir=qarray[Direction::East];
  498. dx+=OffsetEast(area_) ;
  499. //dy+=Forward[area].y* 10 ;
  500. }
  501. else
  502. {
  503. dir=qarray[Direction::West];
  504. dx-=OffsetWest(area_);
  505. //dy-=Forward[area].y*10;
  506. }
  507. }
  508. else
  509. {
  510. if(cur_angle>0&&cur_angle<EIGEN_PI)
  511. {
  512. dir=qarray[Direction::West];
  513. dx-=OffsetWest(area_);
  514. //dy+=Forward[area].y* 10 ;
  515. }
  516. else
  517. {
  518. //dy-=Forward[area].y*10;
  519. dir=qarray[Direction::East];
  520. dx+=OffsetEast(area_) ;
  521. }
  522. }
  523. }
  524. else{
  525. if(cur_angle<EIGEN_PI/4||cur_angle>EIGEN_PI*7/4)
  526. {
  527. dir=qarray[Direction::East];
  528. dx+=OffsetEast(area_) ;
  529. /* if(dx<cx)
  530. {
  531. dir=qarray[Direction::East];
  532. dx-=OffsetWest(area_);
  533. }
  534. else{
  535. dir=qarray[Direction::West];
  536. dx+=OffsetEast(area_) ;
  537. }
  538. */
  539. }
  540. else
  541. {
  542. dir=qarray[Direction::West];
  543. dx-=OffsetWest(area_);
  544. /* if(dx>cx)
  545. {
  546. dir=qarray[Direction::West];
  547. dx+=OffsetEast(area_) ;
  548. }
  549. else{
  550. dir=qarray[Direction::West];
  551. dx-=OffsetWest(area_);
  552. }
  553. */
  554. }
  555. }
  556. }
  557. }
  558. ROS_INFO("area %d,no %d, %f,%f,%f,%f",area,no,dx,dy,dir.z,dir.w);
  559. _destX=dx;
  560. _destY=dy;
  561. pose.pose.position.x=dx;
  562. pose.pose.position.y=dy;
  563. pose.pose.position.z =0;
  564. _dir=Eigen::Quaterniond(dir.w,dir.x,dir.y,dir.z);
  565. pose.pose.orientation.x=dir.x;
  566. pose.pose.orientation.y=dir.y;
  567. pose.pose.orientation.z=dir.z;
  568. pose.pose.orientation.w=dir.w;
  569. std::this_thread::sleep_for(std::chrono::seconds(3));
  570. pub_cmd_.publish(pose);
  571. // std::this_thread::sleep_for(std::chrono::seconds(1));
  572. OnBootPost();
  573. std::this_thread::sleep_for(std::chrono::seconds(2));
  574. _topic_recved=true;
  575. IsActiveStop = false;
  576. /*
  577. vehicle_msg::vehicle_state state;
  578. state.state=true;
  579. pub_driver_.publish(state);
  580. */
  581. }
  582. float VehicleManager::OffsetEast(int32_t area)
  583. {
  584. float OFFSET=GLOBAL_OFFSET;
  585. switch(area)
  586. {
  587. case WorkArea::Area_A:
  588. OFFSET-=0.15f;
  589. break;
  590. case WorkArea::Area_B:
  591. OFFSET-=1.5f;
  592. if (no_ == 0)
  593. OFFSET += 1.0f;
  594. break;
  595. case WorkArea::Area_C:
  596. OFFSET-=0.5f;
  597. break;
  598. case WorkArea::Area_D:
  599. OFFSET-=0.7f;
  600. break;
  601. case WorkArea::Area_E:
  602. case WorkArea::Area_G:
  603. //OFFSET-=0.5f;
  604. OFFSET-=0.15f;
  605. break;
  606. }
  607. return OFFSET;
  608. }
  609. float VehicleManager::OffsetWest(int32_t area)
  610. {
  611. float OFFSET=GLOBAL_OFFSET;
  612. switch(area)
  613. {
  614. case WorkArea::Area_A:
  615. OFFSET-=0.2f;
  616. break;
  617. case WorkArea::Area_B:
  618. OFFSET-=0.0f;
  619. break;
  620. case WorkArea::Area_C:
  621. OFFSET-=0.2f;
  622. break;
  623. case WorkArea::Area_D:
  624. OFFSET+=0.2f;
  625. break;
  626. case WorkArea::Area_E:
  627. case WorkArea::Area_G:
  628. //OFFSET-=0.5f;
  629. OFFSET-=0.2f;
  630. break;
  631. }
  632. return OFFSET;
  633. }
  634. bool VehicleManager::IsLarger_X0(float cx,float cy)
  635. {
  636. float x=AreaPos[area_][0].x;
  637. float y=AreaPos[area_][0].y;
  638. return cx>=x+10;
  639. }
  640. bool VehicleManager::IsSmall_X50(float cx,float cy)
  641. {
  642. float x=AreaPos[area_][49].x;
  643. return cx<=x;
  644. }
  645. void VehicleManager::OnStopAuto()
  646. {
  647. std::cout<<"Stop"<<std::endl;
  648. for(int i=0;i<prev_.size();i++)
  649. {
  650. auto& node=prev_[i];
  651. if(node.pid!=-1)
  652. {
  653. std::string kill_cmd = "kill -9 ";
  654. kill_cmd.append(std::to_string(node.pid));
  655. std::cout<<kill_cmd<<std::endl;
  656. system(kill_cmd.c_str());
  657. // kill(node.pid,SIGINT);
  658. }
  659. node.pid=-1;
  660. }
  661. for(int i=0;i<post_.size();i++)
  662. {
  663. auto& node=post_[i];
  664. if(node.pid!=-1)
  665. {
  666. std::string kill_cmd = "kill -9 ";
  667. kill_cmd.append(std::to_string(node.pid));
  668. std::cout<<kill_cmd<<std::endl;
  669. system(kill_cmd.c_str());
  670. // kill(node.pid,SIGINT);
  671. }
  672. node.pid=-1;
  673. }
  674. std::string p[]={
  675. "twist_filter",
  676. "twist_gate",
  677. "op_global_plann",
  678. "pure_pursuit",
  679. };
  680. for(auto& name:p)
  681. {
  682. FILE *fp;
  683. char buf[255];
  684. char cmd[200] = {'\0'};
  685. pid_t pid = -1;
  686. sprintf(cmd, "ps -e | grep \'%s\' | awk \'{print $1}\'", name.c_str());
  687. ROS_INFO("%s",cmd);
  688. if((fp = popen(cmd, "r")) != NULL)
  689. {
  690. while(fgets(buf, 255, fp) != NULL)
  691. {
  692. pid = atoi(buf);
  693. std::string kill_cmd = "kill -9 ";
  694. kill_cmd.append(std::to_string(pid));
  695. std::cout<<kill_cmd<<std::endl;
  696. system(kill_cmd.c_str());
  697. printf("pid = %d \n", pid);
  698. }
  699. pclose(fp);
  700. }
  701. }
  702. }
  703. /*
  704. Direction VehicleManager::GetCarDirection(float z,float w)
  705. {
  706. Direction dir;
  707. float diff=1000000.f;
  708. for(int i=0;i<Direction::ALL;i++)
  709. {
  710. auto ret=(qarray[i].z-z)*(qarray[i].z-z)+(qarray[i].w-w)*(qarray[i].w-w);
  711. if(diff>ret)
  712. {
  713. diff=ret;
  714. dir=(Direction)i;
  715. }
  716. }
  717. return dir;
  718. }
  719. */
  720. void VehicleManager::callbackGoalFinish(const vehicle_msg::vehicle_stateConstPtr& ptr)
  721. {
  722. ROS_INFO("Goal end,%d,%d",area_,no_);
  723. std::lock_guard<std::mutex> l(_pos_lock);
  724. if(ptr->state==true)
  725. {
  726. float dx=_curPos.pose.position.x-_destX;
  727. float dy=_curPos.pose.position.y-_destY;
  728. ROS_INFO("%f,%f",dx,dy);
  729. // if(dx*dx+dy*dy<1)
  730. {
  731. CIOBuffer pBuffer;
  732. auto ptr=pBuffer.Buffer;
  733. MessageHead Head;
  734. Head.Command=AR_Finish;
  735. ptr=pBuffer.Buffer+sizeof(MessageHead);
  736. ARFinish * node=(ARFinish *)ptr;
  737. node->area=area_;
  738. node->no=no_;
  739. Head.Length=sizeof(ARFinish);
  740. Head.Serialize(pBuffer.Buffer);
  741. pBuffer.Length=sizeof(MessageHead)+sizeof(ARFinish);
  742. _socket->Write(pBuffer.Buffer,pBuffer.Length);
  743. }
  744. std::cout<<"Goal end"<<area_<<","<<no_<<std::endl;
  745. OnStopAuto();
  746. std::this_thread::sleep_for(std::chrono::seconds(5));
  747. OnBootPrev();//临时
  748. _topic_recved=false;
  749. }
  750. }
  751. void VehicleManager::callbackVehicleCmd(const autoware_msgs::VehicleCmdConstPtr vehicle_cmd_ptr)
  752. {
  753. if(_topic_recved==false) return;
  754. auto vel=vehicle_cmd_ptr->twist_cmd.twist.linear.x;
  755. auto accel=vehicle_cmd_ptr->ctrl_cmd.linear_acceleration;
  756. if(vel < 0.05)
  757. {
  758. ROS_INFO("VEL:%f",vel);
  759. }
  760. if(vel!=0||accel!=0)
  761. {
  762. if(_startup==false)
  763. {
  764. _startup=true;
  765. }
  766. _zero_count=0;
  767. }
  768. else
  769. {
  770. if(_startup==true)
  771. {
  772. _zero_count++;
  773. if(_zero_count>500)
  774. {
  775. ROS_INFO("----------------------------------------------------------------------------------------*********");
  776. vehicle_msg::vehicle_state msg;
  777. msg.state=true;
  778. pub_goal_.publish(msg);
  779. _topic_recved=false;
  780. _startup=false;
  781. return;
  782. }
  783. }
  784. }
  785. // ROS_INFO("vel %f,accel %f",vehicle_cmd_ptr->twist_cmd.twist.linear.x,vehicle_cmd_ptr->ctrl_cmd.linear_acceleration);
  786. float fs=(vehicle_cmd_ptr->ctrl_cmd.steering_angle*-1.f)*4096/(2*M_PI);
  787. int16_t steer=fs;
  788. int16_t diff=steer-_steer_angle;
  789. int16_t value=std::min(std::abs(diff*_steer_ratio),3000.f);//ptr->steer>0?1000:-1000;
  790. // ROS_INFO("steer %d,diff %d", steer,value);
  791. if(accel==0&&vel==0)
  792. {
  793. if(_startup==false)
  794. _brake=80;
  795. else
  796. {
  797. if(area_==WorkArea::Area_J)
  798. {
  799. int32_t temp=_brake+40;
  800. _brake=std::min(temp,100);
  801. }
  802. else
  803. {
  804. int32_t temp=++_brake;
  805. _brake=std::min(temp,100);
  806. }
  807. }
  808. _throttle=-30;
  809. }
  810. else
  811. {
  812. //int32_t temp=++_throttle;
  813. //_throttle=std::min(temp,_moveType==MoveType::Forward?60:40);
  814. if(_throttle_increment)
  815. {
  816. if(value>300)
  817. {
  818. if(_throttle>=40)
  819. {
  820. int32_t temp=_throttle;
  821. temp--;
  822. _throttle=std::max(temp,40);
  823. }
  824. // _throttle/=2;
  825. }
  826. else{
  827. int32_t temp=++_throttle;
  828. _throttle=std::min(temp,max_throttle_value);
  829. }
  830. }
  831. else{
  832. _throttle = max_throttle_value;
  833. }
  834. _brake=0;
  835. }
  836. // ROS_INFO("accel %d",_throttle);
  837. //int16_t value=std::min(std::abs(diff*5),3000.0);//ptr->steer>0?1000:-1000;
  838. diff=_moveType==MoveType::Forward?diff:-diff;
  839. CIOBuffer pBuffer;
  840. MessageHead Head;
  841. Head.Command=AR::AR_CTRL;
  842. Head.Length=sizeof(can_array);
  843. Head.Serialize(pBuffer.Buffer);
  844. auto ptr=pBuffer.Buffer+sizeof(MessageHead);
  845. double dx=_curPos.pose.position.x-_destX;
  846. double dy=_curPos.pose.position.y-_destY;
  847. double d=sqrt(dx*dx+dy*dy);
  848. if(d<=30.f&&_throttle>0)
  849. {
  850. Eigen::Quaterniond q(_curPos.pose.orientation.w,_curPos.pose.orientation.x,_curPos.pose.orientation.y,_curPos.pose.orientation.z);
  851. if(q.angularDistance(_dir)<(EIGEN_PI/3))
  852. {
  853. d/=30.f;
  854. _throttle=80*d;
  855. }
  856. }
  857. can_array * data=(can_array *)ptr;
  858. data->count=3;
  859. data->frames[0].canid=0x586;
  860. data->frames[0].dlc=8;
  861. data->frames[0].data[0]=0XFF;
  862. data->frames[0].data[1]=0;
  863. data->frames[0].data[2]=hi_byte(value);
  864. data->frames[0].data[3]=lo_byte(value);
  865. data->frames[0].data[4]=diff < 0 ? 1 : 0;
  866. data->frames[0].data[4]|=0x02;
  867. data->frames[0].data[5]=0;
  868. data->frames[0].data[6]=0;
  869. data->frames[0].data[7]=0;
  870. memset(data->frames[1].data,0,sizeof(data->frames[1].data));
  871. data->frames[1].canid=0x386;
  872. data->frames[1].dlc=8;
  873. data->frames[1].data[0]=_throttle<0?0:_throttle>>1;
  874. data->frames[1].data[1]=_brake ;
  875. data->frames[2].canid=0x286;
  876. data->frames[2].dlc=8;
  877. data->frames[2].data[0]=0x04;//value>500?0x08:0x04;//_moveType==MoveType::Forward?0x04:0x0;
  878. data->frames[2].data[1]=0x0;//_moveType==MoveType::Forward?0x0:0x21;
  879. data->frames[2].data[2]=0x01;
  880. data->frames[2].data[3]=0x0;
  881. data->frames[2].data[4]=0x1B;
  882. data->frames[2].data[5]=0x0;
  883. data->frames[2].data[6]=0x02;
  884. data->frames[2].data[7]=0x0;
  885. pBuffer.Length=sizeof(MessageHead)+sizeof(can_array);
  886. _socket->Write(pBuffer.Buffer,pBuffer.Length);
  887. // ROS_INFO("steer:%f,throttle: %f,brake: %f",output.steer,output.throttle,output.brake);
  888. }
  889. void VehicleManager::callbackNdtPos(const geometry_msgs::PoseStampedConstPtr& msg)
  890. {
  891. std::lock_guard<std::mutex> l(_pos_lock);
  892. _curPos.pose.position.x=msg->pose.position.x;
  893. _curPos.pose.position.y=msg->pose.position.y;
  894. _curPos.pose.position.z=msg->pose.position.z;
  895. _curPos.pose.orientation.x=msg->pose.orientation.x;
  896. _curPos.pose.orientation.y=msg->pose.orientation.y;
  897. _curPos.pose.orientation.z=msg->pose.orientation.z;
  898. _curPos.pose.orientation.w=msg->pose.orientation.w;
  899. static int64_t tick=std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count();
  900. auto diff=std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()).count() -tick;
  901. if(diff>500)
  902. {
  903. CIOBuffer pBuffer;
  904. auto ptr=pBuffer.Buffer;
  905. MessageHead Head;
  906. Head.Command=AR_NDTPos;
  907. Head.Length=sizeof(ARNdtPos);
  908. Head.Serialize(pBuffer.Buffer);
  909. ptr=pBuffer.Buffer+sizeof(MessageHead);
  910. ARNdtPos * node=(ARNdtPos *)ptr;
  911. // std::cout<< msg->pose.position.x<<","<<msg->pose.position.y<<","<<node->z<<std::endl;
  912. node->rx=_curPos.pose.orientation.x;
  913. node->ry=_curPos.pose.orientation.y;
  914. node->rz=_curPos.pose.orientation.z;
  915. node->rw=_curPos.pose.orientation.w;
  916. node->x=_curPos.pose.position.x;
  917. node->y=_curPos.pose.position.y;
  918. node->z=_curPos.pose.position.z;
  919. pBuffer.Length=sizeof(MessageHead)+Head.Length;
  920. _socket->Write(pBuffer.Buffer,pBuffer.Length);
  921. }
  922. }