19 #include <Eigen/Geometry>
22 #include <IceUtil/Time.h>
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>
31 #include <opencv2/core/mat.hpp>
32 #include <opencv2/imgcodecs.hpp>
35 #include <SimoxUtility/algorithm/string/string_tools.h>
36 #include <SimoxUtility/json/json.hpp>
37 #include <SimoxUtility/math.h>
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>
75 #include "util/laser_scanner_conversion.h"
78 namespace carto = ::cartographer;
82 namespace fs = ::std::filesystem;
90 struct tm* timeinfo{};
91 std::array<char, 4 + 1 + 2 + 1 + 2 + 1 + 2 + 1 + 2 + 1> buffer;
94 timeinfo = localtime(&rawtime);
96 strftime(buffer.data(), buffer.size(),
"%Y-%m-%d-%H-%M", timeinfo);
110 mapBuilder->FinishTrajectory(trajectoryId);
119 const std::filesystem::path& mapPath,
120 const std::filesystem::path& configPath,
123 const std::optional<std::filesystem::path>& mapToLoad,
124 const std::optional<Eigen::Isometry3f>& map_T_robot_prior,
126 config(config), mapPath(mapPath), slamDataCallable(slamDataCallable)
129 const std::string mapBuilderLuaCode = R
"text(
130 include "map_builder.lua"
131 return MAP_BUILDER)text";
133 const std::string trajectoryBuilderLuaCode = R
"text(
134 include "trajectory_builder.lua"
135 return TRAJECTORY_BUILDER)text";
138 auto mapBuilderOptions =
139 carto::mapping::CreateMapBuilderOptions(mapBuilderParameters.get());
144 ARMARX_INFO <<
"Setting `global_localization_min_score` to "
146 mapBuilderOptions.mutable_pose_graph_options()
147 ->mutable_constraint_builder_options()
154 mapBuilderOptions.mutable_pose_graph_options()
155 ->mutable_constraint_builder_options()
159 const auto trajectoryBuilderParameters =
161 trajectoryBuilderOptions =
162 carto::mapping::CreateTrajectoryBuilderOptions(trajectoryBuilderParameters.get());
165 mapBuilder = carto::mapping::CreateMapBuilder(mapBuilderOptions);
169 sensorSet.insert(sensorIdLaser);
174 sensorSet.insert(sensorIdOdom);
179 sensorSet.insert(sensorIdIMU);
182 std::vector<std::string> sensorSetNames;
185 std::back_inserter(sensorSetNames),
186 [](
const auto& sensorId) { return sensorId.id; });
198 [&](
const auto& laserScannerName)
200 const SensorId sensorId{.type = SensorId::SensorType::RANGE,
201 .id = laserScannerName};
202 laserSensorMap.insert(
204 LaserScannerSensor(sensorId, Eigen::Isometry3f::Identity())});
213 carto::io::ProtoStreamReader reader(mapToLoad->string());
214 mapBuilder->LoadState(&reader,
true );
215 mapBuilder->pose_graph()->RunFinalOptimization();
218 if (map_T_robot_prior)
220 ARMARX_INFO <<
"Using pose prior \n" << map_T_robot_prior->matrix();
222 ::cartographer::mapping::proto::InitialTrajectoryPose* initial_trajectory_pose =
223 new ::cartographer::mapping::proto::InitialTrajectoryPose;
225 initial_trajectory_pose->set_allocated_relative_pose(
226 new ::cartographer::transform::proto::Rigid3d(
227 ::cartographer::transform::ToProto(
fromEigen(*map_T_robot_prior))));
229 trajectoryBuilderOptions.set_allocated_initial_trajectory_pose(
230 std::move(initial_trajectory_pose));
235 trajectoryId = mapBuilder->AddTrajectoryBuilder(
237 trajectoryBuilderOptions,
238 [
this](
auto&&... args)
239 {
return getLocalSlamResultCallback(std::forward<decltype(args)>(args)...); });
242 const auto dt =
static_cast<int64_t
>(1
'000'000 / config.frequency);
243 const float dtHistoryLength = 1
'000'000;
248 std::make_unique<ApproximateTimeQueue>(
dt,
250 config.laserScanners,
252 config.useOdometryBasedLaserCorrection);
258 cartographerInputDataReporterLaserScanner.emplace(
259 debugObserver,
"CartographerMappingAndLocalization_input_laser");
260 cartographerInputDataReporterOdometry.emplace(
261 debugObserver,
"CartographerMappingAndLocalization_input_odom");
262 if (config.enableDebugTiming)
264 debugObserverHelper.emplace(
265 "CartographerMappingAndLocalization_CartographerAdapter", debugObserver,
true);
274 pushInOdomData(
data.odomPose);
275 pushInLaserData(
data.laserData);
276 if (debugObserverHelper)
279 std::unique_lock g(debugObserverHelperMtx);
280 debugObserverHelper->sendDebugObserverBatch();
285 CartographerAdapter::pushInOdomData(
289 const DebugObserverScopedTimer timer(
this,
"pushInOdomData | Entire Method");
290 if (lastOdomTimestamp.has_value())
293 if (odomPose.
timestamp <= lastOdomTimestamp.value())
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.";
307 auto isOdomSensor = [](
const SensorId& sensorId)
308 {
return sensorId.type == SensorId::SensorType::ODOMETRY; };
310 if (not std::any_of(sensorSet.begin(), sensorSet.end(), isOdomSensor))
313 ARMARX_WARNING <<
"No odometry sensor is registered. Will not use odometry data.";
321 const Eigen::Vector3f p = odomPose.
pose.translation();
323 carto::sensor::OdometryData odomData;
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()});
333 const DebugObserverScopedTimer localTimer(
this,
"pushInOdomData | Inserting Odom Data");
334 std::lock_guard guard{cartoInsertMtx};
336 mapBuilder->GetTrajectoryBuilder(trajectoryId)
337 ->AddSensorData(sensorIdOdom.id, odomData);
340 if (cartographerInputDataReporterOdometry.has_value())
343 cartographerInputDataReporterOdometry->add(
timestamp);
350 CartographerAdapter::pushInLaserData(
const LaserMessages& laserMessages)
354 if (not config.useLaserScanner)
360 const DebugObserverScopedTimer timer(
this,
"pushInLaserData | Entire Method");
361 carto::sensor::TimedPointCloudData timedPointCloudData;
362 timedPointCloudData.origin = Eigen::Vector3f::Zero();
366 const DebugObserverScopedTimer laserMessageTimer(
367 this,
"pushInLaserData | Iterate over laser messages");
368 for (
const auto&
message : laserMessages)
378 auto& lastTimestamp = lastSensorDataTimestamp[
data.frame];
380 if (
data.timestamp <= lastTimestamp)
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.";
389 lastTimestamp =
data.timestamp;
393 Eigen::Isometry3f robot_T_sensor;
396 const LaserScannerSensor sensor = lookupSensor(
data.frame);
398 << sensor.pose.translation();
400 robot_T_sensor = sensor.pose;
402 catch (
const armarx::LocalException&)
404 ARMARX_INFO <<
"Sensor `" <<
data.frame <<
"` not found in sensor set.";
411 const DebugObserverScopedTimer localTimer(
412 this,
"pushInLaserData | Reserve TimedPointCloudData");
413 timedPointCloudData.time =
415 timedPointCloudData.ranges.reserve(timedPointCloudData.ranges.size() +
421 const DebugObserverScopedTimer localTimer(
422 this,
"pushInLaserData | Transform to TimedPointCloudData");
425 std::back_inserter(timedPointCloudData.ranges),
426 [&](
const auto& scanStep) -> carto::sensor::TimedRangefinderPoint
429 toCartesian<Eigen::Vector3f>(scanStep);
432 carto::sensor::TimedRangefinderPoint point;
434 point.position = robot_T_sensor * rangePoint;
442 auto cloud =
toPCL(timedPointCloudData.ranges);
444 const DebugObserverScopedTimer localTimer(
this,
"pushInLaserData | onLaserSensorData");
446 slamDataCallable.onLaserSensorData({
util::fromCarto(timedPointCloudData.time), cloud});
450 const DebugObserverScopedTimer localTimer(
this,
451 "pushInLaserData | Inserting Laser Data");
452 std::lock_guard guard{cartoInsertMtx};
454 auto* trajBuilder = mapBuilder->GetTrajectoryBuilder(trajectoryId);
455 if (trajBuilder ==
nullptr)
461 const std::int64_t laserScannerInsertCartoTimestamp =
462 timedPointCloudData.time.time_since_epoch().count();
464 ARMARX_DEBUG <<
"Inserting " << sensorIdLaser.id <<
" with timestamp "
465 << laserScannerInsertCartoTimestamp;
467 if (lastLaserScannerInsertCartoTimestamp.has_value())
469 if (laserScannerInsertCartoTimestamp <= lastLaserScannerInsertCartoTimestamp)
471 ARMARX_INFO <<
"Received laser scanner data out of order. Will not handle it.";
476 lastLaserScannerInsertCartoTimestamp = laserScannerInsertCartoTimestamp;
479 const DebugObserverScopedTimer addSensorDataTimer(
480 this,
"pushInLaserData | Add Sensor Data to TrajectoryBuilder");
482 trajBuilder->AddSensorData(sensorIdLaser.id, timedPointCloudData);
485 if (cartographerInputDataReporterLaserScanner)
487 cartographerInputDataReporterLaserScanner->add(
497 CartographerAdapter::processOdometryPose(
OdomData odom)
500 const DebugObserverScopedTimer timer(
this,
"processOdometryPose | Entire Method");
504 odomPose.
pose.setIdentity();
508 approxTimeQueue->insertOdomData(std::move(odomPose));
515 const DebugObserverScopedTimer timer(
this,
"processSensorValues | Entire Method");
534 approxTimeQueue->insertLaserData(std::move(
data));
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>
548 const DebugObserverScopedTimer timer(
this,
"getLocalSlamResultCallback | Entire Method");
551 ARMARX_DEBUG <<
"Callback (getLocalSlamResultCallback)";
574 const DebugObserverScopedTimer localTimer(
575 this,
"getLocalSlamResultCallback | Prepare Local Slam Data");
579 << IceUtil::Time::microSeconds(timestampInMicroSeconds);
582 localSlamData.
misses =
toPCL(rangeDataInLocal.misses.points());
584 localSlamData.
timestamp = timestampInMicroSeconds;
586 toEigen(mapBuilder->pose_graph()->GetLocalToGlobalTransform(trajectoryId));
588 ARMARX_DEBUG <<
"Callbacks will be triggered (getLocalSlamResultCallback)";
591 const DebugObserverScopedTimer localTimer(
592 this,
"getLocalSlamResultCallback | On Local Slam Data");
593 slamDataCallable.onLocalSlamData(localSlamData);
597 ARMARX_DEBUG <<
"Callback done (getLocalSlamResultCallback)";
607 CartographerAdapter::hasReceivedSensorData() const noexcept
610 const DebugObserverScopedTimer timer(
this,
"hasReceivedSensorData | Entire Method");
611 std::lock_guard g{cartoInsertMtx};
613 const auto trajectoryNodes = mapBuilder->pose_graph()->GetTrajectoryNodes();
615 auto matchesTrajectoryId = [&](
const auto& node) ->
bool
616 {
return node.id.trajectory_id == trajectoryId; };
619 return std::any_of(trajectoryNodes.begin(), trajectoryNodes.end(), matchesTrajectoryId);
626 std::ofstream ofs(jsonFile, std::ios::out);
636 ARMARX_INFO <<
"Creating dummy registration file `" << jsonFile <<
"`";
646 const std::string filenameNoExtension =
timestamp();
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));
655 const int trajectoryIdToBeOptimized = trajectoryId;
657 std::lock_guard g{cartoInsertMtx};
659 trajectoryId = mapBuilder->AddTrajectoryBuilder(
661 trajectoryBuilderOptions,
663 {
return getLocalSlamResultCallback(std::forward<decltype(args)>(args)...); });
666 mapBuilder->FinishTrajectory(trajectoryIdToBeOptimized);
667 mapBuilder->pose_graph()->RunFinalOptimization();
670 carto::io::ProtoStreamWriter writer(mapFilename);
671 mapBuilder->SerializeState(
true, &writer);
676 const fs::path registrationFilename = mapPath / (filenameNoExtension +
".json");
677 ARMARX_INFO <<
"The default registration data will be stored in " << registrationFilename;
687 CartographerAdapter::lookupSensor(
const std::string& device)
const
690 const DebugObserverScopedTimer timer(
this,
"lookupSensor");
691 auto laserSensorIt = laserSensorMap.find(device);
692 if (laserSensorIt == laserSensorMap.end())
694 throw armarx::LocalException(
"No sensor with id '" + device +
"' found.");
696 return laserSensorIt->second;
700 CartographerAdapter::setSensorPose(
const std::string& sensorId,
const Eigen::Isometry3f& pose)
703 auto laserSensorIt = laserSensorMap.find(sensorId);
704 if (laserSensorIt == laserSensorMap.end())
706 throw armarx::LocalException(
"No sensor with id '" + sensorId +
"' found.");
708 laserSensorIt->second.pose = pose;
711 std::vector<std::string>
712 CartographerAdapter::laserSensorIds()
const
718 CartographerAdapter::DebugObserverScopedTimer::~DebugObserverScopedTimer()
721 if (parent->debugObserverHelper)
724 const std::unique_lock lock(parent->debugObserverHelperMtx);
725 parent->debugObserverHelper->setDebugObserverDatafield(name +
" [ms]",
730 CartographerAdapter::DebugObserverScopedTimer::DebugObserverScopedTimer(
731 const CartographerAdapter* parent,
732 const std::string& name) :