37 #ifndef MERGING_PIPELINE_H_ 38 #define MERGING_PIPELINE_H_ 42 #include <geometry_msgs/Transform.h> 43 #include <nav_msgs/OccupancyGrid.h> 45 #include <opencv2/core/utility.hpp> 58 template <
typename InputIt>
59 void feed(InputIt grids_begin, InputIt grids_end);
61 double confidence = 1.0);
62 nav_msgs::OccupancyGrid::Ptr composeGrids();
64 std::vector<geometry_msgs::Transform> getTransforms()
const;
65 template <
typename InputIt>
66 bool setTransforms(InputIt transforms_begin, InputIt transforms_end);
69 std::vector<nav_msgs::OccupancyGrid::ConstPtr>
grids_;
74 template <
typename InputIt>
77 static_assert(std::is_assignable<nav_msgs::OccupancyGrid::ConstPtr&,
78 decltype(*grids_begin)>::value,
79 "grids_begin must point to nav_msgs::OccupancyGrid::ConstPtr " 86 for (InputIt it = grids_begin; it != grids_end; ++it) {
87 if (*it && !(*it)->data.empty()) {
88 grids_.push_back(*it);
91 images_.emplace_back((*it)->info.height, (*it)->info.width, CV_8UC1,
92 const_cast<signed char*>((*it)->data.data()));
94 grids_.emplace_back();
95 images_.emplace_back();
100 template <
typename InputIt>
102 InputIt transforms_end)
104 static_assert(std::is_assignable<geometry_msgs::Transform&,
105 decltype(*transforms_begin)>::value,
106 "transforms_begin must point to geometry_msgs::Transform " 109 decltype(transforms_) transforms_buf;
110 for (InputIt it = transforms_begin; it != transforms_end; ++it) {
111 const geometry_msgs::Quaternion& q = it->rotation;
112 if ((q.x * q.x + q.y * q.y + q.z * q.z + q.w * q.w) <
113 std::numeric_limits<double>::epsilon()) {
115 transforms_buf.emplace_back();
118 double s = 2.0 / (q.x * q.x + q.y * q.y + q.z * q.z + q.w * q.w);
119 double a = 1 - q.y * q.y * s - q.z * q.z * s;
120 double b = q.x * q.y * s + q.z * q.w * s;
121 double tx = it->translation.x;
122 double ty = it->translation.y;
123 cv::Mat transform = cv::Mat::eye(3, 3, CV_64F);
124 transform.at<
double>(0, 0) = transform.at<
double>(1, 1) = a;
125 transform.at<
double>(1, 0) = b;
126 transform.at<
double>(0, 1) = -b;
127 transform.at<
double>(0, 2) = tx;
128 transform.at<
double>(1, 2) = ty;
130 transforms_buf.emplace_back(std::move(transform));
133 if (transforms_buf.size() != images_.size()) {
136 std::swap(transforms_, transforms_buf);
143 #endif // MERGING_PIPELINE_H_ std::vector< cv::Mat > transforms_
std::vector< cv::Mat > images_
Pipeline for merging overlapping occupancy grids.
bool setTransforms(InputIt transforms_begin, InputIt transforms_end)
void feed(InputIt grids_begin, InputIt grids_end)
std::vector< nav_msgs::OccupancyGrid::ConstPtr > grids_