CARLA
CarlaRecorderQuery.cpp
Go to the documentation of this file.
1 // Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
2 // de Barcelona (UAB).
3 //
4 // This work is licensed under the terms of the MIT license.
5 // For a copy, see <https://opensource.org/licenses/MIT>.
6 
7 #include "CarlaRecorderQuery.h"
8 
9 #include "CarlaRecorderHelpers.h"
10 
11 #include "CarlaRecorder.h"
12 
13 #include <ctime>
14 #include <sstream>
15 #include <string>
16 
21 
23 {
24  if (File.eof())
25  {
26  return false;
27  }
28 
29  ReadValue<char>(File, Header.Id);
30  ReadValue<uint32_t>(File, Header.Size);
31 
32  return true;
33 }
34 
36 {
37  File.seekg(Header.Size, std::ios::cur);
38 }
39 
40 inline bool CarlaRecorderQuery::CheckFileInfo(std::stringstream &Info)
41 {
42  // read Info
43  RecInfo.Read(File);
44 
45  // check magic string
46  if (RecInfo.Magic != "CARLA_RECORDER")
47  {
48  Info << "File is not a CARLA recorder" << std::endl;
49  return false;
50  }
51 
52  // show general Info
53  Info << "Version: " << RecInfo.Version << std::endl;
54  Info << "Map: " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl;
55  tm *TimeInfo = localtime(&RecInfo.Date);
56  char DateStr[100];
57  strftime(DateStr, sizeof(DateStr), "%x %X", TimeInfo);
58  Info << "Date: " << DateStr << std::endl << std::endl;
59 
60  return true;
61 }
62 
63 std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
64 {
65  std::stringstream Info;
66 
67  // get the final path + filename
68  std::string Filename2 = GetRecorderFilename(Filename);
69 
70  // try to open
71  File.open(Filename2, std::ios::binary);
72  if (!File.is_open())
73  {
74  Info << "File " << Filename2 << " not found on server\n";
75  return Info.str();
76  }
77 
78  uint16_t i, Total;
79  bool bFramePrinted = false;
80 
81  // lambda for repeating task
82  auto PrintFrame = [this](std::stringstream &Info)
83  {
84  Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds\n";
85  };
86 
87  if (!CheckFileInfo(Info))
88  return Info.str();
89 
90  // parse only frames
91  while (File)
92  {
93  // get header
94  if (!ReadHeader())
95  {
96  break;
97  }
98 
99  // check for a frame packet
100  switch (Header.Id)
101  {
102  // frame
103  case static_cast<char>(CarlaRecorderPacketId::FrameStart):
104  Frame.Read(File);
105  if (bShowAll)
106  {
107  PrintFrame(Info);
108  bFramePrinted = true;
109  }
110  else
111  bFramePrinted = false;
112  break;
113 
114  // events add
115  case static_cast<char>(CarlaRecorderPacketId::EventAdd):
116  ReadValue<uint16_t>(File, Total);
117  if (Total > 0 && !bFramePrinted)
118  {
119  PrintFrame(Info);
120  bFramePrinted = true;
121  }
122  for (i = 0; i < Total; ++i)
123  {
124  // add
125  EventAdd.Read(File);
126  Info << " Create " << EventAdd.DatabaseId << ": " << TCHAR_TO_UTF8(*EventAdd.Description.Id) <<
127  " (" <<
128  static_cast<int>(EventAdd.Type) << ") at (" << EventAdd.Location.X << ", " <<
129  EventAdd.Location.Y << ", " << EventAdd.Location.Z << ")" << std::endl;
130  for (auto &Att : EventAdd.Description.Attributes)
131  {
132  Info << " " << TCHAR_TO_UTF8(*Att.Id) << " = " << TCHAR_TO_UTF8(*Att.Value) << std::endl;
133  }
134  }
135  break;
136 
137  // events del
138  case static_cast<char>(CarlaRecorderPacketId::EventDel):
139  ReadValue<uint16_t>(File, Total);
140  if (Total > 0 && !bFramePrinted)
141  {
142  PrintFrame(Info);
143  bFramePrinted = true;
144  }
145  for (i = 0; i < Total; ++i)
146  {
147  EventDel.Read(File);
148  Info << " Destroy " << EventDel.DatabaseId << "\n";
149  }
150  break;
151 
152  // events parenting
153  case static_cast<char>(CarlaRecorderPacketId::EventParent):
154  ReadValue<uint16_t>(File, Total);
155  if (Total > 0 && !bFramePrinted)
156  {
157  PrintFrame(Info);
158  bFramePrinted = true;
159  }
160  for (i = 0; i < Total; ++i)
161  {
163  Info << " Parenting " << EventParent.DatabaseId << " with " << EventParent.DatabaseIdParent <<
164  " (parent)\n";
165  }
166  break;
167 
168  // collisions
169  case static_cast<char>(CarlaRecorderPacketId::Collision):
170  ReadValue<uint16_t>(File, Total);
171  if (Total > 0 && !bFramePrinted)
172  {
173  PrintFrame(Info);
174  bFramePrinted = true;
175  }
176  for (i = 0; i < Total; ++i)
177  {
179  Info << " Collision id " << Collision.Id << " between " << Collision.DatabaseId1;
181  Info << " (hero) ";
182  Info << " with " << Collision.DatabaseId2;
184  Info << " (hero) ";
185  Info << std::endl;
186  }
187  break;
188 
189  // positions
190  case static_cast<char>(CarlaRecorderPacketId::Position):
191  if (bShowAll)
192  {
193  ReadValue<uint16_t>(File, Total);
194  if (Total > 0 && !bFramePrinted)
195  {
196  PrintFrame(Info);
197  bFramePrinted = true;
198  }
199  Info << " Positions: " << Total << std::endl;
200  for (i = 0; i < Total; ++i)
201  {
202  Position.Read(File);
203  Info << " Id: " << Position.DatabaseId << " Location: (" << Position.Location.X << ", " << Position.Location.Y << ", " << Position.Location.Z << ") Rotation: (" << Position.Rotation.X << ", " << Position.Rotation.Y << ", " << Position.Rotation.Z << ")" << std::endl;
204  }
205  }
206  else
207  SkipPacket();
208  break;
209 
210  // traffic light
211  case static_cast<char>(CarlaRecorderPacketId::State):
212  if (bShowAll)
213  {
214  ReadValue<uint16_t>(File, Total);
215  if (Total > 0 && !bFramePrinted)
216  {
217  PrintFrame(Info);
218  bFramePrinted = true;
219  }
220  Info << " State traffic lights: " << Total << std::endl;
221  for (i = 0; i < Total; ++i)
222  {
223  StateTraffic.Read(File);
224  Info << " Id: " << StateTraffic.DatabaseId << " state: " << static_cast<char>(0x30 + StateTraffic.State) << " frozen: " <<
225  StateTraffic.IsFrozen << " elapsedTime: " << StateTraffic.ElapsedTime << std::endl;
226  }
227  }
228  else
229  SkipPacket();
230  break;
231 
232  // vehicle animations
233  case static_cast<char>(CarlaRecorderPacketId::AnimVehicle):
234  if (bShowAll)
235  {
236  ReadValue<uint16_t>(File, Total);
237  if (Total > 0 && !bFramePrinted)
238  {
239  PrintFrame(Info);
240  bFramePrinted = true;
241  }
242  Info << " Vehicle animations: " << Total << std::endl;
243  for (i = 0; i < Total; ++i)
244  {
245  Vehicle.Read(File);
246  Info << " Id: " << Vehicle.DatabaseId << " Steering: " << Vehicle.Steering << " Throttle: " << Vehicle.Throttle << " Brake: " << Vehicle.Brake << " Handbrake: " << Vehicle.bHandbrake << " Gear: " << Vehicle.Gear << std::endl;
247  }
248  }
249  else
250  SkipPacket();
251  break;
252 
253  // walker animations
254  case static_cast<char>(CarlaRecorderPacketId::AnimWalker):
255  if (bShowAll)
256  {
257  ReadValue<uint16_t>(File, Total);
258  if (Total > 0 && !bFramePrinted)
259  {
260  PrintFrame(Info);
261  bFramePrinted = true;
262  }
263  Info << " Walker animations: " << Total << std::endl;
264  for (i = 0; i < Total; ++i)
265  {
266  Walker.Read(File);
267  Info << " Id: " << Walker.DatabaseId << " speed: " << Walker.Speed << std::endl;
268  }
269  }
270  else
271  SkipPacket();
272  break;
273 
274  // vehicle light animations
275  case static_cast<char>(CarlaRecorderPacketId::VehicleLight):
276  if (bShowAll)
277  {
278  ReadValue<uint16_t>(File, Total);
279  if (Total > 0 && !bFramePrinted)
280  {
281  PrintFrame(Info);
282  bFramePrinted = true;
283  }
284  Info << " Vehicle light animations: " << Total << std::endl;
285  for (i = 0; i < Total; ++i)
286  {
287  LightVehicle.Read(File);
288 
290  FVehicleLightState State(LightState);
291  std::string enabled_lights_list;
292  if (State.Position)
293  enabled_lights_list += "Position ";
294  if (State.LowBeam)
295  enabled_lights_list += "LowBeam ";
296  if (State.HighBeam)
297  enabled_lights_list += "HighBeam ";
298  if (State.Brake)
299  enabled_lights_list += "Brake ";
300  if (State.RightBlinker)
301  enabled_lights_list += "RightBlinker ";
302  if (State.LeftBlinker)
303  enabled_lights_list += "LeftBlinker ";
304  if (State.Reverse)
305  enabled_lights_list += "Reverse ";
306  if (State.Interior)
307  enabled_lights_list += "Interior ";
308  if (State.Fog)
309  enabled_lights_list += "Fog ";
310  if (State.Special1)
311  enabled_lights_list += "Special1 ";
312  if (State.Special2)
313  enabled_lights_list += "Special2 ";
314 
315  if (enabled_lights_list.size())
316  {
317  Info << " Id: " << LightVehicle.DatabaseId << " " <<
318  enabled_lights_list.substr(0, enabled_lights_list.size() - 1) << std::endl;
319  }
320  else
321  {
322  Info << " Id: " << LightVehicle.DatabaseId << " None" << std::endl;
323  }
324  }
325  }
326  else
327  SkipPacket();
328  break;
329 
330  // scene light animations
331  case static_cast<char>(CarlaRecorderPacketId::SceneLight):
332  if (bShowAll)
333  {
334  ReadValue<uint16_t>(File, Total);
335  if (Total > 0 && !bFramePrinted)
336  {
337  PrintFrame(Info);
338  bFramePrinted = true;
339  }
340  Info << " Scene light changes: " << Total << std::endl;
341  for (i = 0; i < Total; ++i)
342  {
343  LightScene.Read(File);
344  Info << " Id: " << LightScene.LightId << " enabled: " << (LightScene.bOn ? "True" : "False")
345  << " intensity: " << LightScene.Intensity
346  << " RGB_color: (" << LightScene.Color.R << ", " << LightScene.Color.G << ", " << LightScene.Color.B << ")"
347  << std::endl;
348  }
349  }
350  else
351  SkipPacket();
352  break;
353 
354  // dynamic actor kinematics
355  case static_cast<char>(CarlaRecorderPacketId::Kinematics):
356  if (bShowAll)
357  {
358  ReadValue<uint16_t>(File, Total);
359  if (Total > 0 && !bFramePrinted)
360  {
361  PrintFrame(Info);
362  bFramePrinted = true;
363  }
364  Info << " Dynamic actors: " << Total << std::endl;
365  for (i = 0; i < Total; ++i)
366  {
367  Kinematics.Read(File);
368  Info << " Id: " << Kinematics.DatabaseId << " linear_velocity: ("
369  << Kinematics.LinearVelocity.X << ", " << Kinematics.LinearVelocity.Y << ", " << Kinematics.LinearVelocity.Z << ")"
370  << " angular_velocity: ("
371  << Kinematics.AngularVelocity.X << ", " << Kinematics.AngularVelocity.Y << ", " << Kinematics.AngularVelocity.Z << ")"
372  << std::endl;
373  }
374  }
375  else
376  SkipPacket();
377  break;
378 
379  // actors bounding boxes
380  case static_cast<char>(CarlaRecorderPacketId::BoundingBox):
381  if (bShowAll)
382  {
383  ReadValue<uint16_t>(File, Total);
384  if (Total > 0 && !bFramePrinted)
385  {
386  PrintFrame(Info);
387  bFramePrinted = true;
388  }
389  Info << " Actor bounding boxes: " << Total << std::endl;
390  for (i = 0; i < Total; ++i)
391  {
392  ActorBoundingBox.Read(File);
393  Info << " Id: " << ActorBoundingBox.DatabaseId << " origin: ("
394  << ActorBoundingBox.BoundingBox.Origin.X << ", "
395  << ActorBoundingBox.BoundingBox.Origin.Y << ", "
397  << " extension: ("
401  << std::endl;
402  }
403  }
404  else
405  SkipPacket();
406  break;
407 
408  // actors trigger volumes
409  case static_cast<char>(CarlaRecorderPacketId::TriggerVolume):
410  if (bShowAll)
411  {
412  ReadValue<uint16_t>(File, Total);
413  if (Total > 0 && !bFramePrinted)
414  {
415  PrintFrame(Info);
416  bFramePrinted = true;
417  }
418  Info << " Actor trigger volumes: " << Total << std::endl;
419  for (i = 0; i < Total; ++i)
420  {
421  ActorBoundingBox.Read(File);
422  Info << " Id: " << ActorBoundingBox.DatabaseId << " origin: ("
423  << ActorBoundingBox.BoundingBox.Origin.X << ", "
424  << ActorBoundingBox.BoundingBox.Origin.Y << ", "
426  << " extension: ("
430  << std::endl;
431  }
432  }
433  else
434  SkipPacket();
435  break;
436 
437  // Platform time
438  case static_cast<char>(CarlaRecorderPacketId::PlatformTime):
439  if (bShowAll)
440  {
441  if (!bFramePrinted)
442  {
443  PrintFrame(Info);
444  bFramePrinted = true;
445  }
446 
448  Info << " Current platform time: " << PlatformTime.Time << std::endl;
449  }
450  else
451  SkipPacket();
452  break;
453 
454  case static_cast<char>(CarlaRecorderPacketId::PhysicsControl):
455  if (bShowAll)
456  {
457  ReadValue<uint16_t>(File, Total);
458  if (Total > 0 && !bFramePrinted)
459  {
460  PrintFrame(Info);
461  bFramePrinted = true;
462  }
463 
464  Info << " Physics Control events: " << Total << std::endl;
465  for (i = 0; i < Total; ++i)
466  {
467  PhysicsControl.Read(File);
469  Info << " Id: " << PhysicsControl.DatabaseId << std::endl
470  << " max_rpm = " << Control.max_rpm << std::endl
471  << " MOI = " << Control.moi << std::endl
472  << " damping_rate_full_throttle = " << Control.damping_rate_full_throttle << std::endl
473  << " damping_rate_zero_throttle_clutch_engaged = " << Control.damping_rate_zero_throttle_clutch_engaged << std::endl
474  << " damping_rate_zero_throttle_clutch_disengaged = " << Control.damping_rate_zero_throttle_clutch_disengaged << std::endl
475  << " use_gear_auto_box = " << (Control.use_gear_autobox ? "true" : "false") << std::endl
476  << " gear_switch_time = " << Control.gear_switch_time << std::endl
477  << " clutch_strength = " << Control.clutch_strength << std::endl
478  << " final_ratio = " << Control.final_ratio << std::endl
479  << " mass = " << Control.mass << std::endl
480  << " drag_coefficient = " << Control.drag_coefficient << std::endl
481  << " center_of_mass = " << "(" << Control.center_of_mass.x << ", " << Control.center_of_mass.y << ", " << Control.center_of_mass.z << ")" << std::endl;
482  Info << " torque_curve =";
483  for (auto& vec : Control.torque_curve)
484  {
485  Info << " (" << vec.x << ", " << vec.y << ")";
486  }
487  Info << std::endl;
488  Info << " steering_curve =";
489  for (auto& vec : Control.steering_curve)
490  {
491  Info << " (" << vec.x << ", " << vec.y << ")";
492  }
493  Info << std::endl;
494  Info << " forward_gears:" << std::endl;
495  uint32_t count = 0;
496  for (auto& Gear : Control.forward_gears)
497  {
498  Info << " gear " << count << ": ratio " << Gear.ratio
499  << " down_ratio " << Gear.down_ratio
500  << " up_ratio " << Gear.up_ratio << std::endl;
501  ++count;
502  }
503  Info << " wheels:" << std::endl;
504  count = 0;
505  for (auto& Wheel : Control.wheels)
506  {
507  Info << " wheel " << count << ": tire_friction " << Wheel.tire_friction
508  << " damping_rate " << Wheel.damping_rate
509  << " max_steer_angle " << Wheel.max_steer_angle
510  << " radius " << Wheel.radius
511  << " max_brake_torque " << Wheel.max_brake_torque
512  << " max_handbrake_torque " << Wheel.max_handbrake_torque
513  << " position " << "(" << Wheel.position.x << ", " << Wheel.position.y << ", " << Wheel.position.z << ")"
514  << std::endl;
515  ++count;
516  }
517  }
518  }
519  else
520  SkipPacket();
521  break;
522 
523  case static_cast<char>(CarlaRecorderPacketId::TrafficLightTime):
524  if (bShowAll)
525  {
526  ReadValue<uint16_t>(File, Total);
527  if (Total > 0 && !bFramePrinted)
528  {
529  PrintFrame(Info);
530  bFramePrinted = true;
531  }
532 
533  Info << " Traffic Light time events: " << Total << std::endl;
534  for (i = 0; i < Total; ++i)
535  {
536  TrafficLightTime.Read(File);
537  Info << " Id: " << TrafficLightTime.DatabaseId
538  << " green_time: " << TrafficLightTime.GreenTime
539  << " yellow_time: " << TrafficLightTime.YellowTime
540  << " red_time: " << TrafficLightTime.RedTime
541  << std::endl;
542  }
543  }
544  else
545  SkipPacket();
546  break;
547 
548  case static_cast<char>(CarlaRecorderPacketId::WalkerBones):
549  if (bShowAll)
550  {
551  ReadValue<uint16_t>(File, Total);
552  if (Total > 0 && !bFramePrinted)
553  {
554  PrintFrame(Info);
555  bFramePrinted = true;
556  }
557 
558  Info << " Walkers Bones: " << Total << std::endl;
559  for (i = 0; i < Total; ++i)
560  {
561  WalkerBones.Clear();
562  WalkerBones.Read(File);
563  Info << " Id: " << WalkerBones.DatabaseId << "\n";
564  for (const auto &Bone : WalkerBones.Bones)
565  {
566  Info << " Bone: \"" << TCHAR_TO_UTF8(*Bone.Name) << "\" relative: " << "Loc("
567  << Bone.Location.X << ", " << Bone.Location.Y << ", " << Bone.Location.Z << ") Rot("
568  << Bone.Rotation.X << ", " << Bone.Rotation.Y << ", " << Bone.Rotation.Z << ")\n";
569  }
570  }
571  Info << std::endl;
572  }
573  else
574  SkipPacket();
575  break;
576 
577  // frame end
578  case static_cast<char>(CarlaRecorderPacketId::FrameEnd):
579  // do nothing, it is empty
580  break;
581 
582  default:
583  SkipPacket();
584  break;
585  }
586  }
587 
588  Info << "\nFrames: " << Frame.Id << "\n";
589  Info << "Duration: " << Frame.Elapsed << " seconds\n";
590 
591  File.close();
592 
593  return Info.str();
594 }
595 
596 std::string CarlaRecorderQuery::QueryCollisions(std::string Filename, char Category1, char Category2)
597 {
598  std::stringstream Info;
599 
600  // get the final path + filename
601  std::string Filename2 = GetRecorderFilename(Filename);
602 
603  // try to open
604  File.open(Filename2, std::ios::binary);
605  if (!File.is_open())
606  {
607  Info << "File " << Filename2 << " not found on server\n";
608  return Info.str();
609  }
610 
611  if (!CheckFileInfo(Info))
612  return Info.str();
613 
614  // other, vehicle, walkers, trafficLight, hero, any
615  char Categories[] = { 'o', 'v', 'w', 't', 'h', 'a' };
616  uint16_t i, Total;
617  struct ReplayerActorInfo
618  {
619  uint8_t Type;
620  FString Id;
621  };
622  std::unordered_map<uint32_t, ReplayerActorInfo> Actors;
623  struct PairHash
624  {
625  std::size_t operator()(const std::pair<uint32_t, uint32_t>& P) const
626  {
627  std::size_t hash = P.first;
628  hash <<= 32;
629  hash += P.second;
630  return hash;
631  }
632  };
633  std::unordered_set<std::pair<uint32_t, uint32_t>, PairHash > oldCollisions, newCollisions;
634 
635  // header
636  Info << std::setw(8) << "Time";
637  Info << " " << std::setw(6) << "Types";
638  Info << " " << std::setw(6) << std::right << "Id";
639  Info << " " << std::setw(35) << std::left << "Actor 1";
640  Info << " " << std::setw(6) << std::right << "Id";
641  Info << " " << std::setw(35) << std::left << "Actor 2";
642  Info << std::endl;
643 
644  // parse only frames
645  while (File)
646  {
647 
648  // get header
649  if (!ReadHeader())
650  {
651  break;
652  }
653 
654  // check for a frame packet
655  switch (Header.Id)
656  {
657  // frame
658  case static_cast<char>(CarlaRecorderPacketId::FrameStart):
659  Frame.Read(File);
660  // exchange sets of collisions (to know when a collision is new or continue from previous frame)
661  oldCollisions = std::move(newCollisions);
662  newCollisions.clear();
663  break;
664 
665  // events add
666  case static_cast<char>(CarlaRecorderPacketId::EventAdd):
667  ReadValue<uint16_t>(File, Total);
668  for (i = 0; i < Total; ++i)
669  {
670  // add
671  EventAdd.Read(File);
672  Actors[EventAdd.DatabaseId] = ReplayerActorInfo { EventAdd.Type, EventAdd.Description.Id };
673  }
674  break;
675 
676  // events del
677  case static_cast<char>(CarlaRecorderPacketId::EventDel):
678  ReadValue<uint16_t>(File, Total);
679  for (i = 0; i < Total; ++i)
680  {
681  EventDel.Read(File);
682  Actors.erase(EventAdd.DatabaseId);
683  }
684  break;
685 
686  // events parenting
687  case static_cast<char>(CarlaRecorderPacketId::EventParent):
688  SkipPacket();
689  break;
690 
691  // collisions
692  case static_cast<char>(CarlaRecorderPacketId::Collision):
693  ReadValue<uint16_t>(File, Total);
694  for (i = 0; i < Total; ++i)
695  {
697 
698  int Valid = 0;
699 
700  // get categories for both actors
701  uint8_t Type1, Type2;
702  if (Collision.DatabaseId1 != uint32_t(-1))
703  Type1 = Categories[Actors[Collision.DatabaseId1].Type];
704  else
705  Type1 = 'o'; // other non-actor object
706 
707  if (Collision.DatabaseId2 != uint32_t(-1))
708  Type2 = Categories[Actors[Collision.DatabaseId2].Type];
709  else
710  Type2 = 'o'; // other non-actor object
711 
712  // filter actor 1
713  if (Category1 == 'a')
714  ++Valid;
715  else if (Category1 == Type1)
716  ++Valid;
717  else if (Category1 == 'h' && Collision.IsActor1Hero)
718  ++Valid;
719 
720  // filter actor 2
721  if (Category2 == 'a')
722  ++Valid;
723  else if (Category2 == Type2)
724  ++Valid;
725  else if (Category2 == 'h' && Collision.IsActor2Hero)
726  ++Valid;
727 
728  // only show if both actors has passed the filter
729  if (Valid == 2)
730  {
731  // check if we need to show as a starting collision or it is a continuation one
732  auto collisionPair = std::make_pair(Collision.DatabaseId1, Collision.DatabaseId2);
733  if (oldCollisions.count(collisionPair) == 0)
734  {
735  Info << std::setw(8) << std::setprecision(0) << std::right << std::fixed << Frame.Elapsed;
736  Info << " " << " " << Type1 << " " << Type2 << " ";
737  Info << " " << std::setw(6) << std::right << Collision.DatabaseId1;
738  Info << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Collision.DatabaseId1].Id);
739  Info << " " << std::setw(6) << std::right << Collision.DatabaseId2;
740  Info << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Collision.DatabaseId2].Id);
741  Info << std::endl;
742  }
743  // save current collision
744  newCollisions.insert(collisionPair);
745  }
746  }
747  break;
748 
749  case static_cast<char>(CarlaRecorderPacketId::Position):
750  SkipPacket();
751  break;
752 
753  case static_cast<char>(CarlaRecorderPacketId::State):
754  SkipPacket();
755  break;
756 
757  // frame end
758  case static_cast<char>(CarlaRecorderPacketId::FrameEnd):
759  // do nothing, it is empty
760  break;
761 
762  default:
763  SkipPacket();
764  break;
765  }
766  }
767 
768  Info << "\nFrames: " << Frame.Id << "\n";
769  Info << "Duration: " << Frame.Elapsed << " seconds\n";
770 
771  File.close();
772 
773  return Info.str();
774 }
775 
776 std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTime, double MinDistance)
777 {
778  std::stringstream Info;
779 
780  // get the final path + filename
781  std::string Filename2 = GetRecorderFilename(Filename);
782 
783  // try to open
784  File.open(Filename2, std::ios::binary);
785  if (!File.is_open())
786  {
787  Info << "File " << Filename2 << " not found on server\n";
788  return Info.str();
789  }
790 
791  if (!CheckFileInfo(Info))
792  return Info.str();
793 
794  // other, vehicle, walkers, trafficLight, hero, any
795  uint16_t i, Total;
796  struct ReplayerActorInfo
797  {
798  uint8_t Type;
799  FString Id;
800  FVector LastPosition;
801  double Time;
802  double Duration;
803  };
804  std::unordered_map<uint32_t, ReplayerActorInfo> Actors;
805  // to be able to sort the results by the duration of each actor (decreasing order)
806  std::multimap<double, std::string, std::greater<double>> Results;
807 
808  // header
809  Info << std::setw(8) << "Time";
810  Info << " " << std::setw(6) << "Id";
811  Info << " " << std::setw(35) << std::left << "Actor";
812  Info << " " << std::setw(10) << std::right << "Duration";
813  Info << std::endl;
814 
815  // parse only frames
816  while (File)
817  {
818 
819  // get header
820  if (!ReadHeader())
821  {
822  break;
823  }
824 
825  // check for a frame packet
826  switch (Header.Id)
827  {
828  // frame
829  case static_cast<char>(CarlaRecorderPacketId::FrameStart):
830  Frame.Read(File);
831  break;
832 
833  // events add
834  case static_cast<char>(CarlaRecorderPacketId::EventAdd):
835  ReadValue<uint16_t>(File, Total);
836  for (i = 0; i < Total; ++i)
837  {
838  // add
839  EventAdd.Read(File);
840  Actors[EventAdd.DatabaseId] = ReplayerActorInfo { EventAdd.Type, EventAdd.Description.Id, FVector(0, 0, 0), 0.0, 0.0 };
841  }
842  break;
843 
844  // events del
845  case static_cast<char>(CarlaRecorderPacketId::EventDel):
846  ReadValue<uint16_t>(File, Total);
847  for (i = 0; i < Total; ++i)
848  {
849  EventDel.Read(File);
850  Actors.erase(EventAdd.DatabaseId);
851  }
852  break;
853 
854  // events parenting
855  case static_cast<char>(CarlaRecorderPacketId::EventParent):
856  SkipPacket();
857  break;
858 
859  // collisions
860  case static_cast<char>(CarlaRecorderPacketId::Collision):
861  SkipPacket();
862  break;
863 
864  // positions
865  case static_cast<char>(CarlaRecorderPacketId::Position):
866  // read all positions
867  ReadValue<uint16_t>(File, Total);
868  for (i=0; i<Total; ++i)
869  {
870  Position.Read(File);
871  // check if actor moved less than a distance
872  if (FVector::Distance(Actors[Position.DatabaseId].LastPosition, Position.Location) < MinDistance)
873  {
874  // actor stopped
875  if (Actors[Position.DatabaseId].Duration == 0)
876  Actors[Position.DatabaseId].Time = Frame.Elapsed;
877  Actors[Position.DatabaseId].Duration += Frame.DurationThis;
878  }
879  else
880  {
881  // check to show info
882  if (Actors[Position.DatabaseId].Duration >= MinTime)
883  {
884  std::stringstream Result;
885  Result << std::setw(8) << std::setprecision(0) << std::fixed << Actors[Position.DatabaseId].Time;
886  Result << " " << std::setw(6) << Position.DatabaseId;
887  Result << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Position.DatabaseId].Id);
888  Result << " " << std::setw(10) << std::setprecision(0) << std::fixed << std::right << Actors[Position.DatabaseId].Duration;
889  Result << std::endl;
890  Results.insert(std::make_pair(Actors[Position.DatabaseId].Duration, Result.str()));
891  }
892  // actor moving
893  Actors[Position.DatabaseId].Duration = 0;
894  Actors[Position.DatabaseId].LastPosition = Position.Location;
895  }
896  }
897  break;
898 
899  // traffic light
900  case static_cast<char>(CarlaRecorderPacketId::State):
901  SkipPacket();
902  break;
903 
904  // frame end
905  case static_cast<char>(CarlaRecorderPacketId::FrameEnd):
906  // do nothing, it is empty
907  break;
908 
909  default:
910  SkipPacket();
911  break;
912  }
913  }
914 
915  // show actors stopped that were not moving again
916  for (auto &Actor : Actors)
917  {
918  // check to show info
919  if (Actor.second.Duration >= MinTime)
920  {
921  std::stringstream Result;
922  Result << std::setw(8) << std::setprecision(0) << std::fixed << Actor.second.Time;
923  Result << " " << std::setw(6) << Actor.first;
924  Result << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actor.second.Id);
925  Result << " " << std::setw(10) << std::setprecision(0) << std::fixed << std::right << Actor.second.Duration;
926  Result << std::endl;
927  Results.insert(std::make_pair(Actor.second.Duration, Result.str()));
928  }
929  }
930 
931  // show the result
932  for (auto &Result : Results)
933  {
934  Info << Result.second;
935  }
936 
937  Info << "\nFrames: " << Frame.Id << "\n";
938  Info << "Duration: " << Frame.Elapsed << " seconds\n";
939 
940  File.close();
941 
942  return Info.str();
943 }
CarlaRecorderPosition Position
CarlaRecorderStateTrafficLight StateTraffic
CarlaRecorderBoundingBox BoundingBox
void Read(std::istream &InFile)
bool CheckFileInfo(std::stringstream &Info)
void Read(std::istream &InFile)
CarlaRecorderCollision Collision
CarlaRecorderActorBoundingBox ActorBoundingBox
void Read(std::istream &InFile)
std::string QueryBlocked(std::string Filename, double MinTime=30, double MinDistance=10)
void Read(std::istream &InFile)
CarlaRecorderEventDel EventDel
std::string QueryCollisions(std::string Filename, char Category1='a', char Category2='a')
void Read(std::ifstream &InFile)
carla::SharedPtr< cc::Actor > Actor
void Read(std::istream &InFile)
void Read(std::istream &InFile)
void Read(std::istream &File)
std::string QueryInfo(std::string Filename, bool bShowAll=false)
std::vector< CarlaRecorderActorAttribute > Attributes
CarlaRecorderWalkerBones WalkerBones
CarlaRecorderEventAdd EventAdd
void Read(std::istream &InFile)
CarlaRecorderKinematics Kinematics
CarlaRecorderLightVehicle LightVehicle
CarlaRecorderPhysicsControl PhysicsControl
CarlaRecorderInfo RecInfo
CarlaRecorderPlatformTime PlatformTime
CarlaRecorderLightScene LightScene
CarlaRecorderFrame Frame
CarlaRecorderEventParent EventParent
std::string GetRecorderFilename(std::string Filename)
CarlaRecorderAnimVehicle Vehicle
void Read(std::istream &InFile)
CarlaRecorderAnimWalker Walker
CarlaRecorderTrafficLightTime TrafficLightTime
Defines the physical appearance of a vehicle whitch is obtained by the sensors.
std::vector< CarlaRecorderWalkerBone > Bones
void Read(std::istream &InFile)
void Read(std::istream &InFile)
FVehiclePhysicsControl VehiclePhysicsControl
void Read(std::istream &InFile)
CarlaRecorderActorDescription Description
void Read(std::istream &InFile)
void Read(std::istream &InFile)