vtd_pilot.cpp 9.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287
  1. #include "vtd_pilot.h"
  2. static void CalcXY(const double lat0,const double lon0,
  3. const double lat,const double lon,
  4. double & x,double & y)
  5. {
  6. double x0,y0;
  7. GaussProjCal(lon0,lat0,&x0,&y0);
  8. GaussProjCal(lon,lat,&x,&y);
  9. x = x - x0;
  10. y = y- y0;
  11. }
  12. vtd_pilot::vtd_pilot(std::string strfromvtd,std::string strtovtd)
  13. {
  14. (void)strfromvtd;
  15. ModuleFun funvtd =std::bind(&vtd_pilot::UpdateVTD,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
  16. mpfromvtd = iv::modulecomm::RegisterRecvPlus(strfromvtd.data(),funvtd);
  17. mptovtd = iv::modulecomm::RegisterSend(strtovtd.data(),10000,1) ;
  18. ModuleFun fungpsimu =std::bind(&vtd_pilot::UpdateGPSIMU,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
  19. mpagpsimu = iv::modulecomm::RegisterRecvPlus("hcp2_gpsimu",fungpsimu);
  20. mpaegostate = iv::modulecomm::RegisterSend("egostate",10000,1);
  21. mpthread = new std::thread(&vtd_pilot::threadego,this);
  22. memset( &sOwnObjectState, 0, sizeof( RDB_OBJECT_STATE_t ) );
  23. }
  24. void vtd_pilot::UpdateGPSIMU(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  25. {
  26. (void)index;
  27. (void)dt;
  28. (void)strmemname;
  29. iv::gps::gpsimu xgpsimu;
  30. if(!xgpsimu.ParseFromArray(strdata,nSize))
  31. {
  32. std::cout<<"parse gpsimu fail"<<std::endl;
  33. return;
  34. }
  35. mmutex.lock();
  36. mgpsimu.CopyFrom(xgpsimu);
  37. mbupdate_gps = true;
  38. mmutex.unlock();
  39. mcv.notify_all();
  40. }
  41. void vtd_pilot::ConvertToObjectArray(std::vector<iv::vtd::rdbdata> &xvectorrdbdata, iv::fusion::fusionobjectarray &xfusionarray)
  42. {
  43. int i;
  44. int j;
  45. for(i=0;i<(int)xvectorrdbdata.size();i++)
  46. {
  47. iv::vtd::rdbdata * prdbdata = &xvectorrdbdata[i];
  48. for(j=0;j<prdbdata->mrdbitem_size();j++)
  49. {
  50. iv::vtd::rdbitem * pitem = prdbdata->mutable_mrdbitem(j);
  51. if(pitem->pkgid() == RDB_PKG_ID_OBJECT_STATE)
  52. {
  53. RDB_OBJECT_STATE_t xobj;
  54. // std::cout<<" structure RDB_OBJECT_STATE_t size: "<<sizeof(xobj)<<"data size: "<<xrdbitem.mnpkgdatasize<<std::endl;
  55. memcpy(&xobj,pitem->pkgdata().data(),sizeof(RDB_OBJECT_STATE_t));
  56. std::cout<<"id:"<<xobj.base.id<<" name:"<<xobj.base.name<< " pos : x "<<xobj.base.pos.x<<" y "<<xobj.base.pos.y<<" z "<<xobj.base.pos.z<<std::endl;
  57. iv::fusion::fusionobject * pobject = NULL;
  58. int k;
  59. for(k=0;k<xfusionarray.obj_size();k++)
  60. {
  61. if(xfusionarray.mutable_obj(k)->id() == xobj.base.id)
  62. {
  63. pobject = xfusionarray.mutable_obj(k);
  64. break;
  65. }
  66. }
  67. if(pobject == NULL)
  68. {
  69. pobject = xfusionarray.add_obj();
  70. }
  71. pobject->set_id(xobj.base.id);
  72. double x,y;
  73. x = xobj.base.pos.x - mfX;
  74. y = xobj.base.pos.y - mfY;
  75. double relx,rely;
  76. double beta = mfHeading*(-1.0);
  77. relx = x*cos(beta) - y*sin(beta);
  78. rely = x*sin(beta) + y*sin(beta);
  79. double vx,vy;
  80. vx = xobj.ext.speed.x;
  81. vy = xobj.ext.speed.y;
  82. vx = vx - mfvx;
  83. vy = vy - mfvy;
  84. double relvx,relvy;
  85. relvx = vx*cos(beta) - vy*sin(beta);
  86. relvy = vx*sin(beta) + vy*sin(beta);
  87. double fobjheading = xobj.base.pos.h;
  88. fobjheading = fobjheading - mfHeading;
  89. pobject->set_lifetime(100);
  90. pobject->set_prob(1.0);
  91. pobject->set_sensor_type(1);
  92. pobject->set_yaw(fobjheading);
  93. iv::fusion::PointXYZ * ppointxyz = new iv::fusion::PointXYZ;
  94. ppointxyz->set_x(relx);
  95. ppointxyz->set_y(rely);
  96. ppointxyz->set_z(0);
  97. iv::fusion::Dimension * pdim = new iv::fusion::Dimension;
  98. pdim->set_x(xobj.base.geo.dimX);
  99. pdim->set_y(xobj.base.geo.dimY);
  100. pdim->set_z(xobj.base.geo.dimZ);
  101. pobject->set_allocated_centroid(ppointxyz);
  102. pobject->set_allocated_dimensions(pdim);
  103. pobject->set_velocity_linear_x(sqrt(pow(relvx,2)+pow(relvy,2)));
  104. }
  105. }
  106. }
  107. }
  108. void vtd_pilot::threadobject()
  109. {
  110. std::vector<iv::vtd::rdbdata> xvectorrdbdata;
  111. int64_t nlastsharetime = std::chrono::system_clock::now().time_since_epoch().count();
  112. // int nmaxobjid = 2;
  113. int nshareinter = 100; //100 ms share a data.
  114. bool bshare = false;
  115. while(mbRun)
  116. {
  117. int64_t now = std::chrono::system_clock::now().time_since_epoch().count();
  118. int64_t timediff = abs(now-nlastsharetime)/1000000;
  119. if(timediff >= nshareinter)
  120. {
  121. bshare = true;
  122. }
  123. if(bshare)
  124. {
  125. //share object data.
  126. bshare = false;
  127. nlastsharetime = now;
  128. xvectorrdbdata.clear();
  129. }
  130. std::unique_lock<std::mutex> lk(mmutexcvrdb);
  131. if(mcvrdb.wait_for(lk,std::chrono::milliseconds(10)) == std::cv_status::timeout)
  132. {
  133. lk.unlock();
  134. continue;
  135. }
  136. else
  137. {
  138. lk.unlock();
  139. }
  140. mmutexrdb.lock();
  141. int i;
  142. for(i=0;i<(int)mvectorrdbdata.size();i++)
  143. {
  144. xvectorrdbdata.push_back(mvectorrdbdata[i]);
  145. }
  146. mmutexrdb.unlock();
  147. }
  148. }
  149. void vtd_pilot::UpdateVTD(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
  150. {
  151. (void)index;
  152. (void)dt;
  153. (void)strmemname;
  154. iv::vtd::rdbdata xrdbdata;
  155. if(xrdbdata.ParseFromArray(strdata,nSize))
  156. {
  157. mmutexrdb.lock();
  158. mvectorrdbdata.push_back(xrdbdata);
  159. mmutexrdb.unlock();
  160. mcvrdb.notify_all();
  161. if(xrdbdata.mrdbitem_size()>0)
  162. {
  163. iv::vtd::rdbitem * pitem = xrdbdata.mutable_mrdbitem(0);
  164. msimFrame = pitem->simframe();
  165. msimTime = pitem->simtime();
  166. if(pitem->pkgid() == RDB_PKG_ID_OBJECT_STATE)
  167. {
  168. }
  169. }
  170. }
  171. }
  172. void vtd_pilot::setOwnState(double x, double y, double z,double vx,double vy,double fheading)
  173. {
  174. sOwnObjectState.base.id = 1;
  175. sOwnObjectState.base.category = RDB_OBJECT_CATEGORY_PLAYER;
  176. sOwnObjectState.base.type = RDB_OBJECT_TYPE_PLAYER_CAR;
  177. strcpy( sOwnObjectState.base.name, "Ego" );
  178. // dimensions of own vehicle
  179. sOwnObjectState.base.geo.dimX = 4.60 ;//* dimFactor;
  180. sOwnObjectState.base.geo.dimY = 1.86 ;//* dimFactor;
  181. sOwnObjectState.base.geo.dimZ = 1.60 ;//* dimFactor;
  182. // offset between reference point and center of geometry
  183. sOwnObjectState.base.geo.offX = 0.80;
  184. sOwnObjectState.base.geo.offY = 0.00;
  185. sOwnObjectState.base.geo.offZ = 0.30;
  186. sOwnObjectState.base.pos.x = x;
  187. sOwnObjectState.base.pos.y = y;
  188. sOwnObjectState.base.pos.z = z;
  189. sOwnObjectState.base.pos.h = fheading;
  190. sOwnObjectState.base.pos.p = 0.0;
  191. sOwnObjectState.base.pos.r = 0.0;
  192. sOwnObjectState.base.pos.flags = RDB_COORD_FLAG_POINT_VALID | RDB_COORD_FLAG_ANGLES_VALID;
  193. sOwnObjectState.ext.speed.x = vx;
  194. sOwnObjectState.ext.speed.y = vy;
  195. sOwnObjectState.ext.speed.z = 0;
  196. sOwnObjectState.ext.speed.h = 0.0;
  197. sOwnObjectState.ext.speed.p = 0.0;
  198. sOwnObjectState.ext.speed.r = 0.0;
  199. sOwnObjectState.ext.speed.flags = RDB_COORD_FLAG_POINT_VALID | RDB_COORD_FLAG_ANGLES_VALID;
  200. sOwnObjectState.ext.accel.x = 0.0;
  201. sOwnObjectState.ext.accel.y = 0.0;
  202. sOwnObjectState.ext.accel.z = 0.0;
  203. sOwnObjectState.ext.accel.flags = RDB_COORD_FLAG_POINT_VALID;
  204. sOwnObjectState.base.visMask = RDB_OBJECT_VIS_FLAG_TRAFFIC | RDB_OBJECT_VIS_FLAG_RECORDER;
  205. }
  206. void vtd_pilot::threadego()
  207. {
  208. while(mbRun)
  209. {
  210. if(mbupdate_gps == false)
  211. {
  212. std::unique_lock<std::mutex> lk(mmutexcv);
  213. if(mcv.wait_for(lk,std::chrono::milliseconds(100)) == std::cv_status::timeout)
  214. {
  215. lk.unlock();
  216. continue;
  217. }
  218. else
  219. {
  220. lk.unlock();
  221. continue;
  222. }
  223. }
  224. iv::gps::gpsimu xgpsimu;
  225. mmutex.lock();
  226. xgpsimu.CopyFrom(mgpsimu);
  227. mbupdate_gps = false;
  228. mmutex.unlock();
  229. double x,y,z;
  230. CalcXY(mflat0,mflon0,xgpsimu.lat(),xgpsimu.lon(),x,y);
  231. double vx = xgpsimu.ve();
  232. double vy = xgpsimu.vn();
  233. z = 0;
  234. double fheading = (90 - xgpsimu.heading())*M_PI/180.0;
  235. setOwnState(x,y,z,vx,vy,fheading);
  236. mfX = x;
  237. mfY = y;
  238. mfHeading = fheading;
  239. mfvx = vx;
  240. mfvy = vy;
  241. // RDB_OBJECT_STATE_t * pr = &sOwnObjectState;
  242. iv::modulecomm::ModuleSendMsg(mpaegostate,(char *)&sOwnObjectState,sizeof(RDB_OBJECT_STATE_t));
  243. //convert to x,y,z
  244. //send data.
  245. }
  246. }