main.cpp 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713
  1. /*
  2. * esmini - Environment Simulator Minimalistic
  3. * https://github.com/esmini/esmini
  4. *
  5. * This Source Code Form is subject to the terms of the Mozilla Public
  6. * License, v. 2.0. If a copy of the MPL was not distributed with this
  7. * file, You can obtain one at https://mozilla.org/MPL/2.0/.
  8. *
  9. * Copyright (c) partners of Simulation Scenarios
  10. * https://sites.google.com/view/simulationscenarios
  11. */
  12. /*
  13. * The purpose of this application is to support development of the RoadManager by visualizing the road network and moving objects on top.
  14. * Bascially it loads an OpenDRIVE file, and optionally a corresponding 3D model, and then populate vehicles at specified density. The
  15. * vehicles will simply follow it's lane until a potential junction where the choice of route is randomized.
  16. *
  17. * The application can be used both to debug the RoadManager and to check OpenDRIVE files, e.g. w.r.t. gemoetry, lanes and connectivity.
  18. *
  19. * New road/track segments is indicated by a yellow large dot. Geometry segments within a road are indicated by red dots.
  20. * Red line is the reference lane, blue lines shows drivable lanes. Non-drivable lanes are currently not indicated.
  21. */
  22. #include <random>
  23. #include <iostream>
  24. #define _USE_MATH_DEFINES
  25. #include <math.h>
  26. #include "viewer.hpp"
  27. #include "RoadManager.hpp"
  28. #include "CommonMini.hpp"
  29. #define DEFAULT_SPEED 70 // km/h
  30. #define DEFAULT_DENSITY 1 // Cars per 100 m
  31. #define ROAD_MIN_LENGTH 30
  32. #define SIGN(X) ((X<0)?-1:1)
  33. static bool run_only_once = false;
  34. static const double stepSize = 0.01;
  35. static const double maxStepSize = 0.1;
  36. static const double minStepSize = 0.01;
  37. static const bool freerun = true;
  38. static std::mt19937 mt_rand;
  39. static double density = DEFAULT_DENSITY;
  40. static double speed = DEFAULT_SPEED;
  41. static double global_speed_factor = 1.0;
  42. static int first_car_in_focus = -1;
  43. double deltaSimTime; // external - used by Viewer::RubberBandCamera
  44. typedef struct
  45. {
  46. int road_id_init;
  47. int lane_id_init;
  48. double heading_init;
  49. double s_init;
  50. roadmanager::Position *pos;
  51. double speed_factor; // speed vary bewtween lanes, m/s
  52. viewer::EntityModel *model;
  53. int id;
  54. } Car;
  55. typedef struct
  56. {
  57. double mrel_x;
  58. double mrel_y;
  59. viewer::EntityModel * model;
  60. } RadarObj;
  61. std::vector<Car*> cars;
  62. std::vector<RadarObj *> gradarobj;
  63. const int NRADARMX = 100;
  64. Car * gADCIV_car;
  65. viewer::EntityModel * gtestRadar;
  66. // Car models used for populating the road network
  67. // path should be relative the OpenDRIVE file
  68. static const char* carModelsFiles_[] =
  69. {
  70. "car_white.osgb",
  71. "car_blue.osgb",
  72. "car_red.osgb",
  73. "car_yellow.osgb",
  74. "truck_yellow.osgb",
  75. "van_red.osgb",
  76. "bus_blue.osgb",
  77. };
  78. std::vector<osg::ref_ptr<osg::LOD>> carModels_;
  79. #include "modulecomm.h"
  80. #include "gpsimu.pb.h"
  81. #include "radarobjectarray.pb.h"
  82. #include "gnss_coordinate_convert.h"
  83. double glat0 = 39.1201777;
  84. double glon0 = 117.02802270;
  85. double gfrel_x = 0;
  86. double gfrel_y = 0;
  87. double gfrel_z = 0;
  88. double gvehicle_hdg = 0;
  89. double gvehicleheight = 1.6;
  90. double gfspeed = 0;
  91. void Listengpsimu(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  92. {
  93. // ggpsimu->UpdateGPSIMU(strdata,nSize);
  94. iv::gps::gpsimu xgpsimu;
  95. if(!xgpsimu.ParseFromArray(strdata,nSize))
  96. {
  97. std::cout<<"ListenRaw Parse error."<<std::endl;
  98. return;
  99. }
  100. (void)&index;
  101. (void)dt;
  102. (void)strmemname;
  103. double x0,y0;
  104. double x,y;
  105. double rel_x, rel_y;
  106. GaussProjCal(glon0,glat0,&x0,&y0);
  107. GaussProjCal(xgpsimu.lon(),xgpsimu.lat(),&x,&y);
  108. rel_x = x - x0;
  109. rel_y = y - y0;
  110. gfrel_x = rel_x;
  111. gfrel_y = rel_y;
  112. gfrel_z = xgpsimu.height();
  113. if(xgpsimu.has_speed())
  114. {
  115. gfspeed = xgpsimu.speed();
  116. }
  117. else
  118. {
  119. gfspeed = 3.6*sqrt(pow(xgpsimu.vn(),2)+pow(xgpsimu.ve(),2));
  120. }
  121. double hdg = xgpsimu.heading();
  122. hdg = (90-hdg) * M_PI/180.0;
  123. if(hdg < 0)hdg = hdg + M_PI*2.0;
  124. gvehicle_hdg = hdg;
  125. }
  126. void ListenRADAR(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  127. {
  128. static qint64 oldrecvtime;
  129. iv::radar::radarobjectarray xradararray;
  130. if(!xradararray.ParseFromArray(strdata,nSize))
  131. {
  132. std::cout<<"ListenRadar Parse Error."<<std::endl;
  133. return;
  134. }
  135. int i;
  136. for(i=0;i<xradararray.obj_size();i++)
  137. {
  138. iv::radar::radarobject * pobj = xradararray.mutable_obj(i);
  139. if(i<gradarobj.size())
  140. {
  141. if(pobj->bvalid())
  142. {
  143. gradarobj.at(i)->mrel_x = pobj->x();
  144. gradarobj.at(i)->mrel_y = pobj->y();
  145. }
  146. else
  147. {
  148. gradarobj.at(i)->mrel_x = 10000;
  149. gradarobj.at(i)->mrel_y = 10000;
  150. }
  151. }
  152. }
  153. for(i=xradararray.obj_size();i<gradarobj.size();i++)
  154. {
  155. gradarobj.at(i)->mrel_x = 10000;
  156. gradarobj.at(i)->mrel_y = 10000;
  157. }
  158. }
  159. void log_callback(const char *str)
  160. {
  161. printf("%s\n", str);
  162. }
  163. #include <osgDB/ReadFile>
  164. #include <osg/ComputeBoundsVisitor>
  165. #include <osg/LineWidth>
  166. #include <osg/Point>
  167. #include <osg/BlendFunc>
  168. #include <osg/BlendColor>
  169. #include <osg/Geode>
  170. #include <osg/Group>
  171. #include <osg/ShapeDrawable>
  172. #include <osg/CullFace>
  173. #include <osgGA/StateSetManipulator>
  174. #include <osgGA/TrackballManipulator>
  175. #include <osgGA/KeySwitchMatrixManipulator>
  176. #include <osgGA/FlightManipulator>
  177. #include <osgGA/DriveManipulator>
  178. #include <osgGA/TerrainManipulator>
  179. #include <osgGA/SphericalManipulator>
  180. #include <osgViewer/ViewerEventHandlers>
  181. #include <osgDB/Registry>
  182. #include <osgShadow/StandardShadowMap>
  183. #include <osgShadow/ShadowMap>
  184. #include <osgShadow/ShadowedScene>
  185. #include <osgUtil/SmoothingVisitor>
  186. #include <osgUtil/Tessellator> // to tessellate multiple contours
  187. void createosgbox()
  188. {
  189. osg::ref_ptr<osg::Group> group = 0;
  190. osg::ref_ptr<osg::Geode> geode = new osg::Geode;
  191. geode->addDrawable(new osg::ShapeDrawable(new osg::Box()));
  192. osg::ref_ptr<osg::Group> bbGroup = new osg::Group;
  193. osg::ref_ptr<osg::PositionAttitudeTransform> tx = new osg::PositionAttitudeTransform;
  194. osg::Material* material = new osg::Material();
  195. // Set color of vehicle based on its index
  196. double* color;
  197. double b = 1.5; // brighness
  198. int index = 2;
  199. if (index == 0) color = color_white;
  200. else if (index == 1) color = color_red;
  201. else if (index == 2) color = color_blue;
  202. else color = color_yellow;
  203. material->setDiffuse(osg::Material::FRONT, osg::Vec4(b * color[0], b * color[1], b * color[2], 1.0));
  204. material->setAmbient(osg::Material::FRONT, osg::Vec4(b * color[0], b * color[1], b * color[2], 1.0));
  205. osg::ref_ptr<osg::Geode> geodeCopy = dynamic_cast<osg::Geode*>(geode->clone(osg::CopyOp::DEEP_COPY_ALL));
  206. group = new osg::Group;
  207. tx->addChild(geodeCopy);
  208. geodeCopy->setNodeMask(viewer::NodeMask::NODE_MASK_ENTITY_MODEL);
  209. }
  210. int SetupADCIVCar( viewer::Viewer *viewer)
  211. {
  212. int carModelID = 2;
  213. Car *car_ = new Car;
  214. // Higher speeds in lanes closer to reference lane
  215. car_->speed_factor = 0.5 ; // Speed vary between 0.5 to 1.0 times default speed
  216. car_->road_id_init = 0;
  217. car_->lane_id_init = 0;
  218. car_->s_init = 0;
  219. // car_->pos = new roadmanager::Position(odrManager->GetRoadByIdx(r)->GetId(), lane->GetId(), s, 0);
  220. // car_->pos->SetHeadingRelative(lane->GetId() < 0 ? 0 : M_PI);
  221. // car_->heading_init = car_->pos->GetHRelative();
  222. if ((car_->model = viewer->AddEntityModel(carModelsFiles_[carModelID], osg::Vec3(0.5, 0.5, 0.5),
  223. viewer::EntityModel::EntityType::ENTITY_TYPE_VEHICLE, false, "", 0)) == 0)
  224. {
  225. return -1;
  226. }
  227. car_->id = 0;
  228. if (first_car_in_focus == -1 )
  229. {
  230. first_car_in_focus = car_->id;
  231. }
  232. gADCIV_car = car_;
  233. return 0;
  234. }
  235. int SetupRadar(viewer::Viewer *viewer)
  236. {
  237. int i;
  238. for(i=0;i<NRADARMX;i++)
  239. {
  240. RadarObj * pRadar = new RadarObj;
  241. pRadar->mrel_x = 10000;
  242. pRadar->mrel_y = 10000;
  243. pRadar->model = viewer->AddRadarModel(osg::Vec3(0.5, 0.5, 0.5),"");
  244. gradarobj.push_back(pRadar);
  245. }
  246. return 0;
  247. }
  248. int SetupCars(roadmanager::OpenDrive *odrManager, viewer::Viewer *viewer)
  249. {
  250. if (density < 1E-10)
  251. {
  252. // Basically no scenario vehicles
  253. return 0;
  254. }
  255. // for (int r = 0; r < 10; r++)
  256. for (int r = 0; r < odrManager->GetNumOfRoads(); r++)
  257. {
  258. roadmanager::Road *road = odrManager->GetRoadByIdx(r);
  259. double average_distance = 100.0 / density;
  260. if (road->GetLength() > ROAD_MIN_LENGTH)
  261. {
  262. // Populate road lanes with vehicles at some random distances
  263. for (double s = 10; s < road->GetLength() - average_distance; s += average_distance + 0.2 * average_distance * mt_rand() / mt_rand.max())
  264. {
  265. // Pick lane by random
  266. int lane_idx = ((double)road->GetNumberOfDrivingLanes(s) * mt_rand()) / (mt_rand.max)();
  267. roadmanager::Lane *lane = road->GetDrivingLaneByIdx(s, lane_idx);
  268. if (lane == 0)
  269. {
  270. LOG("Failed locate driving lane %d at s %d", lane_idx, s);
  271. continue;
  272. }
  273. if ((SIGN(lane->GetId()) < 0) && (road->GetLength() - s < 50) && (road->GetLink(roadmanager::LinkType::SUCCESSOR) == 0) ||
  274. (SIGN(lane->GetId()) > 0) && (s < 50) && (road->GetLink(roadmanager::LinkType::PREDECESSOR) == 0))
  275. {
  276. // Skip vehicles too close to road end - and where connecting road is missing
  277. continue;
  278. }
  279. // randomly choose model
  280. int carModelID = (double(sizeof(carModelsFiles_) / sizeof(carModelsFiles_[0])) * mt_rand()) / (mt_rand.max)();
  281. LOG("Adding car of model %d to road nr %d (road id %d s %.2f lane id %d), ", carModelID, r, road->GetId(), s, lane->GetId());
  282. carModelID = 2;
  283. Car *car_ = new Car;
  284. // Higher speeds in lanes closer to reference lane
  285. car_->speed_factor = 0.5 + 0.5 / abs(lane->GetId()); // Speed vary between 0.5 to 1.0 times default speed
  286. car_->road_id_init = odrManager->GetRoadByIdx(r)->GetId();
  287. car_->lane_id_init = lane->GetId();
  288. car_->s_init = s;
  289. car_->pos = new roadmanager::Position(odrManager->GetRoadByIdx(r)->GetId(), lane->GetId(), s, 0);
  290. car_->pos->SetHeadingRelative(lane->GetId() < 0 ? 0 : M_PI);
  291. car_->heading_init = car_->pos->GetHRelative();
  292. if ((car_->model = viewer->AddEntityModel(carModelsFiles_[carModelID], osg::Vec3(0.5, 0.5, 0.5),
  293. viewer::EntityModel::EntityType::ENTITY_TYPE_VEHICLE, false, "", 0)) == 0)
  294. {
  295. return -1;
  296. }
  297. car_->id = cars.size();
  298. cars.push_back(car_);
  299. if (first_car_in_focus == -1 && lane->GetId() < 0)
  300. {
  301. first_car_in_focus = car_->id;
  302. }
  303. }
  304. }
  305. }
  306. if (first_car_in_focus == -1)
  307. {
  308. first_car_in_focus = 0;
  309. }
  310. return 0;
  311. }
  312. int SetupCarsSpecial(roadmanager::OpenDrive* odrManager, viewer::Viewer* viewer)
  313. {
  314. // Setup one single vehicle in a dedicated pos
  315. Car* car_ = new Car;
  316. car_->speed_factor = 1.0;
  317. car_->road_id_init = 1;
  318. car_->lane_id_init = -1;
  319. car_->s_init = 40;
  320. car_->pos = new roadmanager::Position(car_->road_id_init, car_->lane_id_init, car_->s_init, 0);
  321. car_->pos->SetHeadingRelative(car_->lane_id_init < 0 ? 0 : M_PI);
  322. car_->heading_init = car_->pos->GetHRelative();
  323. if ((car_->model = viewer->AddEntityModel(carModelsFiles_[0], osg::Vec3(0.5, 0.5, 0.5),
  324. viewer::EntityModel::EntityType::ENTITY_TYPE_VEHICLE, false, "", 0)) == 0)
  325. {
  326. return -1;
  327. }
  328. car_->id = cars.size();
  329. cars.push_back(car_);
  330. first_car_in_focus = 0;
  331. return 0;
  332. }
  333. void updateADCIVCar(Car * car)
  334. {
  335. static float x=0;
  336. static float y=0;
  337. static float z=0;
  338. static float head = M_PI/2.0;
  339. static float pitch =0;
  340. static float roll = 0;
  341. if (car->model->txNode_ != 0)
  342. {
  343. // car->model->txNode_->setPosition(osg::Vec3(car->pos->GetX(), car->pos->GetY(), car->pos->GetZ()));
  344. // car->model->quat_.makeRotate(
  345. // car->pos->GetR(), osg::Vec3(1, 0, 0),
  346. // car->pos->GetP(), osg::Vec3(0, 1, 0),
  347. // car->pos->GetH(), osg::Vec3(0, 0, 1));
  348. y = y+ 0.1;
  349. x = gfrel_x;
  350. y = gfrel_y;
  351. z = gfrel_z - gvehicleheight;
  352. head = gvehicle_hdg;
  353. car->model->txNode_->setPosition(osg::Vec3(x, y, z));
  354. car->model->quat_.makeRotate(
  355. roll, osg::Vec3(1, 0, 0),
  356. pitch, osg::Vec3(0, 1, 0),
  357. head, osg::Vec3(0, 0, 1));
  358. car->model->txNode_->setAttitude(car->model->quat_);
  359. int k;
  360. // head = head +M_PI/2.0;
  361. for(k=0;k<gradarobj.size();k++)
  362. {
  363. double relx,rely;
  364. relx = gradarobj.at(k)->mrel_y*cos(head) + gradarobj.at(k)->mrel_x * sin(head);
  365. rely = gradarobj.at(k)->mrel_y*sin(head) - gradarobj.at(k)->mrel_x*cos(head);
  366. gradarobj.at(k)->model->txNode_->setPosition(osg::Vec3(x+relx, y+rely, z));
  367. gradarobj.at(k)->model->quat_.makeRotate(
  368. roll, osg::Vec3(1, 0, 0),
  369. pitch, osg::Vec3(0, 1, 0),
  370. head, osg::Vec3(0, 0, 1));
  371. gradarobj.at(k)->model->txNode_->setAttitude(car->model->quat_);
  372. }
  373. }
  374. }
  375. void updateCar(roadmanager::OpenDrive *odrManager, Car *car, double dt)
  376. {
  377. double new_speed = car->pos->GetSpeedLimit() * car->speed_factor * global_speed_factor;
  378. double ds = new_speed * dt; // right lane is < 0 in road dir;
  379. if (car->pos->MoveAlongS(ds) != 0)
  380. {
  381. // Start from beginning of lane section - not initial s-position
  382. roadmanager::LaneSection* ls = odrManager->GetRoadById(car->road_id_init)->GetLaneSectionByS(car->s_init);
  383. double start_s = ls->GetS() + 5;
  384. if (car->lane_id_init > 0)
  385. {
  386. start_s = ls->GetS() + ls->GetLength() - 5;
  387. }
  388. car->pos->SetLanePos(car->road_id_init, car->lane_id_init, start_s, 0);
  389. car->pos->SetHeadingRelative(car->heading_init);
  390. }
  391. if (car->model->txNode_ != 0)
  392. {
  393. car->model->txNode_->setPosition(osg::Vec3(car->pos->GetX(), car->pos->GetY(), car->pos->GetZ()));
  394. car->model->quat_.makeRotate(
  395. car->pos->GetR(), osg::Vec3(1, 0, 0),
  396. car->pos->GetP(), osg::Vec3(0, 1, 0),
  397. car->pos->GetH(), osg::Vec3(0, 0, 1));
  398. car->model->txNode_->setAttitude(car->model->quat_);
  399. }
  400. }
  401. int main(int argc, char** argv)
  402. {
  403. static char str_buf[128];
  404. SE_Options opt;
  405. argc = 3;
  406. argv = new char*[3];
  407. argv[0] = "testodrviewer";
  408. argv[1] = "--odr";
  409. argv[2] = "/home/yuchuli/map/models/y.xodr";
  410. void * pa = iv::modulecomm::RegisterRecv("hcp2_gpsimu",Listengpsimu);
  411. pa = iv::modulecomm::RegisterRecv("radar",ListenRADAR);
  412. (void)pa;
  413. // Use logger callback
  414. Logger::Inst().SetCallback(log_callback);
  415. mt_rand.seed((unsigned int)time(0));
  416. std::vector<std::string> args;
  417. for (int i = 0; i < argc; i++) args.push_back(argv[i]);
  418. // use an ArgumentParser object to manage the program arguments.
  419. opt.AddOption("odr", "OpenDRIVE filename", "odr_filename");
  420. opt.AddOption("model", "3D Model filename", "model_filename");
  421. opt.AddOption("density", "density (cars / 100 m)", "density");
  422. opt.AddOption("speed_factor", "speed_factor <number>", "speed_factor");
  423. opt.AddOption("osi_lines", "Show OSI road lines (toggle during simulation by press 'u') ");
  424. opt.AddOption("osi_points", "Show OSI road points (toggle during simulation by press 'y') ");
  425. opt.AddOption("road_features", "Show OpenDRIVE road features (toggle during simulation by press 'o') ");
  426. opt.AddOption("path", "Search path prefix for assets, e.g. car and sign model files", "path");
  427. opt.AddOption("logfile_path", "logfile path/filename, e.g. \"../esmini.log\" (default: log.txt)", "path");
  428. opt.AddOption("disable_log", "Prevent logfile from being created");
  429. opt.AddOption("help", "Show this help message");
  430. if (argc < 2 || opt.GetOptionSet("help"))
  431. {
  432. opt.PrintUsage();
  433. return -1;
  434. }
  435. opt.ParseArgs(&argc, argv);
  436. std::string arg_str;
  437. if (opt.GetOptionSet("disable_log"))
  438. {
  439. SE_Env::Inst().SetLogFilePath("");
  440. printf("Disable logfile\n");
  441. }
  442. else if (opt.IsOptionArgumentSet("logfile_path"))
  443. {
  444. arg_str = opt.GetOptionArg("logfile_path");
  445. SE_Env::Inst().SetLogFilePath(arg_str);
  446. if (arg_str.empty())
  447. {
  448. printf("Custom logfile path empty, disable logfile\n");
  449. }
  450. else
  451. {
  452. printf("Custom logfile path: %s\n", arg_str.c_str());
  453. }
  454. }
  455. Logger::Inst().OpenLogfile();
  456. if ((arg_str = opt.GetOptionArg("path")) != "")
  457. {
  458. SE_Env::Inst().AddPath(arg_str);
  459. LOG("Added path %s", arg_str.c_str());
  460. }
  461. std::string odrFilename = opt.GetOptionArg("odr");
  462. // odrFilename = "/home/yuchuli/map/models/mapxiali.xodr";
  463. if (odrFilename.empty())
  464. {
  465. printf("Missing required argument --odr\n");
  466. opt.PrintUsage();
  467. return -1;
  468. }
  469. std::string modelFilename = opt.GetOptionArg("model");
  470. if (opt.GetOptionArg("density") != "")
  471. {
  472. density = strtod(opt.GetOptionArg("density"));
  473. }
  474. printf("density: %.2f\n", density);
  475. if (opt.GetOptionArg("speed_factor") != "")
  476. {
  477. global_speed_factor = strtod(opt.GetOptionArg("speed_factor"));
  478. }
  479. printf("global speed factor: %.2f\n", global_speed_factor);
  480. roadmanager::Position *lane_pos = new roadmanager::Position();
  481. roadmanager::Position *track_pos = new roadmanager::Position();
  482. try
  483. {
  484. if (!roadmanager::Position::LoadOpenDrive(odrFilename.c_str()))
  485. {
  486. printf("Failed to load ODR %s\n", odrFilename.c_str());
  487. return -1;
  488. }
  489. roadmanager::OpenDrive *odrManager = roadmanager::Position::GetOpenDrive();
  490. osg::ArgumentParser arguments(&argc, argv);
  491. viewer::Viewer *viewer = new viewer::Viewer(
  492. odrManager,
  493. modelFilename.c_str(),
  494. NULL,
  495. argv[0],
  496. arguments,
  497. &opt);
  498. viewer->SetWindowTitleFromArgs(args);
  499. if (opt.GetOptionSet("road_features"))
  500. {
  501. viewer->SetNodeMaskBits(viewer::NodeMask::NODE_MASK_ODR_FEATURES);
  502. }
  503. else
  504. {
  505. viewer->ClearNodeMaskBits(viewer::NodeMask::NODE_MASK_ODR_FEATURES);
  506. }
  507. if (opt.GetOptionSet("osi_lines"))
  508. {
  509. viewer->SetNodeMaskBits(viewer::NodeMask::NODE_MASK_OSI_LINES);
  510. }
  511. if (opt.GetOptionSet("osi_points"))
  512. {
  513. viewer->SetNodeMaskBits(viewer::NodeMask::NODE_MASK_OSI_POINTS);
  514. }
  515. printf("osi_features: lines %s points %s \n",
  516. viewer->GetNodeMaskBit(viewer::NodeMask::NODE_MASK_OSI_LINES) ? "on" : "off",
  517. viewer->GetNodeMaskBit(viewer::NodeMask::NODE_MASK_OSI_POINTS) ? "on" : "off");
  518. SetupADCIVCar(viewer);
  519. SetupRadar(viewer);
  520. // gtestRadar = viewer->AddRadarModel(osg::Vec3(0.5, 0.5, 0.5),"");
  521. // gtestRadar = viewer->AddEntityModel(carModelsFiles_[0], osg::Vec3(0.5, 0.5, 0.5),
  522. // viewer::EntityModel::EntityType::ENTITY_TYPE_VEHICLE, false, "", 0);
  523. // if (SetupCars(odrManager, viewer) == -1)
  524. // {
  525. // return 4;
  526. // }
  527. printf("%d cars added\n", (int)cars.size());
  528. viewer->SetVehicleInFocus(first_car_in_focus);
  529. __int64 now, lastTimeStamp = 0;
  530. static bool first_time = true;
  531. while (!viewer->osgViewer_->done())
  532. {
  533. // Get milliseconds since Jan 1 1970
  534. now = SE_getSystemTime();
  535. deltaSimTime = (now - lastTimeStamp) / 1000.0; // step size in seconds
  536. lastTimeStamp = now;
  537. if (deltaSimTime > maxStepSize) // limit step size
  538. {
  539. deltaSimTime = maxStepSize;
  540. }
  541. else if (deltaSimTime < minStepSize) // avoid CPU rush, sleep for a while
  542. {
  543. SE_sleep(now - lastTimeStamp);
  544. deltaSimTime = minStepSize;
  545. }
  546. if (!(run_only_once && !first_time))
  547. {
  548. updateADCIVCar(gADCIV_car);
  549. for (size_t i = 0; i < cars.size(); i++)
  550. {
  551. updateCar(odrManager, cars[i], deltaSimTime);
  552. }
  553. first_time = false;
  554. }
  555. snprintf(str_buf, sizeof(str_buf), "(%6.2f,%6.2f,%6.2f,%6.2f) (%6.2fkm/h)", gfrel_x,
  556. gfrel_y,gfrel_z,gvehicle_hdg,gfspeed);
  557. viewer->SetInfoText(str_buf);
  558. // Set info text
  559. if (cars.size() > 0 && viewer->currentCarInFocus_ >= 0 && viewer->currentCarInFocus_ < cars.size())
  560. {
  561. Car* car = cars[viewer->currentCarInFocus_];
  562. snprintf(str_buf, sizeof(str_buf), "entity[%d]: %.2fkm/h (%d, %d, %.2f, %.2f) / (%.2f, %.2f %.2f)", viewer->currentCarInFocus_,
  563. 3.6 * car->pos->GetSpeedLimit() * car->speed_factor * global_speed_factor, car->pos->GetTrackId(), car->pos->GetLaneId(),
  564. fabs(car->pos->GetOffset()) < SMALL_NUMBER ? 0 : car->pos->GetOffset(), car->pos->GetS(), car->pos->GetX(), car->pos->GetY(), car->pos->GetH());
  565. viewer->SetInfoText(str_buf);
  566. }
  567. // Step the simulation
  568. viewer->osgViewer_->frame();
  569. }
  570. delete viewer;
  571. }
  572. catch (std::logic_error &e)
  573. {
  574. printf("%s\n", e.what());
  575. return 2;
  576. }
  577. catch (std::runtime_error &e)
  578. {
  579. printf("%s\n", e.what());
  580. return 3;
  581. }
  582. for (size_t i = 0; i < cars.size(); i++)
  583. {
  584. delete(cars[i]);
  585. }
  586. delete track_pos;
  587. delete lane_pos;
  588. return 0;
  589. }