Component.cpp
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * ArmarX is free software; you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License version 2 as
6 * published by the Free Software Foundation.
7 *
8 * ArmarX is distributed in the hope that it will be useful, but
9 * WITHOUT ANY WARRANTY; without even the implied warranty of
10 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 * GNU General Public License for more details.
12 *
13 * You should have received a copy of the GNU General Public License
14 * along with this program. If not, see <http://www.gnu.org/licenses/>.
15 *
16 * @author Fabian Reister ( fabian dot reister at kit dot edu )
17 * @date 2021
18 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
19 * GNU General Public License
20 */
21
22#include "Component.h"
23
24#include <algorithm>
25#include <chrono>
26#include <cstddef>
27#include <cstdint>
28#include <filesystem>
29#include <fstream>
30#include <iomanip>
31#include <ios>
32#include <memory>
33#include <mutex>
34#include <optional>
35#include <sstream>
36#include <stdexcept>
37#include <string>
38#include <thread>
39#include <vector>
40
41#include <Eigen/Core>
42#include <Eigen/Geometry>
43
44#include <Ice/Current.h>
45
46#include <nlohmann/json.hpp>
47#include <nlohmann/json_fwd.hpp>
48
49#include <opencv2/core.hpp>
50#include <opencv2/core/eigen.hpp>
51#include <opencv2/core/mat.hpp>
52#include <opencv2/imgcodecs.hpp>
53#include <opencv2/imgproc.hpp>
54
55#include <SimoxUtility/algorithm/string/string_tools.h>
56
67#include <ArmarXCore/interface/observers/Timestamp.h>
69
70#include <RobotAPI/interface/core/GeometryBase.h>
71#include <RobotAPI/interface/units/LaserScannerUnit.h>
76
88
89namespace fs = std::filesystem;
90
91namespace
92{
93 inline Eigen::Isometry3f
94 toM(Eigen::Isometry3f pose)
95 {
96 pose.translation() /= 1000;
97 return pose;
98 }
99
100 inline Eigen::Isometry3f
101 toMM(Eigen::Isometry3f pose)
102 {
103 pose.translation() *= 1000;
104 return pose;
105 }
106
107} // namespace
108
110{
111
112 std::string
114 {
115 std::string modeStr;
116
117 switch (mode)
118 {
120 modeStr = "localization";
121 break;
123 modeStr = "mapping";
124 break;
125 }
126
127 return modeStr;
128 }
129
130 std::string
132 {
133 std::string modeStr;
134
135 switch (profile)
136 {
138 modeStr = "Default";
139 break;
141 modeStr = "RobotSpecific";
142 break;
143 }
144
145 return modeStr;
146 }
147
149 {
150 addPlugin(heartbeatPlugin);
151 // addPlugin(occupancyGridWriterPlugin);
152 addPlugin(costmapWriterPlugin);
153 addPlugin(robotReaderPlugin);
154
155 setTag(getName());
156 }
157
158 Component::~Component() = default;
159
160 std::string
162 {
163 return GetDefaultName();
164 }
165
166 std::string
168 {
169 return "CartographerMappingAndLocalization";
170 }
171
174 {
177
178 // topic publisher
179 def->topic(debugObserver);
180
181 // topic subscriber
182 // def->topic<LaserScannerUnitListener>(
183 // "LaserScans", "laser_scanner_topic", "Name of the laser scanner topic.");
184
185 // def->topic<PlatformUnitListener>(
186 // "PlatformState",
187 // "platform_state",
188 // "Name of the platform + state to use. This property is used to listen to "
189 // "the platform topic");
190
191 // def->topic<OdometryListener>();
192
193 def->component(remoteGui,
194 "RemoteGuiProvider",
195 "remote_gui_provider",
196 "Name of the remote gui provider");
197
198
199 // mapPath package path
200 def->optional(properties.mapPath.package,
201 "map_path.package",
202 "Path where the map will be created (within a unique subdirectory)");
203 def->optional(properties.mapPath.path,
204 "map_path.path",
205 "Path where the map will be created (within a unique subdirectory)");
206
207 def->optional(properties.mapStorageSubDir,
208 "map_mapStorageSubDir",
209 "Only relevant in mapping mode. Path relative to `properties.mapPath` where "
210 "the generated map should be stored.");
211
212 // mapToLoad package path
213 def->optional(properties.mapToLoad.package,
214 "map_to_load.package",
215 "Name of a map, e.g. 2021-02-15-17-17.carto. Load this map from "
216 "within the 'map_path'");
217 def->optional(properties.mapToLoad.path,
218 "map_to_load.path",
219 "Name of a map, e.g. 2021-02-15-17-17.carto. Load this map from "
220 "within the 'map_path'");
221
222 // cartographerConfigPath package path
223 def->optional(properties.cartographerConfigPath.package,
224 "config_path.package",
225 "Path to the lua config files");
226 def->optional(properties.cartographerConfigPath.path,
227 "config_path.path",
228 "Path to the lua config files");
229
230 def->optional(properties.mode,
231 "mode",
232 "Either run the component in mapping or localization optimized mode")
235
236 def->optional(properties.profile,
237 "profile",
238 "Either default or robot specific. Will load config from directory based on "
239 "this parameter.")
242
243 def->optional(properties.enableVisualization,
244 "enable_arviz",
245 "If enabled, ArViz layers are created.");
246
247 def->optional(properties.enableMappingVisualization,
248 "enable_arviz_mapping",
249 "If enabled, ArViz layers are created.");
250
251 def->optional(adapterConfig.useOdometry, "use_odometry");
252 def->optional(adapterConfig.useLaserScanner, "use_laserscanner");
253 def->optional(adapterConfig.useImu, "use_imu");
254 def->optional(adapterConfig.frequency,
255 "frequency",
256 "The rate (in Hz) at which the cartographer processes data");
257 def->optional(
258 adapterConfig.enableDebugTiming,
259 "enableCartographerAdapterTiming",
260 "If true, the cartographer adapter will publish timing information to the debug topic");
261 def->optional(
262 adapterConfig.useOdometryBasedLaserCorrection, "useOdometryBasedLaserCorrection", "");
263 def->optional(adapterConfig.global_localization_min_score, "global_localization_min_score");
264 def->optional(adapterConfig.min_score, "min_score");
265
266 def->optional(properties.laserScanners,
267 "laser_scanners",
268 "Set of laser scanners to use. Comma separated.");
269
270 def->optional(
271 properties.useNativeOdometryTimestamps,
272 "useNativeOdometryTimestamps",
273 "if disabled, will assume that odometry is always available (this is a bit hacky)");
274
275 def->optional(properties.occupancyGridMemoryUpdatePeriodMs,
276 "occupancyGridMemoryUpdatePeriodMs",
277 "The frequency to store the occupancy grid in the memory.");
278 def->optional(properties.odomQueryPeriodMs,
279 "odomQueryPeriodMs",
280 "The polling frequency to retrieve odometry data from the memory.");
281
282 def->optional(properties.obstacleRadius, "obstacleRadius");
283 def->optional(properties.occupiedThreshold, "occupiedThreshold");
284
285
286 return def;
287 }
288
289 void
290 Component::setupMappingAdapter()
291 {
293
294 if (mappingAdapter != nullptr)
295 {
296 ARMARX_INFO << "Mapping adapter already intialized. Skipping setup.";
297 return;
298 }
299
300 const std::string modeSubfolder = toString(properties.mode);
301 const std::string profileSubfolder = [&]() -> std::string
302 {
303 std::string dir;
304 switch (properties.profile)
305 {
307 ARMARX_INFO << "Using `default` profile";
308 dir = "default";
309 break;
311 ARMARX_INFO << "Using robot specific profile: `" << getRobotName() << "`.";
312 dir = getRobotName();
313 break;
314 }
315
317 return dir;
318 }();
319
320 const fs::path mapPath = armarx::PackagePath(properties.mapPath).toSystemPath();
321
322 ARMARX_INFO << "Map will be stored in " << mapPath.string();
323 fs::create_directories(mapPath);
324
325 const auto configPath =
326 armarx::PackagePath(properties.cartographerConfigPath).toSystemPath() / modeSubfolder /
327 profileSubfolder;
328 ARMARX_IMPORTANT << "Using config files from " << configPath;
329 ARMARX_CHECK(std::filesystem::exists(configPath))
330 << "The config path `" << configPath
331 << "` does not exist. If you use a robot-specific config profile (see property "
332 "`profile`) then this folder must exist.";
333
334
335 switch (properties.mode)
336 {
337 case Mode::Mapping:
338 {
339 // this is the interface to cartographer
340 mappingAdapter =
341 std::make_unique<cartographer_adapter::CartographerAdapter>(mapPath,
342 configPath,
343 *this,
344 adapterConfig,
345 std::nullopt,
346 std::nullopt,
347 debugObserver);
348 break;
349 }
351 {
352 // load the map in localization mode
353 const fs::path mapToLoad = armarx::PackagePath(properties.mapToLoad).toSystemPath();
354
355 ARMARX_INFO << "Trying to load map from " << mapToLoad;
356
357 ARMARX_CHECK(fs::is_regular_file(mapToLoad))
358 << "In localization mode, a valid map has to be provided.";
359
360
361 std::optional<Eigen::Isometry3f> world_T_robot_prior = globalPose(); // [mm]
362
363 // if user didn't set any correction via RemoteGUI, use pose from LTM
364 if (not map_T_map_correct.has_value())
365 {
366 world_T_robot_prior = globalPoseFromLongTermMemory(); // [mm]
367 }
368
369 const auto map_T_robot_prior = [&]() -> std::optional<Eigen::Isometry3f> // [m] !!
370 {
371 if (not world_T_robot_prior.has_value())
372 {
373 return std::nullopt;
374 }
375
376 return toM(world_T_map.inverse() * world_T_robot_prior.value());
377 }();
378
379 // this is the interface to cartographer
380 mappingAdapter =
381 std::make_unique<cartographer_adapter::CartographerAdapter>(mapPath,
382 configPath,
383 *this,
384 adapterConfig,
385 mapToLoad,
386 map_T_robot_prior,
387 debugObserver);
388
389 break;
390 }
391 default:
392 throw std::invalid_argument("Unknown mode");
393 }
394
395 // hook up the input queues
397 mappingAdapter.get());
399 mappingAdapter.get());
400
401 auto sensorPose = [this](const std::string& sensorFrame) -> Eigen::Isometry3f
402 {
403 Eigen::Isometry3f robot_T_sensor = Eigen::Isometry3f::Identity();
404 robot_T_sensor.matrix() = getRobot()->getRobotNode(sensorFrame)->getPoseInRootFrame();
405 robot_T_sensor.translation() /= 1000.; // to [m]
406
407 ARMARX_DEBUG << "Sensor pose for sensor " << sensorFrame << " is " << '\n'
408 << robot_T_sensor.matrix();
409
410 return robot_T_sensor;
411 };
412
413 // set sensor poses
414 const auto sensorIds = mappingAdapter->laserSensorIds();
415 std::for_each(sensorIds.begin(),
416 sensorIds.end(),
417 [&](const std::string& sensorId)
418 { mappingAdapter->setSensorPose(sensorId, sensorPose(sensorId)); });
419 }
420
421 std::optional<Eigen::Isometry3f>
422 Component::globalPose() const
423 {
424 if (not map_T_robot.has_value())
425 {
426 return std::nullopt;
427 }
428
429 return world_T_map * map_T_robot.value();
430 }
431
432 // Lifecycle management methods
433
434 void
436 {
437 const auto laserScanners = simox::alg::split(properties.laserScanners, ",");
438 ARMARX_INFO << "Using laser scanners: " << laserScanners;
439 adapterConfig.laserScanners.insert(laserScanners.begin(), laserScanners.end());
440
442 }
443
444 Eigen::Isometry3f
446 {
448
449 if (properties.mode == Mode::Mapping)
450 {
451 ARMARX_IMPORTANT << "Mapping mode. World to map transform set to identity";
452 return Eigen::Isometry3f::Identity();
453 }
454
455 // store data alongside the map file
456 const fs::path mapPath = armarx::PackagePath(properties.mapPath).toSystemPath();
457
458 fs::path jsonFilename = armarx::PackagePath(properties.mapToLoad).toSystemPath();
459 jsonFilename.replace_extension("json");
460 const fs::path jsonLoadPath = mapPath / jsonFilename;
461
462 ARMARX_CHECK(fs::is_regular_file(jsonLoadPath))
463 << "In mapping mode, the json registration file " << jsonLoadPath << " has to exist!";
464
465 ARMARX_IMPORTANT << "Loading registration result: " << jsonLoadPath.string();
466
467 if (not fs::is_regular_file(jsonLoadPath))
468 {
469 return Eigen::Isometry3f::Identity();
470 }
471
472 std::ifstream ifs(jsonLoadPath.string(), std::ios::in);
473 const auto j = nlohmann::json::parse(ifs);
474
475 ARMARX_CHECK(ifs.is_open());
476 ARMARX_CHECK(not ifs.fail());
477
478 Eigen::Isometry3f world_T_map = Eigen::Isometry3f::Identity();
479 world_T_map.translation().x() = j.at("x");
480 world_T_map.translation().y() = j.at("y");
481 world_T_map.linear() =
482 Eigen::AngleAxisf(j.at("yaw"), Eigen::Vector3f::UnitZ()).toRotationMatrix();
483
484 ARMARX_IMPORTANT << "Loading registration result is " << world_T_map.matrix();
485
486 return world_T_map;
487 }
488
489 void
491 {
492
493 // const bool reconnect = mappingAdapter != nullptr;
494 // if (reconnect)
495 // {
496 // onReconnectComponent();
497 // return;
498 // }
499
500 ARMARX_INFO << "SelfLocalization::onConnectComponent";
503
504 slamResultReporter.emplace(debugObserver, "CartographerMappingAndLocalization_slam_result");
505 laserDataReporter.emplace(debugObserver, "CartographerMappingAndLocalization_laser_data");
506 odomDataReporter.emplace(debugObserver, "CartographerMappingAndLocalization_odom_data");
507
508 world_T_map = worldToMapTransform();
509
511 setupMappingAdapter();
512 ARMARX_CHECK_NOT_NULL(mappingAdapter);
513
514 map_T_map_correct = std::nullopt;
515
516 // Only in the mapping mode, allow the user to create a map.
517 // Although this would be possible in localization mode as well, this might
518 // be confusing and likely results in suboptimal maps. It's therefore prefered to record
519 // the data using the TopicRecorder such that you can create the map afterwards.
520 switch (properties.mode)
521 {
522 case Mode::Mapping:
523
524 {
525 const MappingRemoteGui::Params mappingRemoteGuiParams{
526 .remoteGuiTabName = getName(),
527 .mapStorageDir = armarx::PackagePath(properties.mapPath.package,
528 properties.mapPath.path + "/" +
529 properties.mapStorageSubDir)};
530
531 mappingRemoteGui =
532 std::make_unique<MappingRemoteGui>(remoteGui, *this, mappingRemoteGuiParams);
533 break;
534 }
536 localizationRemoteGui = std::make_unique<LocalizationRemoteGui>(remoteGui, *this);
537 ARMARX_INFO << "The remote GUI will only be shown in 'MAPPING' mode.";
538 break;
539 }
540
541
542 if (properties.enableVisualization)
543 {
544 arvizDrawer =
545 std::make_unique<cartographer_adapter::ArVizDrawer>(getArvizClient(), world_T_map);
546
547 // we use the map visu also to visualize the recorded / known map
548 arVizDrawerMapBuilder = std::make_unique<cartographer_adapter::ArVizDrawerMapBuilder>(
549 getArvizClient(), mappingAdapter->getMapBuilder(), world_T_map);
550
551 arVizDrawerMapBuilder->drawOnce();
552
553 if (properties.enableMappingVisualization and properties.mode == Mode::Mapping)
554 {
555 arVizDrawerMapBuilder->startMappingVisu();
556 }
557 }
558
559
560 const auto storeOccupancyGridAndCostmapInMemory = [&]()
561 {
562 ARMARX_INFO << "Obtaining grids";
563 const auto grids =
565 mappingAdapter->getMapBuilder(), 0);
566
567 if (grids.empty())
568 {
569 ARMARX_INFO << "No grids.";
570 return;
571 }
572
573 armem::vision::OccupancyGrid grid = grids.front();
574 grid.pose.translation() *= 1'000; // [m] to [mm]
575 grid.resolution *= 1'000; // [m] to [mm]
576
577 ARMARX_INFO << VAROUT(world_T_map.matrix());
578
579 ARMARX_CHECK_EQUAL(grid.frame, MapFrame) << "Assuming map frame";
580 grid.pose = world_T_map * grid.pose; // map to global frame
581 grid.frame = GlobalFrame;
582
583 ARMARX_INFO << "Storing occupancy grid in memory";
584 // TODO latest timestamp
585 // occupancyGridWriterPlugin->get().store(
586 // grid, MapFrame, getName(), IceUtil::Time::now().toMicroSeconds());
587
588 // grid as costmap
589
590 OccupancyGridHelper::Params helperParams{
591 .freespaceThreshold = 0.45F, .occupiedThreshold = properties.occupiedThreshold};
592
593 OccupancyGridHelper helper(grid, helperParams);
594
595 const std::size_t nKnownCells = helper.knownCells().cast<int>().sum();
596 const std::size_t nFreeCells = helper.freespace().cast<int>().sum();
597 const std::size_t nOccupied = helper.obstacles().cast<int>().sum();
598
599 ARMARX_INFO << VAROUT(nKnownCells) << VAROUT(nFreeCells) << VAROUT(nOccupied);
600
601 // freespace as 0:occupied, 1:free
602 // const OccupancyGridHelper::BinaryArray freespace = helper.freespace();
603
604 // alternative: treat everything that is not an obstacle as free
605 OccupancyGridHelper::BinaryArray freespace = helper.obstacles() == false;
606 freespace = helper.knownCells() and freespace;
607
608 ARMARX_INFO << VAROUT(freespace.cast<int>().sum());
609
611 freespace.cast<std::uint8_t>() * 255;
612
613 cv::Mat1b freespaceMat;
614 cv::eigen2cv(freespaceCvFormat, freespaceMat);
615
616 cv::Mat1f distanceMat(freespaceMat.size());
617 cv::distanceTransform(freespaceMat, distanceMat, cv::DIST_L2, cv::DIST_MASK_PRECISE);
618
619 // The distance is in pixel units, we need to convert it to metric units
620 distanceMat *= grid.resolution;
621
623 .binaryGrid = false, .cellSize = grid.resolution, .sceneBoundsMargin = 0};
624
625 const navigation::algorithms::SceneBounds sceneBounds{
626 .min = Eigen::Vector2f::Zero(),
627 // FIXME check rows / cols order
628 .max = Eigen::Vector2f{grid.grid.rows(), grid.grid.cols()} * grid.resolution};
629
631 cv::cv2eigen(distanceMat, cGrid);
632
633 // store without considering robot radius
634 {
635 const Eigen::Array<bool, Eigen::Dynamic, Eigen::Dynamic> reducedFreespace =
636 cGrid.array() > 0;
637
638 const navigation::algorithms::Costmap::Mask mask = reducedFreespace.matrix();
639
641 cGrid, params, sceneBounds, mask, navigation::conv::to2D(grid.pose));
642
643 ARMARX_INFO << VAROUT(grid.pose.matrix());
644
645 ARMARX_INFO << "Storing costmap in memory";
646 costmapWriterPlugin->get().store(
647 costmap, "distance_to_obstacles_raw", getName(), Clock::Now());
648 }
649
650 // store with considering robot radius
651 {
652 // we substract the obstacle radius which also has an influence on the available freespace
653 cGrid.array() -= properties.obstacleRadius;
654
655 const Eigen::Array<bool, Eigen::Dynamic, Eigen::Dynamic> reducedFreespace =
656 cGrid.array() > 0;
657
658 const navigation::algorithms::Costmap::Mask mask = reducedFreespace.matrix();
659
661 cGrid, params, sceneBounds, mask, navigation::conv::to2D(grid.pose));
662
663 ARMARX_INFO << VAROUT(grid.pose.matrix());
664
665 ARMARX_INFO << "Storing costmap in memory";
666 costmapWriterPlugin->get().store(
667 costmap, "distance_to_obstacles", getName(), Clock::Now());
668 }
669 };
670
671 // store once on startup
672 storeOccupancyGridAndCostmapInMemory();
673
674 // occupancyGridTask = new SimplePeriodicTask<>(storeOccupancyGridAndCostmapInMemory,
675 // properties.occupancyGridMemoryUpdatePeriodMs);
676 // occupancyGridTask->start();
677
678 laserMessageQueue.enable();
679 odomMessageQueue.enable();
680
681 // wait a bit such that all threads are initialized
682 std::this_thread::sleep_for(std::chrono::milliseconds(100));
683
684
685 receivingData.store(true);
686 ARMARX_INFO << "Will now process incoming messages.";
687
688
689 // ARMARX_INFO << "Enabling robot unit streaming";
690 // robotUnitReader = std::make_unique<components::cartographer_localization_and_mapping::RobotUnitReader>(*robotUnit, odomMessageQueue, *odomDataReporter);
691
692 if (odometryQueryTask)
693 {
694 odometryQueryTask->stop();
695 odometryQueryTask = nullptr;
696 }
697
698 odometryQueryTask = new SimplePeriodicTask<>(
699 [&]()
700 {
701 const auto timestamp = armarx::Clock::Now();
702
704 if (not receivingData.load())
705 {
706 ARMARX_INFO << deactivateSpam(1) << "Receiving data is deactivated";
707 return;
708 }
709
710 ARMARX_CHECK_NOT_NULL(robotReaderPlugin);
711 if (auto odomPose =
712 robotReaderPlugin->get().queryOdometryPose(getRobotName(), timestamp))
713 {
714
715 if (properties.useNativeOdometryTimestamps)
716 {
717 // did we retrieve the same data as last time?
718 if (lastTimestamp >= odomPose->header.timestamp.toMicroSecondsSinceEpoch())
719 {
720 return;
721 }
722
723 lastTimestamp = odomPose->header.timestamp.toMicroSecondsSinceEpoch();
724 }
725 else
726 {
727 lastTimestamp = timestamp.toMicroSecondsSinceEpoch();
728 }
729
730
732 .position = odomPose->transform.translation() / 1000, // mm -> m
733 .orientation = Eigen::Quaternionf(odomPose->transform.linear()),
734 .timestamp = lastTimestamp};
735
736 // ARMARX_INFO << deactivateSpam(1) << "received odom data from memory";
737 odomMessageQueue.push(odomData);
738
739 if (odomDataReporter)
740 {
741 odomDataReporter->add(odomData.timestamp);
742 }
743 }
744 else
745 {
746 ARMARX_WARNING << deactivateSpam(10) << "Failed to query odom pose";
747 }
748 },
749 properties.odomQueryPeriodMs);
750
751 odometryQueryTask->start();
752
753 heartbeatPlugin->signUp(armarx::Duration::MilliSeconds(500),
755 {"Localization"},
756 "CartographerMappingAndLocalization");
757
758 ARMARX_DEBUG << "onConnectComponent completed";
759 }
760
761 void
763 {
764 ARMARX_INFO << "CartographerMappingAndLocalization::reconnecting ...";
766
767 if (localizationRemoteGui)
768 {
769 localizationRemoteGui->enable();
770 }
771
772 if (mappingRemoteGui)
773 {
774 mappingRemoteGui->enable();
775 }
776
777 slamResultReporter.emplace(debugObserver, "slam_result");
778 laserDataReporter.emplace(debugObserver, "laser_data");
779 odomDataReporter.emplace(debugObserver, "odom_data");
780
781
782 map_T_map_correct = std::nullopt;
783 if (arvizDrawer)
784 {
786 arvizDrawer->setWorldToMapTransform(world_T_map);
787 arvizDrawer->setMapCorrection(Eigen::Isometry3f::Identity());
788 }
789
790 laserMessageQueue.enable();
791 odomMessageQueue.enable();
792
793 receivingData.store(true);
794 ARMARX_INFO << "Will now process incoming messages.";
795 ARMARX_DEBUG << "onReconnectComponent completed";
796 }
797
798 void
800 {
802
803 ARMARX_WARNING << "Disconnecting ...";
804
805 receivingData.store(false);
806
807 if (localizationRemoteGui)
808 {
809 localizationRemoteGui->disable();
810 }
811
812 if (mappingRemoteGui)
813 {
814 mappingRemoteGui->disable();
815 }
816
817 {
818 if (odometryQueryTask and odometryQueryTask->isRunning())
819 {
820 odometryQueryTask->stop();
821 }
822 odometryQueryTask = nullptr;
823 }
824
825 {
826 if (helperTask and helperTask->isRunning())
827 {
828 helperTask->stop();
829 }
830 helperTask = nullptr;
831 }
832
833
834 laserMessageQueue.clear();
835 odomMessageQueue.clear();
836
837 laserMessageQueue.waitUntilProcessed();
838 odomMessageQueue.waitUntilProcessed();
839
840
841 slamResultReporter.reset();
842 laserDataReporter.reset();
843 odomDataReporter.reset();
844
846 }
847
848 void
850 {
852
853 ARMARX_DEBUG << "Stopping task";
854
855 // this causes remote guis and arviz layers to be cleaned up
856 if (mappingRemoteGui)
857 {
858 mappingRemoteGui->shutdown();
859 }
860
861 if (localizationRemoteGui)
862 {
863 localizationRemoteGui->shutdown();
864 }
865
866 if (arvizDrawer)
867 {
868 arvizDrawer.reset();
869 }
870 }
871
872 void
874 {
875 // publish localization
876 ARMARX_DEBUG << "Received SLAM result";
877
878 map_T_robot = map_T_map_correct.value_or(Eigen::Isometry3f::Identity()) *
879 toMM(slamData.global_pose());
881 {map_T_robot.value(),
883
884
885 heartbeatPlugin->heartbeat();
886
887 // publish visualization stuff
888 if (arvizDrawer != nullptr && throttlerArviz.check(slamData.timestamp))
889 {
890 ARMARX_DEBUG << "arvizDrawer->onLocalSlamData";
891 arvizDrawer->onLocalSlamData(slamData);
892 }
893
894 if (slamResultReporter)
895 {
896 slamResultReporter->add(slamData.timestamp);
897 }
898 }
899
900 void
902 {
903 static int i{0};
904
905 for (const auto& sd : submapData)
906 {
907 cv::Mat2b img;
908 cv::flip(sd.submap, img, 1); // horizontally
909
910 std::vector<cv::Mat> channels(img.channels());
911 cv::split(img, channels);
912
913 // save the submap (occupancy grid) ...
914 std::stringstream ss;
915 ss << "/tmp/cartographer_mapping/submap_";
916 ss << std::setw(10) << std::setfill('0') << ++i;
917 ss << ".png";
918 std::string s = ss.str();
919
920 cv::imwrite(s, channels.at(0));
921
922 // ... and its mask
923 std::stringstream ssm;
924 ssm << "/tmp/cartographer_mapping/submap_mask_";
925 ssm << std::setw(10) << std::setfill('0') << i;
926 ssm << ".png";
927 std::string sm = ssm.str();
928
929 cv::imwrite(sm, channels.at(1));
930 }
931 }
932
933 void
935 {
936 if (arvizDrawer != nullptr)
937 {
938 arvizDrawer->onLaserSensorData(laserData);
939 }
940 }
941
942 void
944 {
946
947 ARMARX_CHECK_NOT_NULL(mappingRemoteGui);
948 ARMARX_CHECK_NOT_NULL(mappingAdapter);
949
950 // check if sensor data has been received
951 if (not mappingAdapter->hasReceivedSensorData())
952 {
953 ARMARX_WARNING << "No sensor data received yet. Will not create map.";
954 return;
955 }
956
957 ARMARX_INFO << "Map button clicked which triggers map creation.";
958
959 // ensure that only one map can be created at a time
960 // mappingRemoteGui->disable();
961
962 receivingData.store(false);
963
964 ARMARX_INFO << "Waiting until all data is processed.";
965 laserMessageQueue.waitUntilProcessed();
966 odomMessageQueue.waitUntilProcessed();
967
968 ARMARX_INFO << "Creating map.";
969 mappingAdapter->createMap(ctx.mapStorageDir);
970 // mappingRemoteGui->enable();
971 }
972
973 void
974 Component::reportSensorValues(const ::std::string&,
975 const ::std::string& name,
976 const ::armarx::LaserScan& scan,
977 const ::armarx::TimestampBasePtr& timestamp,
978 const ::Ice::Current&)
979 {
981
982 ARMARX_VERBOSE << name << " points " << scan.size();
983
984 const armarx::DateTime timestampReference =
986 const armarx::DateTime timestampArrival = armarx::Clock::Now();
987
988 const armarx::Duration timediff = timestampArrival - timestampReference;
989 if (timediff.toMilliSeconds() > 100)
990 {
991 ARMARX_WARNING << "There is a significant delay (receiving laserscanner data) of "
992 << timediff.toMilliSeconds() << "ms from sensor " << name;
993 }
994
995 std::lock_guard g{inputMtx};
996
997 if (not receivingData.load())
998 {
999 return;
1000 }
1001
1002 // check if this is a laser scanner not activated.
1003 if (adapterConfig.laserScanners.count(name) == 0)
1004 {
1005 return;
1006 }
1007
1008 laserMessageQueue.push(
1010 ARMARX_DEBUG << "Inserted laser scanner data into laserMessageQueue";
1011
1012 if (laserDataReporter)
1013 {
1014 laserDataReporter->add(timestamp->timestamp);
1015 }
1016
1017 if (properties.mode == Mode::Mapping)
1018 {
1019 // if (throttlerLaserScansMemoryWriter.check(timestamp->timestamp) and
1020 // laserScansMemoryWriter != nullptr)
1021 // {
1022 // laserScansMemoryWriter->storeSensorData(
1023 // scan, name, getAgentName(), timestamp->timestamp);
1024 // }
1025 }
1026 }
1027
1028 namespace util
1029 {
1030
1032 toTransform(const TransformStamped& transform)
1033 {
1034 return {.header = {.parentFrame = transform.header.parentFrame,
1035 .frame = transform.header.frame,
1036 .agent = transform.header.agent,
1037 .timestamp = armarx::Duration::MicroSeconds(
1038 transform.header.timestampInMicroSeconds)},
1039 .transform = Eigen::Isometry3f(transform.transform)};
1040 }
1041
1042 } // namespace util
1043
1044 // void CartographerMappingAndLocalization::reportOdometryPose(
1045 // const TransformStamped& odometryPose, const Ice::Current&)
1046 // {
1047 // std::lock_guard g{inputMtx};
1048
1049 // ARMARX_TRACE;
1050 // if (not receivingData.load())
1051 // {
1052 // return;
1053 // }
1054
1055 // Eigen::Isometry3f odomPose(odometryPose.transform);
1056
1057 // constexpr float mmToM = 1 / 1000.;
1058
1059 // CartographerAdapter::OdomData odomData;
1060 // odomData.position = odomPose.translation() * mmToM;
1061 // odomData.orientation = Eigen::Quaternionf(odomPose.linear());
1062 // odomData.timestamp = odometryPose.header.timestampInMicroSeconds;
1063
1064 // ARMARX_TRACE;
1065 // odomMessageQueue.push(odomData);
1066 // ARMARX_DEBUG << "Inserted odom data into odomMessageQueue";
1067
1068 // Eigen::Isometry3f odomVisuPose(odometryPose.transform);
1069 // odomVisuPose.translation() /= 1000.;
1070
1071 // if (arvizDrawer)
1072 // {
1073 // arvizDrawer->onOdomPose(odomVisuPose);
1074 // }
1075
1076 // if (odomDataReporter)
1077 // {
1078 // odomDataReporter->add(odomData.timestamp);
1079 // }
1080
1081 // // TODO(fabian.reister): this should be published by robot state component
1082 // // getTransformWriter().commitTransform(util::toTransform(odometryPose));
1083 // }
1084
1085 void
1086 Component::onLocalizationCorrection(const Eigen::Isometry3f& map_T_map_correct)
1087 {
1088
1089 if (not receivingData.load())
1090 {
1091 ARMARX_INFO << "onLocalizationCorrection() requested but component is deactivated. "
1092 "Will not process request.";
1093 return;
1094 }
1095
1096 this->map_T_map_correct = map_T_map_correct;
1097
1098 if (arvizDrawer)
1099 {
1100 arvizDrawer->setMapCorrection(map_T_map_correct);
1101 }
1102 }
1103
1104 void
1106 {
1107 if (not receivingData.load())
1108 {
1109 ARMARX_INFO << "onApplyLocalizationCorrection() requested but component is "
1110 "deactivated. Will not process request.";
1111 return;
1112 }
1113
1114 if (helperTask)
1115 {
1116 helperTask->stop();
1117 helperTask = nullptr;
1118 }
1119
1120 // In onDisconnect(), we want to stop the LocalizationRemoteGui, which is the caller of this function.
1121 // Therefore, delegate this to a new task.
1122 helperTask = new SimpleRunningTask<>(
1123 [&]()
1124 {
1126
1127 std::this_thread::sleep_for(std::chrono::milliseconds(500));
1128 mappingAdapter.reset();
1129 std::this_thread::sleep_for(std::chrono::milliseconds(100));
1131 },
1132 "HelperTask");
1133
1134 helperTask->start();
1135 }
1136
1138
1139} // namespace armarx::localization_and_mapping::components::cartographer_localization_and_mapping
std::string timestamp()
#define ARMARX_REGISTER_COMPONENT_EXECUTABLE(ComponentT, applicationName)
Definition Decoupled.h:29
#define ARMARX_CHECK_NOT_EMPTY(c)
#define VAROUT(x)
armarx::viz::Client & getArvizClient()
static DateTime Now()
Current time on the virtual clock.
Definition Clock.cpp:93
static Duration MicroSeconds(std::int64_t microSeconds)
Constructs a duration in microseconds.
Definition Duration.cpp:24
static Duration MilliSeconds(std::int64_t milliSeconds)
Constructs a duration in milliseconds.
Definition Duration.cpp:48
SpamFilterDataPtr deactivateSpam(float deactivationDurationSec=10.0f, const std::string &identifier="", bool deactivate=true) const
disables the logging for the current line for the given amount of seconds.
Definition Logging.cpp:99
void setTag(const LogTag &tag)
Definition Logging.cpp:54
PluginT * addPlugin(const std::string prefix="", ParamsT &&... params)
std::string getName() const
Retrieve name of object.
detail::OccupancyGridHelperParams Params
Eigen::Array< bool, Eigen::Dynamic, Eigen::Dynamic > BinaryArray
static std::filesystem::path toSystemPath(const data::PackagePath &pp)
void onDisconnectComponent() override
void onExitComponent() override
Represents a point in time.
Definition DateTime.h:25
Represents a duration.
Definition Duration.h:17
std::int64_t toMilliSeconds() const
Returns the amount of milliseconds.
Definition Duration.cpp:60
void onLocalizationCorrection(const Eigen::Isometry3f &map_T_map_correct) override
void reportSensorValues(const ::std::string &, const ::std::string &, const ::armarx::LaserScan &, const ::armarx::TimestampBasePtr &, const ::Ice::Current &) override
void onLocalSlamData(const cartographer_adapter::LocalSlamData &slamData) override
Eigen::Isometry3f worldToMapTransform() const override
static transformation from world to map
void onCreateMapButtonClicked(const RemoteGuiCallee::ButtonClickContext &ctx) override
void onLaserSensorData(const cartographer_adapter::LaserScannerData &laserData) override
std::optional< Eigen::Isometry3f > globalPoseFromLongTermMemory() const
const std::shared_ptr< VirtualRobot::Robot > & getRobot() const noexcept
Eigen::Matrix< bool, Eigen::Dynamic, Eigen::Dynamic > Mask
Definition Costmap.h:60
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
#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...
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_IMPORTANT
The logging level for always important information, but expected behaviour (in contrast to ARMARX_WAR...
Definition Logging.h:190
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
Definition Logging.h:184
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
#define ARMARX_VERBOSE
The logging level for verbose information.
Definition Logging.h:187
std::string const GlobalFrame
Variable of the global coordinate system.
Definition FramedPose.h:65
Quaternion< float, 0 > Quaternionf
std::vector< armem::vision::OccupancyGrid > occupancyGrids(::cartographer::mapping::MapBuilderInterface &mapBuilder, int trajectoryId)
Definition utils.cpp:112
armem::robot_state::localization::Transform toTransform(const TransformStamped &transform)
void dumpSubMapsToDisk(const cartographer_adapter::SubMapDataVector &submapData)
auto toM(Eigen::Isometry3f t) -> Eigen::Isometry3f
std::vector< Eigen::Vector2f > to2D(const std::vector< Eigen::Vector3f > &v)
Definition eigen.cpp:29
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
IceUtil::Handle< class PropertyDefinitionContainer > PropertyDefinitionsPtr
PropertyDefinitions smart pointer type.
SimplePeriodicTask(Ts...) -> SimplePeriodicTask< std::function< void(void)> >
std::string const MapFrame
Definition FramedPose.h:67
SimpleRunningTask(Ts...) -> SimpleRunningTask< std::function< void(void)> >
Eigen::Vector3f toMM(const Eigen::Vector3f &vec)
#define ARMARX_TRACE
Definition trace.h:77