CartographerAdapter.h
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 #pragma once
23 
24 #include <cstdint>
25 #include <filesystem>
26 #include <memory>
27 #include <mutex>
28 #include <optional>
29 #include <vector>
30 
31 #include <Eigen/Core>
32 #include <Eigen/Geometry>
33 
34 #include <opencv2/core/mat.hpp>
35 
37 #include <ArmarXCore/interface/observers/ObserverInterface.h>
40 
41 #include <RobotAPI/interface/units/LaserScannerUnit.h>
42 
45 
46 #include <cartographer/mapping/trajectory_builder_interface.h>
47 
48 namespace cartographer::mapping
49 {
50  class MapBuilderInterface;
51 } // namespace cartographer::mapping
52 
54 {
55  struct PoseStamped;
56 }
57 
59 {
60  class ApproximateTimeQueue;
61  struct LaserMessage;
62 
63  class CartographerAdapter : virtual public MessageCallee
64  {
65  public:
66  struct Config
67  {
68  bool useOdometry{false};
69  bool useLaserScanner{true};
70  bool useImu{false};
71 
72  float frequency{-1.F};
73 
75 
76  std::set<std::string> laserScanners; // "LaserScannerFront", "LaserScannerBack";
77 
78  bool enableDebugTiming{false};
79 
81  float min_score = 0.55F;
82  };
83 
85  const std::filesystem::path& mapPath,
86  const std::filesystem::path& configPath,
87  SlamDataCallable& slamDataCallable,
88  const Config& config,
89  const std::optional<std::filesystem::path>& mapToLoad = std::nullopt,
90  const std::optional<Eigen::Isometry3f>& map_T_robot_prior = std::nullopt,
91  const DebugObserverInterfacePrx& debugObserver = nullptr);
92 
93  virtual ~CartographerAdapter();
94 
96 
97  void onTimedDataAvailable(const TimedData& data) override;
98 
99  struct OdomData
100  {
101  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
102  Eigen::Vector3f position;
104 
105  //! timestamp in [ms]
106  int64_t timestamp;
107  };
108 
109  void processOdometryPose(OdomData odomData);
110 
111  using SensorId = ::cartographer::mapping::TrajectoryBuilderInterface::SensorId;
112 
114  {
115  public:
117 
118  [[nodiscard]] auto
119  origin() const -> Eigen::Vector3f
120  {
121  return pose.translation();
122  }
123 
124  explicit LaserScannerSensor(const SensorId& sensorId, Eigen::Isometry3f pose) :
125  LaserScannerSensorBase(sensorId.id, pose), id(sensorId)
126  {
127  }
128  };
129 
131 
132  bool createMap(const armarx::PackagePath& mapOutputPath);
133  void setSensorPose(const std::string& sensorId, const Eigen::Isometry3f& pose);
134  bool hasReceivedSensorData() const noexcept;
135 
136  std::vector<std::string> laserSensorIds() const;
137 
138  // void triggerCallbacks() const;
139 
140  ::cartographer::mapping::MapBuilderInterface&
142  {
143  return *mapBuilder;
144  }
145 
146  private:
147  void pushInOdomData(
149  void pushInLaserData(const std::vector<LaserMessage>& laserMessages);
150 
151  // laser scanners will be merged
152  const SensorId sensorIdLaser{SensorId::SensorType::RANGE, "laser"};
153  const SensorId sensorIdIMU{SensorId::SensorType::IMU, "imu"};
154  const SensorId sensorIdOdom{SensorId::SensorType::ODOMETRY, "odom"};
155 
156  const LaserScannerSensor& lookupSensor(const std::string& device) const;
157 
158  void getLocalSlamResultCallback(
159  const int /*trajectory_id*/,
161  const ::cartographer::transform::Rigid3d localPose,
162  ::cartographer::sensor::RangeData rangeDataInLocal,
163  const std::unique_ptr<
164  const ::cartographer::mapping::TrajectoryBuilderInterface::InsertionResult>
165  insertionResult);
166 
167  std::unique_ptr<::cartographer::mapping::MapBuilderInterface> mapBuilder;
168 
169  std::map<std::string, int64_t> lastSensorDataTimestamp;
170  std::optional<std::int64_t> lastOdomTimestamp;
171 
172  std::optional<std::int64_t> lastLaserScannerInsertCartoTimestamp;
173 
174  const Config config;
175 
176  int trajectoryId{0};
177 
178  std::filesystem::path mapPath;
179 
180  std::set<SensorId> sensorSet;
181 
182  SlamDataCallable& slamDataCallable;
183 
184  ::cartographer::mapping::proto::TrajectoryBuilderOptions trajectoryBuilderOptions;
185 
186  mutable std::mutex cartoInsertMtx;
187 
188  std::unique_ptr<ApproximateTimeQueue> approxTimeQueue;
189 
190  std::unordered_map<std::string, LaserScannerSensor> laserSensorMap;
191 
192  std::optional<FrequencyReporter> cartographerInputDataReporterLaserScanner;
193  std::optional<FrequencyReporter> cartographerInputDataReporterOdometry;
194 
195  mutable std::optional<DebugObserverHelper> debugObserverHelper;
196  mutable std::mutex debugObserverHelperMtx;
197 
198  struct DebugObserverScopedTimer
199  {
200  DebugObserverScopedTimer(const CartographerAdapter* parent, const std::string& name);
201 
202  ~DebugObserverScopedTimer();
203 
204  const CartographerAdapter* parent;
205  std::string name;
206  armarx::DateTime start;
207  };
208  };
209 } // 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
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::global_localization_min_score
float global_localization_min_score
Definition: CartographerAdapter.h:80
Eigen
Definition: Elements.h:32
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::processOdometryPose
void processOdometryPose(OdomData odomData)
Definition: CartographerAdapter.cpp:497
armarx::localization_and_mapping::cartographer_adapter::TimedData
Definition: ApproximateTimeQueue.h:50
armarx::localization_and_mapping::cartographer_adapter::LaserScannerMessage
Definition: types.h:153
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::LaserScannerSensor::LaserScannerSensor
LaserScannerSensor(const SensorId &sensorId, Eigen::Isometry3f pose)
Definition: CartographerAdapter.h:124
interfaces.h
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::LaserScannerSensor::origin
auto origin() const -> Eigen::Vector3f
Definition: CartographerAdapter.h:119
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::processSensorValues
void processSensorValues(LaserScannerMessage data)
Definition: CartographerAdapter.cpp:512
armarx::localization_and_mapping::cartographer_adapter::LaserScannerSensorBase
Definition: types.h:133
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::optimizedGraphData
OptimizedGraphData optimizedGraphData() const
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::OdomData
Definition: CartographerAdapter.h:99
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::useImu
bool useImu
Definition: CartographerAdapter.h:70
armarx::localization_and_mapping::cartographer_adapter::PoseStamped
Definition: InterpolatingTimeQueue.h:43
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::min_score
float min_score
Definition: CartographerAdapter.h:81
armarx::localization_and_mapping::cartographer_adapter::OptimizedGraphData
Definition: types.h:128
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::onTimedDataAvailable
void onTimedDataAvailable(const TimedData &data) override
Definition: CartographerAdapter.cpp:271
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::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::enableDebugTiming
bool enableDebugTiming
Definition: CartographerAdapter.h:78
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::OdomData::orientation
Eigen::Quaternionf orientation
Definition: CartographerAdapter.h:103
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::setSensorPose
void setSensorPose(const std::string &sensorId, const Eigen::Isometry3f &pose)
Definition: CartographerAdapter.cpp:700
cartographer::mapping
Definition: ArVizDrawer.h:40
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::frequency
float frequency
Definition: CartographerAdapter.h:72
armarx::localization_and_mapping::cartographer_adapter
This file is part of ArmarX.
Definition: ApproximateTimeQueue.cpp:15
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::hasReceivedSensorData
bool hasReceivedSensorData() const noexcept
Definition: CartographerAdapter.cpp:607
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::core::time::DateTime
Represents a point in time.
Definition: DateTime.h:24
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::getMapBuilder
::cartographer::mapping::MapBuilderInterface & getMapBuilder()
Definition: CartographerAdapter.h:141
DebugObserverHelper.h
armarx::localization_and_mapping::cartographer_adapter::MessageCallee
Definition: interfaces.h:43
std
Definition: Application.h:66
armarx::localization_and_mapping::cartographer_adapter::LaserScannerSensorBase::pose
Eigen::Isometry3f pose
Definition: types.h:139
armarx::Quaternion< float, 0 >
FrequencyReporter.h
IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface >
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::Config::useOdometryBasedLaserCorrection
bool useOdometryBasedLaserCorrection
Definition: CartographerAdapter.h:74
types.h
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::LaserScannerSensor
Definition: CartographerAdapter.h:113
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::laserSensorIds
std::vector< std::string > laserSensorIds() const
Definition: CartographerAdapter.cpp:712
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::SensorId
::cartographer::mapping::TrajectoryBuilderInterface::SensorId SensorId
Definition: CartographerAdapter.h:111
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter
Definition: CartographerAdapter.h:63
armarx::localization_and_mapping::cartographer_adapter::CartographerAdapter::createMap
bool createMap(const armarx::PackagePath &mapOutputPath)
Definition: CartographerAdapter.cpp:643
cartographer
Definition: ArVizDrawer.h:40
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::localization_and_mapping::cartographer_adapter::CartographerAdapter::LaserScannerSensor::id
SensorId id
Definition: CartographerAdapter.h:116
PackagePath.h