CartographerAdapter.cpp
Go to the documentation of this file.
1 #include "CartographerAdapter.h"
2 
3 // STL
4 #include <algorithm>
5 #include <cmath>
6 #include <cstdlib>
7 #include <ctime>
8 #include <filesystem>
9 #include <functional>
10 #include <iterator>
11 #include <memory>
12 #include <mutex>
13 #include <optional>
14 #include <stdexcept>
15 #include <string>
16 
17 // Eigen
18 #include <Eigen/Core>
19 #include <Eigen/Geometry>
20 
21 // Ice
22 #include <IceUtil/Time.h>
23 
24 // PCL
25 #include <pcl/common/transforms.h>
26 #include <pcl/io/pcd_io.h>
27 #include <pcl/point_cloud.h>
28 #include <pcl/point_types.h>
29 
30 // OpenCV
31 #include <opencv2/core/mat.hpp>
32 #include <opencv2/imgcodecs.hpp>
33 
34 // Simox
35 #include <SimoxUtility/algorithm/string/string_tools.h>
36 #include <SimoxUtility/json/json.hpp>
37 #include <SimoxUtility/math.h>
38 
39 // ArmarX
44 
45 // RobotComponents
47 
48 // cartographer (this has to come last!)
49 #include <cartographer/common/configuration_file_resolver.h>
50 #include <cartographer/common/time.h>
51 #include <cartographer/io/file_writer.h>
52 #include <cartographer/io/points_processor_pipeline_builder.h>
53 #include <cartographer/io/proto_stream.h>
54 #include <cartographer/mapping/2d/grid_2d.h>
55 #include <cartographer/mapping/2d/probability_grid.h>
56 #include <cartographer/mapping/2d/submap_2d.h>
57 #include <cartographer/mapping/internal/2d/tsdf_2d.h>
58 #include <cartographer/mapping/map_builder.h>
59 #include <cartographer/mapping/map_builder_interface.h>
60 #include <cartographer/mapping/submaps.h>
61 #include <cartographer/mapping/trajectory_builder_interface.h>
62 #include <cartographer/mapping/trajectory_node.h>
63 #include <cartographer/sensor/point_cloud.h>
64 #include <cartographer/sensor/rangefinder_point.h>
65 #include <cartographer/transform/rigid_transform.h>
66 #include <cartographer/transform/transform.h>
67 
68 // this library
69 #include "ApproximateTimeQueue.h"
70 #include "ArVizDrawer.h"
71 #include "grid_conversion.h"
72 #include "types.h"
74 #include "util/eigen_conversions.h"
75 #include "util/laser_scanner_conversion.h"
76 #include "util/pcl_conversions.h"
77 
78 namespace carto = ::cartographer;
79 
80 constexpr int SCALE_M_TO_MM = 1000;
81 
82 namespace fs = ::std::filesystem;
83 
84 std::string
86 {
87  // http://www.cplusplus.com/reference/ctime/strftime/
88 
89  time_t rawtime{};
90  struct tm* timeinfo{};
91  std::array<char, 4 + 1 + 2 + 1 + 2 + 1 + 2 + 1 + 2 + 1> buffer;
92 
93  time(&rawtime);
94  timeinfo = localtime(&rawtime);
95 
96  strftime(buffer.data(), buffer.size(), "%Y-%m-%d-%H-%M", timeinfo);
97 
98  std::string timestamp(buffer.data());
99  return timestamp;
100 }
101 
103 {
104 
106  {
107  ARMARX_TRACE;
108 
109  ARMARX_INFO << "Finishing cartographer";
110  mapBuilder->FinishTrajectory(trajectoryId);
111 
112  ARMARX_INFO << "Releasing cartographer";
113  mapBuilder.reset();
114 
115  ARMARX_INFO << "Done";
116  }
117 
119  const std::filesystem::path& mapPath,
120  const std::filesystem::path& configPath,
121  SlamDataCallable& slamDataCallable,
122  const Config& config,
123  const std::optional<std::filesystem::path>& mapToLoad,
124  const std::optional<Eigen::Isometry3f>& map_T_robot_prior,
125  const DebugObserverInterfacePrx& debugObserver) :
126  config(config), mapPath(mapPath), slamDataCallable(slamDataCallable)
127  {
128  ARMARX_TRACE;
129  const std::string mapBuilderLuaCode = R"text(
130  include "map_builder.lua"
131  return MAP_BUILDER)text";
132 
133  const std::string trajectoryBuilderLuaCode = R"text(
134  include "trajectory_builder.lua"
135  return TRAJECTORY_BUILDER)text";
136 
137  const auto mapBuilderParameters = util::resolveLuaParameters(mapBuilderLuaCode, configPath);
138  auto mapBuilderOptions =
139  carto::mapping::CreateMapBuilderOptions(mapBuilderParameters.get());
140 
141 
142  if (config.global_localization_min_score > 0)
143  {
144  ARMARX_INFO << "Setting `global_localization_min_score` to "
146  mapBuilderOptions.mutable_pose_graph_options()
147  ->mutable_constraint_builder_options()
148  ->set_global_localization_min_score(config.global_localization_min_score);
149  }
150 
151  if (config.min_score > 0)
152  {
153  ARMARX_INFO << "Setting `min_score` to " << config.min_score;
154  mapBuilderOptions.mutable_pose_graph_options()
155  ->mutable_constraint_builder_options()
156  ->set_min_score(config.min_score);
157  }
158 
159  const auto trajectoryBuilderParameters =
160  util::resolveLuaParameters(trajectoryBuilderLuaCode, configPath);
161  trajectoryBuilderOptions =
162  carto::mapping::CreateTrajectoryBuilderOptions(trajectoryBuilderParameters.get());
163 
164  // create map builder
165  mapBuilder = carto::mapping::CreateMapBuilder(mapBuilderOptions);
166 
167  if (config.useLaserScanner)
168  {
169  sensorSet.insert(sensorIdLaser);
170  }
171 
172  if (config.useOdometry)
173  {
174  sensorSet.insert(sensorIdOdom);
175  }
176 
177  if (config.useImu)
178  {
179  sensorSet.insert(sensorIdIMU);
180  }
181 
182  std::vector<std::string> sensorSetNames;
183  std::transform(sensorSet.begin(),
184  sensorSet.end(),
185  std::back_inserter(sensorSetNames),
186  [](const auto& sensorId) { return sensorId.id; });
187 
188  ARMARX_IMPORTANT << "Sensor set '" << sensorSetNames << "' will be used";
189 
190  if (config.useLaserScanner)
191  {
192  ARMARX_IMPORTANT << "This includes the following laser scanners: "
193  << std::vector<std::string>(config.laserScanners.begin(),
194  config.laserScanners.end());
195 
196  std::for_each(config.laserScanners.begin(),
197  config.laserScanners.end(),
198  [&](const auto& laserScannerName)
199  {
200  const SensorId sensorId{.type = SensorId::SensorType::RANGE,
201  .id = laserScannerName};
202  laserSensorMap.insert(
203  {laserScannerName,
204  LaserScannerSensor(sensorId, Eigen::Isometry3f::Identity())});
205  });
206  }
207 
208 
209  if (mapToLoad)
210  {
211  ARMARX_TRACE;
212  ARMARX_DEBUG << "Loading map";
213  carto::io::ProtoStreamReader reader(mapToLoad->string());
214  mapBuilder->LoadState(&reader, true /* load_frozen_state */);
215  mapBuilder->pose_graph()->RunFinalOptimization();
216 
217 
218  if (map_T_robot_prior)
219  {
220  ARMARX_INFO << "Using pose prior \n" << map_T_robot_prior->matrix();
221 
222  ::cartographer::mapping::proto::InitialTrajectoryPose* initial_trajectory_pose =
223  new ::cartographer::mapping::proto::InitialTrajectoryPose;
224 
225  initial_trajectory_pose->set_allocated_relative_pose(
226  new ::cartographer::transform::proto::Rigid3d(
227  ::cartographer::transform::ToProto(fromEigen(*map_T_robot_prior))));
228 
229  trajectoryBuilderOptions.set_allocated_initial_trajectory_pose(
230  std::move(initial_trajectory_pose)); // owner -> trajectoryBuilderOptions
231  }
232  }
233 
234 
235  trajectoryId = mapBuilder->AddTrajectoryBuilder(
236  sensorSet,
237  trajectoryBuilderOptions,
238  [this](auto&&... args)
239  { return getLocalSlamResultCallback(std::forward<decltype(args)>(args)...); });
240 
241  // TODO(fabian.reister): variable sensor set
242  const auto dt = static_cast<int64_t>(1'000'000 / config.frequency);
243  const float dtHistoryLength = 1'000'000;
244 
245  ARMARX_IMPORTANT << "Frequency: " << config.frequency << ", dt: " << dt;
246 
247  approxTimeQueue =
248  std::make_unique<ApproximateTimeQueue>(dt,
249  dtHistoryLength,
250  config.laserScanners,
251  *this,
252  config.useOdometryBasedLaserCorrection);
253 
254  if (debugObserver)
255  {
256  ARMARX_TRACE;
257  ARMARX_IMPORTANT << "Debug observer is set";
258  cartographerInputDataReporterLaserScanner.emplace(
259  debugObserver, "CartographerMappingAndLocalization_input_laser");
260  cartographerInputDataReporterOdometry.emplace(
261  debugObserver, "CartographerMappingAndLocalization_input_odom");
262  if (config.enableDebugTiming)
263  {
264  debugObserverHelper.emplace(
265  "CartographerMappingAndLocalization_CartographerAdapter", debugObserver, true);
266  }
267  }
268  }
269 
270  void
271  CartographerAdapter::onTimedDataAvailable(const TimedData& data)
272  {
273  ARMARX_TRACE;
274  pushInOdomData(data.odomPose);
275  pushInLaserData(data.laserData);
276  if (debugObserverHelper)
277  {
278  ARMARX_TRACE;
279  std::unique_lock g(debugObserverHelperMtx);
280  debugObserverHelper->sendDebugObserverBatch();
281  }
282  }
283 
284  void
285  CartographerAdapter::pushInOdomData(
287  {
288  ARMARX_TRACE;
289  const DebugObserverScopedTimer timer(this, "pushInOdomData | Entire Method");
290  if (lastOdomTimestamp.has_value())
291  {
292  ARMARX_TRACE;
293  if (odomPose.timestamp <= lastOdomTimestamp.value())
294  {
296  << "Requested to add old data into odom queue. Not willing to do this. It is "
297  << (odomPose.timestamp - lastOdomTimestamp.value()) << "ms in the past.";
298  return;
299  }
300  }
301 
302  lastOdomTimestamp = odomPose.timestamp;
303 
304  const auto& timestamp = odomPose.timestamp;
305  ARMARX_DEBUG << "New odom pose received " << timestamp;
306 
307  auto isOdomSensor = [](const SensorId& sensorId)
308  { return sensorId.type == SensorId::SensorType::ODOMETRY; };
309 
310  if (not std::any_of(sensorSet.begin(), sensorSet.end(), isOdomSensor))
311  {
312  ARMARX_TRACE;
313  ARMARX_WARNING << "No odometry sensor is registered. Will not use odometry data.";
314  ARMARX_DEBUG << deactivateSpam(2.) << "Odometry will not be used";
315  return;
316  }
317 
318  ARMARX_DEBUG << "Processing odom pose";
319 
320  const Eigen::Quaternionf q(odomPose.pose.linear());
321  const Eigen::Vector3f p = odomPose.pose.translation();
322 
323  carto::sensor::OdometryData odomData;
324  odomData.pose =
325  carto::transform::Rigid3d::FromArrays(std::array<double, 4>{q.w(), q.x(), q.y(), q.z()},
326  std::array<double, 3>{p.x(), p.y(), p.z()});
327  odomData.time = util::toCarto(timestamp);
328 
329  ARMARX_VERBOSE << "Will now insert odom data";
330 
331  {
332  ARMARX_TRACE;
333  const DebugObserverScopedTimer localTimer(this, "pushInOdomData | Inserting Odom Data");
334  std::lock_guard guard{cartoInsertMtx};
335 
336  mapBuilder->GetTrajectoryBuilder(trajectoryId)
337  ->AddSensorData(sensorIdOdom.id, odomData);
338  }
339 
340  if (cartographerInputDataReporterOdometry.has_value())
341  {
342  ARMARX_TRACE;
343  cartographerInputDataReporterOdometry->add(timestamp);
344  }
345 
346  ARMARX_DEBUG << "Inserted odom data";
347  }
348 
349  void
350  CartographerAdapter::pushInLaserData(const LaserMessages& laserMessages)
351  {
352  ARMARX_TRACE;
353 
354  if (not config.useLaserScanner)
355  {
356  ARMARX_INFO << deactivateSpam(100) << "Not considering laser scanner data.";
357  return;
358  }
359 
360  const DebugObserverScopedTimer timer(this, "pushInLaserData | Entire Method");
361  carto::sensor::TimedPointCloudData timedPointCloudData;
362  timedPointCloudData.origin = Eigen::Vector3f::Zero();
363 
364  {
365  ARMARX_TRACE;
366  const DebugObserverScopedTimer laserMessageTimer(
367  this, "pushInLaserData | Iterate over laser messages");
368  for (const auto& message : laserMessages)
369  {
370  const auto& data = message.data;
371 
372  ARMARX_VERBOSE << "pushInLaserData" << data.scan.size() << " for "
373  << message.data.frame;
374 
375  // validate timestamp
376  {
377  // First iteration: lastTimestamp will be created and initialized to 0
378  auto& lastTimestamp = lastSensorDataTimestamp[data.frame];
379 
380  if (data.timestamp <= lastTimestamp)
381  {
382  ARMARX_DEBUG << "Requested to add old data with timestamp "
383  << data.timestamp << " into laser queue for sensor "
384  << data.frame << ". Not willing to do this. It is "
385  << (data.timestamp - lastTimestamp) << "ms in the past.";
386  return;
387  }
388 
389  lastTimestamp = data.timestamp;
390  }
391 
392  // assumption: all points from single sensor
393  Eigen::Isometry3f robot_T_sensor;
394  try
395  {
396  const LaserScannerSensor sensor = lookupSensor(data.frame);
397  ARMARX_DEBUG << "Sensor " << data.frame << " position is "
398  << sensor.pose.translation();
399 
400  robot_T_sensor = sensor.pose;
401  }
402  catch (const armarx::LocalException&)
403  {
404  ARMARX_INFO << "Sensor `" << data.frame << "` not found in sensor set.";
405  return;
406  }
407 
408  // [m]
409 
410  {
411  const DebugObserverScopedTimer localTimer(
412  this, "pushInLaserData | Reserve TimedPointCloudData");
413  timedPointCloudData.time =
414  util::toCarto(data.timestamp); // universal is in 100ns
415  timedPointCloudData.ranges.reserve(timedPointCloudData.ranges.size() +
416  data.scan.size());
417  }
418  ARMARX_DEBUG << "Laser range data: " << data.scan.size() << " points";
419 
420  {
421  const DebugObserverScopedTimer localTimer(
422  this, "pushInLaserData | Transform to TimedPointCloudData");
423  std::transform(data.scan.begin(),
424  data.scan.end(),
425  std::back_inserter(timedPointCloudData.ranges),
426  [&](const auto& scanStep) -> carto::sensor::TimedRangefinderPoint
427  {
428  auto rangePoint =
429  toCartesian<Eigen::Vector3f>(scanStep); // [mm]
430  rangePoint /= 1000; // [mm] -> [m]
431 
432  carto::sensor::TimedRangefinderPoint point;
433  // point.position = robot_time_correction_T_sensor* rangePoint;
434  point.position = robot_T_sensor * rangePoint;
435  point.time = .0; // relative measurement time (not known)
436  return point;
437  });
438  }
439  }
440  }
441 
442  auto cloud = toPCL(timedPointCloudData.ranges);
443  {
444  const DebugObserverScopedTimer localTimer(this, "pushInLaserData | onLaserSensorData");
445  ARMARX_VERBOSE << VAROUT(cloud.size());
446  slamDataCallable.onLaserSensorData({util::fromCarto(timedPointCloudData.time), cloud});
447  }
448  {
449  ARMARX_TRACE;
450  const DebugObserverScopedTimer localTimer(this,
451  "pushInLaserData | Inserting Laser Data");
452  std::lock_guard guard{cartoInsertMtx};
453 
454  auto* trajBuilder = mapBuilder->GetTrajectoryBuilder(trajectoryId);
455  if (trajBuilder == nullptr)
456  {
457  ARMARX_WARNING << "No trajectory builder.";
458  return;
459  }
460 
461  const std::int64_t laserScannerInsertCartoTimestamp =
462  timedPointCloudData.time.time_since_epoch().count();
463 
464  ARMARX_DEBUG << "Inserting " << sensorIdLaser.id << " with timestamp "
465  << laserScannerInsertCartoTimestamp;
466 
467  if (lastLaserScannerInsertCartoTimestamp.has_value())
468  {
469  if (laserScannerInsertCartoTimestamp <= lastLaserScannerInsertCartoTimestamp)
470  {
471  ARMARX_INFO << "Received laser scanner data out of order. Will not handle it.";
472  return;
473  }
474  }
475 
476  lastLaserScannerInsertCartoTimestamp = laserScannerInsertCartoTimestamp;
477 
478  {
479  const DebugObserverScopedTimer addSensorDataTimer(
480  this, "pushInLaserData | Add Sensor Data to TrajectoryBuilder");
481  ARMARX_VERBOSE << VAROUT(timedPointCloudData.ranges.size());
482  trajBuilder->AddSensorData(sensorIdLaser.id, timedPointCloudData);
483  }
484 
485  if (cartographerInputDataReporterLaserScanner)
486  {
487  cartographerInputDataReporterLaserScanner->add(
488  Duration::MicroSeconds(util::fromCarto(timedPointCloudData.time)));
489  }
490  }
491 
492 
493  ARMARX_DEBUG << "Inserted laser data";
494  }
495 
496  void
497  CartographerAdapter::processOdometryPose(OdomData odom)
498  {
499  ARMARX_TRACE;
500  const DebugObserverScopedTimer timer(this, "processOdometryPose | Entire Method");
502 
503  odomPose.timestamp = odom.timestamp;
504  odomPose.pose.setIdentity();
505  odomPose.pose.translation() = odom.position;
506  odomPose.pose.linear() = odom.orientation.toRotationMatrix();
507 
508  approxTimeQueue->insertOdomData(std::move(odomPose));
509  }
510 
511  void
512  CartographerAdapter::processSensorValues(LaserScannerMessage data)
513  {
514  ARMARX_TRACE;
515  const DebugObserverScopedTimer timer(this, "processSensorValues | Entire Method");
516  ARMARX_DEBUG << "processing sensor values (intro)";
517 
518 
519  // auto isSensorRegistered = [&](const std::string& sensorId)
520  // {
521  // return std::any_of(sensorSet.begin(),
522  // sensorSet.end(),
523  // [&sensorId](const SensorId& id) -> bool
524  // { return id.id == sensorId; });
525  // };
526 
527  // if (not isSensorRegistered(data.frame))
528  // {
529  // ARMARX_VERBOSE << deactivateSpam(1.0) << "Sensor " << data.frame << " not registered. Registered sensors: " << sensorSet;
530  // return;
531  // }
532 
533  ARMARX_CHECK_NOT_NULL(approxTimeQueue);
534  approxTimeQueue->insertLaserData(std::move(data));
535  }
536 
537  void
538  CartographerAdapter::getLocalSlamResultCallback(
539  const int trajectoryId,
541  const ::cartographer::transform::Rigid3d localPose,
542  ::cartographer::sensor::RangeData rangeDataInLocal,
543  const std::unique_ptr<
544  const ::cartographer::mapping::TrajectoryBuilderInterface::InsertionResult>
545  insertion_result)
546  {
547  ARMARX_TRACE;
548  const DebugObserverScopedTimer timer(this, "getLocalSlamResultCallback | Entire Method");
549  // std::lock_guard g{cartoInsertMtx};
550 
551  ARMARX_DEBUG << "Callback (getLocalSlamResultCallback)";
552 
553 
554  // std::lock_guard g{cartoInsertMtx};
555 
556  // const auto constraints = mapBuilder->pose_graph()->constraints();
557  // ARMARX_DEBUG << "number of contraints: " << constraints.size();
558 
559  // const size_t nConstraintsInter = std::count_if(
560  // constraints.begin(),
561  // constraints.end(),
562  // [](const ::cartographer::mapping::PoseGraphInterface::Constraint & constraint)
563  // {
564  // return constraint.tag ==
565  // ::cartographer::mapping::PoseGraphInterface::Constraint::INTER_SUBMAP;
566  // });
567 
568  // ARMARX_DEBUG << "Inter submap constraints: " << nConstraintsInter;
569 
570  LocalSlamData localSlamData;
571 
572  {
573  ARMARX_TRACE;
574  const DebugObserverScopedTimer localTimer(
575  this, "getLocalSlamResultCallback | Prepare Local Slam Data");
576  const auto timestampInMicroSeconds = util::fromCarto(time);
577 
578  ARMARX_DEBUG << "local slam data timestamp: "
579  << IceUtil::Time::microSeconds(timestampInMicroSeconds);
580 
581  localSlamData.local_points = toPCL(rangeDataInLocal.returns.points());
582  localSlamData.misses = toPCL(rangeDataInLocal.misses.points());
583  localSlamData.local_pose = toEigen(localPose);
584  localSlamData.timestamp = timestampInMicroSeconds;
585  localSlamData.trajectory_pose =
586  toEigen(mapBuilder->pose_graph()->GetLocalToGlobalTransform(trajectoryId));
587 
588  ARMARX_DEBUG << "Callbacks will be triggered (getLocalSlamResultCallback)";
589  }
590  {
591  const DebugObserverScopedTimer localTimer(
592  this, "getLocalSlamResultCallback | On Local Slam Data");
593  slamDataCallable.onLocalSlamData(localSlamData);
594  }
595  // triggerCallbacks();
596 
597  ARMARX_DEBUG << "Callback done (getLocalSlamResultCallback)";
598  }
599 
600  // void CartographerAdapter::triggerCallbacks() const
601  // {
602  // // slamDataCallable.onGraphOptimized(optimizedGraphData());
603  // // slamDataCallable.onGridMap(submapData(trajectoryId));
604  // }
605 
606  bool
607  CartographerAdapter::hasReceivedSensorData() const noexcept
608  {
609  ARMARX_TRACE;
610  const DebugObserverScopedTimer timer(this, "hasReceivedSensorData | Entire Method");
611  std::lock_guard g{cartoInsertMtx};
612 
613  const auto trajectoryNodes = mapBuilder->pose_graph()->GetTrajectoryNodes();
614 
615  auto matchesTrajectoryId = [&](const auto& node) -> bool
616  { return node.id.trajectory_id == trajectoryId; };
617 
618  // checks if nodes wrt. trajectory_id exist
619  return std::any_of(trajectoryNodes.begin(), trajectoryNodes.end(), matchesTrajectoryId);
620  }
621 
622  bool
623  storeDefaultRegistrationFile(const fs::path& jsonFile)
624  {
625  ARMARX_TRACE;
626  std::ofstream ofs(jsonFile, std::ios::out);
627 
628  ARMARX_CHECK(ofs.is_open());
629  ARMARX_CHECK(not ofs.fail());
630 
631  nlohmann::json data;
632  data["x"] = 0.F;
633  data["y"] = 0.F;
634  data["yaw"] = 0.F;
635 
636  ARMARX_INFO << "Creating dummy registration file `" << jsonFile << "`";
637  ofs << data;
638 
639  return true;
640  }
641 
642  bool
643  CartographerAdapter::createMap(const armarx::PackagePath& mapOutputPath)
644  {
645  ARMARX_TRACE;
646  const std::string filenameNoExtension = timestamp();
647 
648  const fs::path mapFilename = std::filesystem::path(mapOutputPath.toSystemPath()) / (filenameNoExtension + ".carto");
649  ARMARX_DEBUG << "The concrete map file is " << mapFilename.string();
650  assert(!fs::exists(map_filename));
651 
652  // Create a new trajectory such that new data will not interfer with the map
653  // that we are optimizing. Therefore, keep track of the trajectory that we
654  // optimize.
655  const int trajectoryIdToBeOptimized = trajectoryId;
656 
657  std::lock_guard g{cartoInsertMtx};
658 
659  trajectoryId = mapBuilder->AddTrajectoryBuilder(
660  sensorSet,
661  trajectoryBuilderOptions,
662  [&](auto... args)
663  { return getLocalSlamResultCallback(std::forward<decltype(args)>(args)...); });
664 
665  ARMARX_IMPORTANT << "Optimizing map ...";
666  mapBuilder->FinishTrajectory(trajectoryIdToBeOptimized);
667  mapBuilder->pose_graph()->RunFinalOptimization();
668  ARMARX_IMPORTANT << "... done.";
669 
670  carto::io::ProtoStreamWriter writer(mapFilename);
671  mapBuilder->SerializeState(true, &writer);
672  writer.Close();
673 
674  ARMARX_IMPORTANT << "Saved map to '" << mapFilename << "'";
675 
676  const fs::path registrationFilename = mapPath / (filenameNoExtension + ".json");
677  ARMARX_INFO << "The default registration data will be stored in " << registrationFilename;
678  storeDefaultRegistrationFile(registrationFilename);
679 
680  // slamDataCallable.onGraphOptimized(optimizedGraphData());
681  // slamDataCallable.onGridMap(submapData(trajectoryIdToBeOptimized));
682 
683  return true;
684  }
685 
687  CartographerAdapter::lookupSensor(const std::string& device) const
688  {
689  ARMARX_TRACE;
690  const DebugObserverScopedTimer timer(this, "lookupSensor");
691  auto laserSensorIt = laserSensorMap.find(device);
692  if (laserSensorIt == laserSensorMap.end())
693  {
694  throw armarx::LocalException("No sensor with id '" + device + "' found.");
695  }
696  return laserSensorIt->second;
697  }
698 
699  void
700  CartographerAdapter::setSensorPose(const std::string& sensorId, const Eigen::Isometry3f& pose)
701  {
702  ARMARX_TRACE;
703  auto laserSensorIt = laserSensorMap.find(sensorId);
704  if (laserSensorIt == laserSensorMap.end())
705  {
706  throw armarx::LocalException("No sensor with id '" + sensorId + "' found.");
707  }
708  laserSensorIt->second.pose = pose;
709  }
710 
711  std::vector<std::string>
712  CartographerAdapter::laserSensorIds() const
713  {
714  ARMARX_TRACE;
715  return armarx::getMapKeys(laserSensorMap);
716  }
717 
718  CartographerAdapter::DebugObserverScopedTimer::~DebugObserverScopedTimer()
719  {
720  ARMARX_TRACE;
721  if (parent->debugObserverHelper)
722  {
723  const armarx::Duration duration = armarx::DateTime::Now() - start;
724  const std::unique_lock lock(parent->debugObserverHelperMtx);
725  parent->debugObserverHelper->setDebugObserverDatafield(name + " [ms]",
726  duration.toMicroSeconds());
727  }
728  }
729 
730  CartographerAdapter::DebugObserverScopedTimer::DebugObserverScopedTimer(
731  const CartographerAdapter* parent,
732  const std::string& name) :
733  parent(parent), name(name), start(armarx::DateTime::Now())
734  {
735  }
736 } // namespace armarx::localization_and_mapping::cartographer_adapter
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::useLaserScanner
bool useLaserScanner
Definition: CartographerAdapter.h:69
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::OdomData::timestamp
int64_t timestamp
timestamp in [ms]
Definition: CartographerAdapter.h:106
ArVizDrawer.h
armarx::localization_and_mapping::cartographer_adapter::util::fromCarto
int64_t fromCarto(::cartographer::common::Time time)
Convert cartographer time to unix time in [µs].
Definition: cartographer_utils.cpp:22
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:187
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::global_localization_min_score
float global_localization_min_score
Definition: CartographerAdapter.h:80
armarx::localization_and_mapping::cartographer_adapter::PoseStamped::timestamp
int64_t timestamp
Definition: InterpolatingTimeQueue.h:46
algorithm.h
cartographer_utils.h
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:190
SCALE_M_TO_MM
constexpr int SCALE_M_TO_MM
Definition: CartographerAdapter.cpp:80
armarx::localization_and_mapping::cartographer_adapter::TimedData
Definition: ApproximateTimeQueue.h:50
armarx::core::time::DateTime::Now
static DateTime Now()
Definition: DateTime.cpp:51
armarx::localization_and_mapping::cartographer_adapter::LocalSlamData::misses
pcl::PointCloud< pcl::PointXYZ > misses
Definition: types.h:42
armarx::localization_and_mapping::cartographer_adapter::LaserScannerMessage
Definition: types.h:153
ARMARX_CHECK_NOT_NULL
#define ARMARX_CHECK_NOT_NULL(ptr)
This macro evaluates whether ptr is not null and if it turns out to be false it will throw an Express...
Definition: ExpressionException.h:206
interfaces.h
trace.h
message
message(STATUS "Boost-Library-Dir: " "${Boost_LIBRARY_DIRS}") message(STATUS "Boost-LIBRARIES
Definition: CMakeLists.txt:8
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::OdomData::position
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3f position
Definition: CartographerAdapter.h:102
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::CartographerAdapter
CartographerAdapter(const std::filesystem::path &mapPath, const std::filesystem::path &configPath, SlamDataCallable &slamDataCallable, const Config &config, const std::optional< std::filesystem::path > &mapToLoad=std::nullopt, const std::optional< Eigen::Isometry3f > &map_T_robot_prior=std::nullopt, const DebugObserverInterfacePrx &debugObserver=nullptr)
Definition: CartographerAdapter.cpp:118
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::OdomData
Definition: CartographerAdapter.h:99
eigen_conversions.h
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::useImu
bool useImu
Definition: CartographerAdapter.h:70
ARMARX_CHECK
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
Definition: ExpressionException.h:82
armarx::localization_and_mapping::cartographer_adapter::PoseStamped
Definition: InterpolatingTimeQueue.h:43
armarx::localization_and_mapping::cartographer_adapter::LocalSlamData::trajectory_pose
Eigen::Isometry3f trajectory_pose
Definition: types.h:50
ApproximateTimeQueue.h
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::min_score
float min_score
Definition: CartographerAdapter.h:81
deactivateSpam
SpamFilterDataPtr deactivateSpam(SpamFilterDataPtr const &spamFilter, float deactivationDurationSec, const std::string &identifier, bool deactivate)
Definition: Logging.cpp:75
armarx::localization_and_mapping::cartographer_adapter::LocalSlamData::timestamp
int64_t timestamp
Definition: types.h:46
ARMARX_TRACE
#define ARMARX_TRACE
Definition: trace.h:77
armarx::localization_and_mapping::cartographer_adapter::util::resolveLuaParameters
std::unique_ptr<::cartographer::common::LuaParameterDictionary > resolveLuaParameters(const std::string &luaCode, const std::filesystem::path &configPath)
Helper function to create Lua parameter object from string.
Definition: cartographer_utils.cpp:11
CartographerAdapter.h
armarx::toEigen
Eigen::Vector3f toEigen(const pcl::PointXYZ &pt)
Definition: PointToModelICP.h:67
armarx::PackagePath::toSystemPath
static std::filesystem::path toSystemPath(const data::PackagePath &pp)
Definition: PackagePath.cpp:47
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::~CartographerAdapter
virtual ~CartographerAdapter()
Definition: CartographerAdapter.cpp:105
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::laserScanners
std::set< std::string > laserScanners
Definition: CartographerAdapter.h:76
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config
Definition: CartographerAdapter.h:66
data
uint8_t data[1]
Definition: EtherCATFrame.h:68
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:184
armarx::cartographer::toPCL
pcl::PointXYZ toPCL(const Eigen::Vector3f &v)
Definition: MapRegistration.cpp:237
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::OdomData::orientation
Eigen::Quaternionf orientation
Definition: CartographerAdapter.h:103
armarx::localization_and_mapping::cartographer_adapter::LocalSlamData::local_pose
Eigen::Isometry3f local_pose
Definition: types.h:45
timestamp
std::string timestamp()
Definition: CartographerAdapter.cpp:85
armarx::localization_and_mapping::cartographer_adapter
This file is part of ArmarX.
Definition: ApproximateTimeQueue.cpp:15
armarx::localization_and_mapping::cartographer_adapter::LocalSlamData::local_points
pcl::PointCloud< pcl::PointXYZ > local_points
Definition: types.h:41
armarx::localization_and_mapping::cartographer_adapter::LaserMessages
std::vector< LaserMessage > LaserMessages
Definition: ApproximateTimeQueue.h:48
q
#define q
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::transform
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT >>
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition: algorithm.h:351
ExpressionException.h
armarx::core::time::DateTime
Represents a point in time.
Definition: DateTime.h:24
armarx::localization_and_mapping::cartographer_adapter::util::toCarto
::cartographer::common::Time toCarto(const int64_t &time)
Convert unix time in [µs] to cartographer time.
Definition: cartographer_utils.cpp:35
armarx::localization_and_mapping::cartographer_adapter::PoseStamped::pose
Eigen::Isometry3f pose
Definition: InterpolatingTimeQueue.h:45
armarx::localization_and_mapping::cartographer_adapter::fromEigen
::cartographer::transform::Rigid3d fromEigen(const Eigen::Isometry3f &pose)
Definition: eigen_conversions.cpp:21
grid_conversion.h
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:181
VAROUT
#define VAROUT(x)
Definition: StringHelpers.h:198
armarx::Quaternion< float, 0 >
armarx::core::time::Duration
Represents a duration.
Definition: Duration.h:16
IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface >
armarx::localization_and_mapping::cartographer_adapter::LocalSlamData
Definition: types.h:39
types.h
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::LaserScannerSensor
Definition: CartographerAdapter.h:113
armarx::core::time::Duration::toMicroSeconds
std::int64_t toMicroSeconds() const
Returns the amount of microseconds.
Definition: Duration.cpp:36
Logging.h
pcl_conversions.h
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:193
armarx::localization_and_mapping::cartographer_adapter::storeDefaultRegistrationFile
bool storeDefaultRegistrationFile(const fs::path &jsonFile)
Definition: CartographerAdapter.cpp:623
cartographer
Definition: ArVizDrawer.h:40
armarx::core::time::Duration::MicroSeconds
static Duration MicroSeconds(std::int64_t microSeconds)
Constructs a duration in microseconds.
Definition: Duration.cpp:24
armarx::PackagePath
Definition: PackagePath.h:52
armarx::localization_and_mapping::cartographer_adapter::SlamDataCallable
Definition: interfaces.h:29
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::useOdometry
bool useOdometry
Definition: CartographerAdapter.h:68
armarx::getMapKeys
void getMapKeys(const MapType &map, OutputIteratorType it)
Definition: algorithm.h:173
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
dt
constexpr T dt
Definition: UnscentedKalmanFilterTest.cpp:45