Rerun C++ SDK
Loading...
Searching...
No Matches
grid_map.hpp
1// DO NOT EDIT! This file was auto-generated by crates/build/re_types_builder/src/codegen/cpp/mod.rs
2// Based on "crates/store/re_sdk_types/definitions/rerun/archetypes/grid_map.fbs".
3
4#pragma once
5
6#include "../collection.hpp"
7#include "../component_batch.hpp"
8#include "../component_column.hpp"
9#include "../components/cell_size.hpp"
10#include "../components/colormap.hpp"
11#include "../components/draw_order.hpp"
12#include "../components/image_buffer.hpp"
13#include "../components/image_format.hpp"
14#include "../components/opacity.hpp"
15#include "../components/rotation_axis_angle.hpp"
16#include "../components/rotation_quat.hpp"
17#include "../components/translation3d.hpp"
18#include "../result.hpp"
19
20#include <cstdint>
21#include <optional>
22#include <utility>
23#include <vector>
24
25namespace rerun::archetypes {
26 /// **Archetype**: A 2D grid map stored as raster data in an image buffer, with a cell size in scene units and pose.
27 ///
28 /// This archetype is intended for robotics applications like occupancy maps or navigation costmaps.
29 ///
30 /// ## Example
31 ///
32 /// ### Simple occupancy grid map
33 /// ```cpp
34 /// #include <rerun.hpp>
35 ///
36 /// #include <vector>
37 ///
38 /// int main(int argc, char* argv[]) {
39 /// const auto rec = rerun::RecordingStream("rerun_example_grid_map");
40 /// rec.spawn().exit_on_failure();
41 ///
42 /// const size_t width = 64;
43 /// const size_t height = 64;
44 /// const float cell_size = 0.1f;
45 ///
46 /// // Create a synthetic image with ROS `nav_msgs/OccupancyGrid` cell value conventions:
47 /// // -1 (255) unknown, 0 free, 100 occupied.
48 /// std::vector<uint8_t> grid(width * height, 255);
49 /// for (size_t y = 8; y <56; ++y) {
50 /// for (size_t x = 8; x <56; ++x) {
51 /// grid[y * width + x] = 0;
52 /// }
53 /// }
54 /// for (size_t y = 20; y <44; ++y) {
55 /// for (size_t x = 20; x <44; ++x) {
56 /// grid[y * width + x] = 100;
57 /// }
58 /// }
59 ///
60 /// rec.log(
61 /// "world/map",
62 /// rerun::archetypes::GridMap()
63 /// .with_data(rerun::components::ImageBuffer(grid))
64 /// .with_format(rerun::components::ImageFormat(
65 /// {width, height},
66 /// rerun::ColorModel::L,
67 /// rerun::ChannelDatatype::U8
68 /// ))
69 /// .with_cell_size(cell_size)
70 /// .with_translation(
71 /// {-(static_cast<float>(width) * cell_size) / 2.0f,
72 /// -(static_cast<float>(height) * cell_size) / 2.0f,
73 /// 0.0f}
74 /// )
75 /// .with_colormap(rerun::components::Colormap::RvizMap)
76 /// );
77 /// }
78 /// ```
79 struct GridMap {
80 /// The raw grid data.
81 std::optional<ComponentBatch> data;
82
83 /// The format of the grid's image data.
84 std::optional<ComponentBatch> format;
85
86 /// The scene unit size of a single grid cell (e.g. m / pixel).
87 std::optional<ComponentBatch> cell_size;
88
89 /// Translation of the lower-left corner of the grid map in space.
90 ///
91 /// Together with `components::RotationAxisAngle` or `components::RotationQuat`, this defines the pose of the
92 /// lower-left image corner relative to the map's parent coordinate frame.
93 ///
94 /// If not set, the lower-left image corner is placed at origin of the map's parent coordinate frame.
95 std::optional<ComponentBatch> translation;
96
97 /// Rotation of the lower-left corner of the grid map in space via axis + angle.
98 ///
99 /// Together with `components::Translation3D`, this defines the pose of the
100 /// lower-left image corner relative to the map's parent coordinate frame.
101 ///
102 /// Note: either this or `components::RotationQuat` can be set to specify the grid map's rotation, but not both.
103 /// If both this and `components::RotationQuat` are set, this is ignored in favor of the quaternion.
104 std::optional<ComponentBatch> rotation_axis_angle;
105
106 /// Rotation of the lower-left corner of the grid map in space via quaternion.
107 ///
108 /// Together with `components::Translation3D`, this defines the pose of the
109 /// lower-left image corner relative to the map's parent coordinate frame.
110 std::optional<ComponentBatch> quaternion;
111
112 /// Opacity of the grid map texture after all image decoding and colormap application.
113 ///
114 /// Defaults to 1.0 (fully opaque).
115 std::optional<ComponentBatch> opacity;
116
117 /// Optional draw order for layering multiple grid maps that overlap in space.
118 ///
119 /// Higher values are drawn on top of lower values.
120 std::optional<ComponentBatch> draw_order;
121
122 /// Colormap to use for rendering single-channel grid maps.
123 ///
124 /// If not set, the grid map is shown using the underlying `components::ImageFormat`
125 /// interpretation.
126 std::optional<ComponentBatch> colormap;
127
128 public:
129 /// The name of the archetype as used in `ComponentDescriptor`s.
130 static constexpr const char ArchetypeName[] = "rerun.archetypes.GridMap";
131
132 /// `ComponentDescriptor` for the `data` field.
133 static constexpr auto Descriptor_data = ComponentDescriptor(
135 );
136 /// `ComponentDescriptor` for the `format` field.
137 static constexpr auto Descriptor_format = ComponentDescriptor(
139 );
140 /// `ComponentDescriptor` for the `cell_size` field.
143 );
144 /// `ComponentDescriptor` for the `translation` field.
146 ArchetypeName, "GridMap:translation",
148 );
149 /// `ComponentDescriptor` for the `rotation_axis_angle` field.
151 ArchetypeName, "GridMap:rotation_axis_angle",
153 );
154 /// `ComponentDescriptor` for the `quaternion` field.
156 ArchetypeName, "GridMap:quaternion",
158 );
159 /// `ComponentDescriptor` for the `opacity` field.
162 );
163 /// `ComponentDescriptor` for the `draw_order` field.
165 ArchetypeName, "GridMap:draw_order",
167 );
168 /// `ComponentDescriptor` for the `colormap` field.
171 );
172
173 public:
174 GridMap() = default;
175 GridMap(GridMap&& other) = default;
176 GridMap(const GridMap& other) = default;
177 GridMap& operator=(const GridMap& other) = default;
178 GridMap& operator=(GridMap&& other) = default;
179
180 /// Update only some specific fields of a `GridMap`.
182 return GridMap();
183 }
184
185 /// Clear all the fields of a `GridMap`.
187
188 /// The raw grid data.
190 data = ComponentBatch::from_loggable(_data, Descriptor_data).value_or_throw();
191 return std::move(*this);
192 }
193
194 /// This method makes it possible to pack multiple `data` in a single component batch.
195 ///
196 /// This only makes sense when used in conjunction with `columns`. `with_data` should
197 /// be used when logging a single row's worth of data.
199 data = ComponentBatch::from_loggable(_data, Descriptor_data).value_or_throw();
200 return std::move(*this);
201 }
202
203 /// The format of the grid's image data.
205 format = ComponentBatch::from_loggable(_format, Descriptor_format).value_or_throw();
206 return std::move(*this);
207 }
208
209 /// This method makes it possible to pack multiple `format` in a single component batch.
210 ///
211 /// This only makes sense when used in conjunction with `columns`. `with_format` should
212 /// be used when logging a single row's worth of data.
214 format = ComponentBatch::from_loggable(_format, Descriptor_format).value_or_throw();
215 return std::move(*this);
216 }
217
218 /// The scene unit size of a single grid cell (e.g. m / pixel).
220 cell_size =
221 ComponentBatch::from_loggable(_cell_size, Descriptor_cell_size).value_or_throw();
222 return std::move(*this);
223 }
224
225 /// This method makes it possible to pack multiple `cell_size` in a single component batch.
226 ///
227 /// This only makes sense when used in conjunction with `columns`. `with_cell_size` should
228 /// be used when logging a single row's worth of data.
230 cell_size =
231 ComponentBatch::from_loggable(_cell_size, Descriptor_cell_size).value_or_throw();
232 return std::move(*this);
233 }
234
235 /// Translation of the lower-left corner of the grid map in space.
236 ///
237 /// Together with `components::RotationAxisAngle` or `components::RotationQuat`, this defines the pose of the
238 /// lower-left image corner relative to the map's parent coordinate frame.
239 ///
240 /// If not set, the lower-left image corner is placed at origin of the map's parent coordinate frame.
243 .value_or_throw();
244 return std::move(*this);
245 }
246
247 /// This method makes it possible to pack multiple `translation` in a single component batch.
248 ///
249 /// This only makes sense when used in conjunction with `columns`. `with_translation` should
250 /// be used when logging a single row's worth of data.
253 ) && {
255 .value_or_throw();
256 return std::move(*this);
257 }
258
259 /// Rotation of the lower-left corner of the grid map in space via axis + angle.
260 ///
261 /// Together with `components::Translation3D`, this defines the pose of the
262 /// lower-left image corner relative to the map's parent coordinate frame.
263 ///
264 /// Note: either this or `components::RotationQuat` can be set to specify the grid map's rotation, but not both.
265 /// If both this and `components::RotationQuat` are set, this is ignored in favor of the quaternion.
267 const rerun::components::RotationAxisAngle& _rotation_axis_angle
268 ) && {
271 .value_or_throw();
272 return std::move(*this);
273 }
274
275 /// This method makes it possible to pack multiple `rotation_axis_angle` in a single component batch.
276 ///
277 /// This only makes sense when used in conjunction with `columns`. `with_rotation_axis_angle` should
278 /// be used when logging a single row's worth of data.
280 const Collection<rerun::components::RotationAxisAngle>& _rotation_axis_angle
281 ) && {
284 .value_or_throw();
285 return std::move(*this);
286 }
287
288 /// Rotation of the lower-left corner of the grid map in space via quaternion.
289 ///
290 /// Together with `components::Translation3D`, this defines the pose of the
291 /// lower-left image corner relative to the map's parent coordinate frame.
293 quaternion =
294 ComponentBatch::from_loggable(_quaternion, Descriptor_quaternion).value_or_throw();
295 return std::move(*this);
296 }
297
298 /// This method makes it possible to pack multiple `quaternion` in a single component batch.
299 ///
300 /// This only makes sense when used in conjunction with `columns`. `with_quaternion` should
301 /// be used when logging a single row's worth of data.
303 ) && {
304 quaternion =
305 ComponentBatch::from_loggable(_quaternion, Descriptor_quaternion).value_or_throw();
306 return std::move(*this);
307 }
308
309 /// Opacity of the grid map texture after all image decoding and colormap application.
310 ///
311 /// Defaults to 1.0 (fully opaque).
313 opacity = ComponentBatch::from_loggable(_opacity, Descriptor_opacity).value_or_throw();
314 return std::move(*this);
315 }
316
317 /// This method makes it possible to pack multiple `opacity` in a single component batch.
318 ///
319 /// This only makes sense when used in conjunction with `columns`. `with_opacity` should
320 /// be used when logging a single row's worth of data.
322 opacity = ComponentBatch::from_loggable(_opacity, Descriptor_opacity).value_or_throw();
323 return std::move(*this);
324 }
325
326 /// Optional draw order for layering multiple grid maps that overlap in space.
327 ///
328 /// Higher values are drawn on top of lower values.
330 draw_order =
331 ComponentBatch::from_loggable(_draw_order, Descriptor_draw_order).value_or_throw();
332 return std::move(*this);
333 }
334
335 /// This method makes it possible to pack multiple `draw_order` in a single component batch.
336 ///
337 /// This only makes sense when used in conjunction with `columns`. `with_draw_order` should
338 /// be used when logging a single row's worth of data.
340 ) && {
341 draw_order =
342 ComponentBatch::from_loggable(_draw_order, Descriptor_draw_order).value_or_throw();
343 return std::move(*this);
344 }
345
346 /// Colormap to use for rendering single-channel grid maps.
347 ///
348 /// If not set, the grid map is shown using the underlying `components::ImageFormat`
349 /// interpretation.
351 colormap =
352 ComponentBatch::from_loggable(_colormap, Descriptor_colormap).value_or_throw();
353 return std::move(*this);
354 }
355
356 /// This method makes it possible to pack multiple `colormap` in a single component batch.
357 ///
358 /// This only makes sense when used in conjunction with `columns`. `with_colormap` should
359 /// be used when logging a single row's worth of data.
361 colormap =
362 ComponentBatch::from_loggable(_colormap, Descriptor_colormap).value_or_throw();
363 return std::move(*this);
364 }
365
366 /// Partitions the component data into multiple sub-batches.
367 ///
368 /// Specifically, this transforms the existing `ComponentBatch` data into `ComponentColumn`s
369 /// instead, via `ComponentBatch::partitioned`.
370 ///
371 /// This makes it possible to use `RecordingStream::send_columns` to send columnar data directly into Rerun.
372 ///
373 /// The specified `lengths` must sum to the total length of the component batch.
375
376 /// Partitions the component data into unit-length sub-batches.
377 ///
378 /// This is semantically similar to calling `columns` with `std::vector<uint32_t>(n, 1)`,
379 /// where `n` is automatically guessed.
381 };
382
383} // namespace rerun::archetypes
384
385namespace rerun {
386 /// \private
387 template <typename T>
388 struct AsComponents;
389
390 /// \private
391 template <>
392 struct AsComponents<archetypes::GridMap> {
393 /// Serialize all set component batches.
394 static Result<Collection<ComponentBatch>> as_batches(const archetypes::GridMap& archetype);
395 };
396} // namespace rerun
Generic collection of elements that are roughly contiguous in memory.
Definition collection.hpp:49
A class for representing either a usable value, or an error.
Definition result.hpp:14
All built-in archetypes. See Types in the Rerun manual.
Definition rerun.hpp:81
Colormap
Component: Colormap for mapping scalar values within a given range to a color.
Definition colormap.hpp:28
All Rerun C++ types and functions are in the rerun namespace or one of its nested namespaces.
Definition rerun.hpp:23
static Result< ComponentBatch > from_loggable(const rerun::Collection< T > &components, const ComponentDescriptor &descriptor)
Creates a new component batch from a collection of component instances.
Definition component_batch.hpp:46
A ComponentDescriptor fully describes the semantics of a column of data.
Definition component_descriptor.hpp:16
The Loggable trait is used by all built-in implementation of rerun::AsComponents to serialize a colle...
Definition loggable.hpp:11
Archetype: A 2D grid map stored as raster data in an image buffer, with a cell size in scene units an...
Definition grid_map.hpp:79
GridMap with_many_rotation_axis_angle(const Collection< rerun::components::RotationAxisAngle > &_rotation_axis_angle) &&
This method makes it possible to pack multiple rotation_axis_angle in a single component batch.
Definition grid_map.hpp:279
GridMap with_translation(const rerun::components::Translation3D &_translation) &&
Translation of the lower-left corner of the grid map in space.
Definition grid_map.hpp:241
std::optional< ComponentBatch > quaternion
Rotation of the lower-left corner of the grid map in space via quaternion.
Definition grid_map.hpp:110
static constexpr auto Descriptor_rotation_axis_angle
ComponentDescriptor for the rotation_axis_angle field.
Definition grid_map.hpp:150
std::optional< ComponentBatch > rotation_axis_angle
Rotation of the lower-left corner of the grid map in space via axis + angle.
Definition grid_map.hpp:104
static GridMap update_fields()
Update only some specific fields of a GridMap.
Definition grid_map.hpp:181
GridMap with_many_colormap(const Collection< rerun::components::Colormap > &_colormap) &&
This method makes it possible to pack multiple colormap in a single component batch.
Definition grid_map.hpp:360
GridMap with_many_quaternion(const Collection< rerun::components::RotationQuat > &_quaternion) &&
This method makes it possible to pack multiple quaternion in a single component batch.
Definition grid_map.hpp:302
std::optional< ComponentBatch > cell_size
The scene unit size of a single grid cell (e.g. m / pixel).
Definition grid_map.hpp:87
GridMap with_many_translation(const Collection< rerun::components::Translation3D > &_translation) &&
This method makes it possible to pack multiple translation in a single component batch.
Definition grid_map.hpp:251
static constexpr const char ArchetypeName[]
The name of the archetype as used in ComponentDescriptors.
Definition grid_map.hpp:130
std::optional< ComponentBatch > colormap
Colormap to use for rendering single-channel grid maps.
Definition grid_map.hpp:126
static constexpr auto Descriptor_translation
ComponentDescriptor for the translation field.
Definition grid_map.hpp:145
Collection< ComponentColumn > columns()
Partitions the component data into unit-length sub-batches.
GridMap with_many_opacity(const Collection< rerun::components::Opacity > &_opacity) &&
This method makes it possible to pack multiple opacity in a single component batch.
Definition grid_map.hpp:321
std::optional< ComponentBatch > format
The format of the grid's image data.
Definition grid_map.hpp:84
GridMap with_quaternion(const rerun::components::RotationQuat &_quaternion) &&
Rotation of the lower-left corner of the grid map in space via quaternion.
Definition grid_map.hpp:292
std::optional< ComponentBatch > translation
Translation of the lower-left corner of the grid map in space.
Definition grid_map.hpp:95
GridMap with_many_cell_size(const Collection< rerun::components::CellSize > &_cell_size) &&
This method makes it possible to pack multiple cell_size in a single component batch.
Definition grid_map.hpp:229
GridMap with_many_format(const Collection< rerun::components::ImageFormat > &_format) &&
This method makes it possible to pack multiple format in a single component batch.
Definition grid_map.hpp:213
static constexpr auto Descriptor_format
ComponentDescriptor for the format field.
Definition grid_map.hpp:137
std::optional< ComponentBatch > opacity
Opacity of the grid map texture after all image decoding and colormap application.
Definition grid_map.hpp:115
GridMap with_draw_order(const rerun::components::DrawOrder &_draw_order) &&
Optional draw order for layering multiple grid maps that overlap in space.
Definition grid_map.hpp:329
Collection< ComponentColumn > columns(const Collection< uint32_t > &lengths_)
Partitions the component data into multiple sub-batches.
GridMap with_colormap(const rerun::components::Colormap &_colormap) &&
Colormap to use for rendering single-channel grid maps.
Definition grid_map.hpp:350
static constexpr auto Descriptor_quaternion
ComponentDescriptor for the quaternion field.
Definition grid_map.hpp:155
static constexpr auto Descriptor_draw_order
ComponentDescriptor for the draw_order field.
Definition grid_map.hpp:164
GridMap with_many_data(const Collection< rerun::components::ImageBuffer > &_data) &&
This method makes it possible to pack multiple data in a single component batch.
Definition grid_map.hpp:198
GridMap with_rotation_axis_angle(const rerun::components::RotationAxisAngle &_rotation_axis_angle) &&
Rotation of the lower-left corner of the grid map in space via axis + angle.
Definition grid_map.hpp:266
GridMap with_many_draw_order(const Collection< rerun::components::DrawOrder > &_draw_order) &&
This method makes it possible to pack multiple draw_order in a single component batch.
Definition grid_map.hpp:339
std::optional< ComponentBatch > data
The raw grid data.
Definition grid_map.hpp:81
GridMap with_format(const rerun::components::ImageFormat &_format) &&
The format of the grid's image data.
Definition grid_map.hpp:204
GridMap with_data(const rerun::components::ImageBuffer &_data) &&
The raw grid data.
Definition grid_map.hpp:189
static constexpr auto Descriptor_opacity
ComponentDescriptor for the opacity field.
Definition grid_map.hpp:160
static GridMap clear_fields()
Clear all the fields of a GridMap.
std::optional< ComponentBatch > draw_order
Optional draw order for layering multiple grid maps that overlap in space.
Definition grid_map.hpp:120
GridMap with_opacity(const rerun::components::Opacity &_opacity) &&
Opacity of the grid map texture after all image decoding and colormap application.
Definition grid_map.hpp:312
static constexpr auto Descriptor_colormap
ComponentDescriptor for the colormap field.
Definition grid_map.hpp:169
static constexpr auto Descriptor_data
ComponentDescriptor for the data field.
Definition grid_map.hpp:133
static constexpr auto Descriptor_cell_size
ComponentDescriptor for the cell_size field.
Definition grid_map.hpp:141
GridMap with_cell_size(const rerun::components::CellSize &_cell_size) &&
The scene unit size of a single grid cell (e.g. m / pixel).
Definition grid_map.hpp:219
Component: The metric size of one grid cell in local scene units.
Definition cell_size.hpp:16
Component: Draw order of 2D elements.
Definition draw_order.hpp:19
Component: A buffer that is known to store image data.
Definition image_buffer.hpp:18
Component: The metadata describing the contents of a components::ImageBuffer.
Definition image_format.hpp:14
Component: Degree of transparency ranging from 0.0 (fully transparent) to 1.0 (fully opaque).
Definition opacity.hpp:17
Component: 3D rotation represented by a rotation around a given axis.
Definition rotation_axis_angle.hpp:17
Component: A 3D rotation expressed as a quaternion.
Definition rotation_quat.hpp:18
Component: A translation vector in 3D space.
Definition translation3d.hpp:15