submap_painter.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2017 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
21 
22 namespace cartographer {
23 namespace io {
24 namespace {
25 
26 Eigen::Affine3d ToEigen(const ::cartographer::transform::Rigid3d& rigid3) {
27  return Eigen::Translation3d(rigid3.translation()) * rigid3.rotation();
28 }
29 
30 void CairoPaintSubmapSlices(
31  const double scale,
32  const std::map<::cartographer::mapping::SubmapId, SubmapSlice>& submaps,
33  cairo_t* cr, std::function<void(const SubmapSlice&)> draw_callback) {
34  cairo_scale(cr, scale, scale);
35 
36  for (auto& pair : submaps) {
37  const auto& submap_slice = pair.second;
38  if (submap_slice.surface == nullptr) {
39  return;
40  }
41  const Eigen::Matrix4d homo =
42  ToEigen(submap_slice.pose * submap_slice.slice_pose).matrix();
43 
44  cairo_save(cr);
45  cairo_matrix_t matrix;
46  cairo_matrix_init(&matrix, homo(1, 0), homo(0, 0), -homo(1, 1), -homo(0, 1),
47  homo(0, 3), -homo(1, 3));
48  cairo_transform(cr, &matrix);
49 
50  const double submap_resolution = submap_slice.resolution;
51  cairo_scale(cr, submap_resolution, submap_resolution);
52 
53  // Invokes caller's callback to utilize slice data in global cooridnate
54  // frame. e.g. finds bounding box, paints slices.
55  draw_callback(submap_slice);
56  cairo_restore(cr);
57  }
58 }
59 
60 } // namespace
61 
63  const std::map<::cartographer::mapping::SubmapId, SubmapSlice>& submaps,
64  const double resolution) {
65  Eigen::AlignedBox2f bounding_box;
66  {
67  auto surface = MakeUniqueCairoSurfacePtr(
68  cairo_image_surface_create(kCairoFormat, 1, 1));
69  auto cr = MakeUniqueCairoPtr(cairo_create(surface.get()));
70  const auto update_bounding_box = [&bounding_box, &cr](double x, double y) {
71  cairo_user_to_device(cr.get(), &x, &y);
72  bounding_box.extend(Eigen::Vector2f(x, y));
73  };
74 
75  CairoPaintSubmapSlices(
76  1. / resolution, submaps, cr.get(),
77  [&update_bounding_box](const SubmapSlice& submap_slice) {
78  update_bounding_box(0, 0);
79  update_bounding_box(submap_slice.width, 0);
80  update_bounding_box(0, submap_slice.height);
81  update_bounding_box(submap_slice.width, submap_slice.height);
82  });
83  }
84 
85  const int kPaddingPixel = 5;
86  const Eigen::Array2i size(
87  std::ceil(bounding_box.sizes().x()) + 2 * kPaddingPixel,
88  std::ceil(bounding_box.sizes().y()) + 2 * kPaddingPixel);
89  const Eigen::Array2f origin(-bounding_box.min().x() + kPaddingPixel,
90  -bounding_box.min().y() + kPaddingPixel);
91 
92  auto surface = MakeUniqueCairoSurfacePtr(
93  cairo_image_surface_create(kCairoFormat, size.x(), size.y()));
94  {
95  auto cr = MakeUniqueCairoPtr(cairo_create(surface.get()));
96  cairo_set_source_rgba(cr.get(), 0.5, 0.0, 0.0, 1.);
97  cairo_paint(cr.get());
98  cairo_translate(cr.get(), origin.x(), origin.y());
99  CairoPaintSubmapSlices(1. / resolution, submaps, cr.get(),
100  [&cr](const SubmapSlice& submap_slice) {
101  cairo_set_source_surface(
102  cr.get(), submap_slice.surface.get(), 0., 0.);
103  cairo_paint(cr.get());
104  });
105  cairo_surface_flush(surface.get());
106  }
107  return PaintSubmapSlicesResult(std::move(surface), origin);
108 }
109 
111  const ::cartographer::transform::Rigid3d& global_submap_pose,
112  const ::cartographer::mapping::proto::Submap& proto,
113  SubmapSlice* const submap_slice) {
114  ::cartographer::mapping::proto::SubmapQuery::Response response;
116  if (proto.has_submap_3d()) {
117  mapping::Submap3D submap(proto.submap_3d());
118  local_pose = submap.local_pose();
119  submap.ToResponseProto(global_submap_pose, &response);
120  } else {
121  ::cartographer::mapping::Submap2D submap(proto.submap_2d());
122  local_pose = submap.local_pose();
123  submap.ToResponseProto(global_submap_pose, &response);
124  }
125  submap_slice->pose = global_submap_pose;
126 
127  auto& texture_proto = response.textures(0);
129  texture_proto.cells(), texture_proto.width(), texture_proto.height());
130  submap_slice->width = texture_proto.width();
131  submap_slice->height = texture_proto.height();
132  submap_slice->resolution = texture_proto.resolution();
133  submap_slice->slice_pose =
134  ::cartographer::transform::ToRigid3(texture_proto.slice_pose());
135  submap_slice->surface =
136  DrawTexture(pixels.intensity, pixels.alpha, texture_proto.width(),
137  texture_proto.height(), &submap_slice->cairo_data);
138 }
139 
140 SubmapTexture::Pixels UnpackTextureData(const std::string& compressed_cells,
141  const int width, const int height) {
142  SubmapTexture::Pixels pixels;
143  std::string cells;
144  ::cartographer::common::FastGunzipString(compressed_cells, &cells);
145  const int num_pixels = width * height;
146  CHECK_EQ(cells.size(), 2 * num_pixels);
147  pixels.intensity.reserve(num_pixels);
148  pixels.alpha.reserve(num_pixels);
149  for (int i = 0; i < height; ++i) {
150  for (int j = 0; j < width; ++j) {
151  pixels.intensity.push_back(cells[(i * width + j) * 2]);
152  pixels.alpha.push_back(cells[(i * width + j) * 2 + 1]);
153  }
154  }
155  return pixels;
156 }
157 
158 UniqueCairoSurfacePtr DrawTexture(const std::vector<char>& intensity,
159  const std::vector<char>& alpha,
160  const int width, const int height,
161  std::vector<uint32_t>* const cairo_data) {
162  CHECK(cairo_data->empty());
163 
164  // Properly dealing with a non-common stride would make this code much more
165  // complicated. Let's check that it is not needed.
166  const int expected_stride = 4 * width;
167  CHECK_EQ(expected_stride, cairo_format_stride_for_width(kCairoFormat, width));
168  for (size_t i = 0; i < intensity.size(); ++i) {
169  // We use the red channel to track intensity information. The green
170  // channel we use to track if a cell was ever observed.
171  const uint8_t intensity_value = intensity.at(i);
172  const uint8_t alpha_value = alpha.at(i);
173  const uint8_t observed =
174  (intensity_value == 0 && alpha_value == 0) ? 0 : 255;
175  cairo_data->push_back((alpha_value << 24) | (intensity_value << 16) |
176  (observed << 8) | 0);
177  }
178 
179  auto surface = MakeUniqueCairoSurfacePtr(cairo_image_surface_create_for_data(
180  reinterpret_cast<unsigned char*>(cairo_data->data()), kCairoFormat, width,
181  height, expected_stride));
182  CHECK_EQ(cairo_surface_status(surface.get()), CAIRO_STATUS_SUCCESS)
183  << cairo_status_to_string(cairo_surface_status(surface.get()));
184  return surface;
185 }
186 
187 } // namespace io
188 } // namespace cartographer
Rigid3< double > Rigid3d
::cartographer::transform::Rigid3d pose
UniqueCairoSurfacePtr MakeUniqueCairoSurfacePtr(cairo_surface_t *surface)
Definition: image.cc:41
PaintSubmapSlicesResult PaintSubmapSlices(const std::map<::cartographer::mapping::SubmapId, SubmapSlice > &submaps, const double resolution)
transform::Rigid3d ToRigid3(const proto::Rigid3d &rigid)
Definition: transform.cc:71
std::vector< uint32_t > cairo_data
constexpr cairo_format_t kCairoFormat
Definition: image.h:33
::cartographer::transform::Rigid3d slice_pose
void FillSubmapSlice(const ::cartographer::transform::Rigid3d &global_submap_pose, const ::cartographer::mapping::proto::Submap &proto, SubmapSlice *const submap_slice)
UniqueCairoSurfacePtr DrawTexture(const std::vector< char > &intensity, const std::vector< char > &alpha, const int width, const int height, std::vector< uint32_t > *const cairo_data)
void FastGunzipString(const std::string &compressed, std::string *decompressed)
Definition: port.h:60
::cartographer::io::UniqueCairoSurfacePtr surface
UniqueCairoPtr MakeUniqueCairoPtr(cairo_t *surface)
Definition: image.cc:45
Eigen::Transform< T, 2, Eigen::Affine > ToEigen(const Rigid2< T > &rigid2)
SubmapTexture::Pixels UnpackTextureData(const std::string &compressed_cells, const int width, const int height)
std::unique_ptr< cairo_surface_t, void(*)(cairo_surface_t *)> UniqueCairoSurfacePtr
Definition: image.h:38


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58