117 const ::std::string&,
118 const ::armarx::LaserScan&,
119 const ::armarx::TimestampBasePtr&,
120 const ::Ice::Current&)
override;
172 void setupMappingAdapter();
175 std::unique_ptr<cartographer_adapter::CartographerAdapter> mappingAdapter;
179 std::unique_ptr<cartographer_adapter::ArVizDrawer> arvizDrawer;
182 std::unique_ptr<MappingRemoteGui> mappingRemoteGui;
183 std::unique_ptr<LocalizationRemoteGui> localizationRemoteGui;
192 bool mapCreated{
false};
200 RemoteGuiInterfacePrx remoteGui;
211 armarx::data::PackagePath mapPath{.package =
"PriorKnowledgeData",
212 .path =
"maps/cartographer"};
214 std::string mapStorageSubDir;
216 armarx::data::PackagePath mapToLoad{.package =
"PriorKnowledgeData",
217 .path =
"maps/cartographer/..."};
219 armarx::data::PackagePath cartographerConfigPath{.package =
220 "armarx_localization_and_mapping",
221 .path =
"cartographer/config/"};
224 bool enableVisualization =
true;
225 bool enableMappingVisualization =
true;
229 int odomQueryPeriodMs = 20;
230 int occupancyGridMemoryUpdatePeriodMs = 1000;
232 bool useNativeOdometryTimestamps =
true;
233 bool useNativeLaserscannerTimestamps =
true;
235 std::string laserScanners;
239 float global_localization_min_score = 0.5;
242 float obstacleRadius = 500;
244 float occupiedThreshold = 0.55;
248 Throttler throttlerLaserScansMemoryWriter{10.F};
249 Throttler throttlerOccupancyGridMemoryWriter{10.F};
251 Throttler throttlerArviz{10.F};
253 std::unique_ptr<cartographer_adapter::ArVizDrawerMapBuilder> arVizDrawerMapBuilder;
255 std::optional<FrequencyReporter> laserDataReporter;
256 std::optional<FrequencyReporter> odomDataReporter;
257 std::optional<FrequencyReporter> slamResultReporter;
264 std::experimental::observer_ptr<armem::client::plugins::ReaderWriterPlugin<
265 armem::vision::occupancy_grid::client::Writer>>
266 occupancyGridWriterPlugin;
268 std::experimental::observer_ptr<
269 armem::client::plugins::ReaderWriterPlugin<navigation::memory::client::costmap::Writer>>
272 std::experimental::observer_ptr<
273 armem::client::plugins::ReaderWriterPlugin<armem::robot_state::RobotReader>>
278 Eigen::Isometry3f world_T_map = Eigen::Isometry3f::Identity();
279 std::optional<Eigen::Isometry3f> map_T_map_correct = std::nullopt;
280 std::optional<Eigen::Isometry3f> map_T_robot = std::nullopt;
282 std::atomic_bool receivingData{
false};
285 std::optional<Eigen::Isometry3f> globalPose()
const;
294 int64_t lastTimestamp = 0;
295 std::atomic_bool robotIsMoving =
false;
297 plugins::HeartbeatComponentPlugin* heartbeatPlugin =
nullptr;