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 ///
80 /// ⚠ **This type is _unstable_ and may change significantly in a way that the data won't be backwards compatible.**
81 ///
82 struct GridMap {
83 /// The raw grid data.
84 std::optional<ComponentBatch> data;
85
86 /// The format of the grid's image data.
87 std::optional<ComponentBatch> format;
88
89 /// The scene unit size of a single grid cell (e.g. m / pixel).
90 std::optional<ComponentBatch> cell_size;
91
92 /// Translation of the lower-left corner of the grid map in space.
93 ///
94 /// Together with `components::RotationAxisAngle` or `components::RotationQuat`, this defines the pose of the
95 /// lower-left image corner relative to the map's parent coordinate frame.
96 ///
97 /// If not set, the lower-left image corner is placed at origin of the map's parent coordinate frame.
98 std::optional<ComponentBatch> translation;
99
100 /// Rotation of the lower-left corner of the grid map in space via axis + angle.
101 ///
102 /// Together with `components::Translation3D`, this defines the pose of the
103 /// lower-left image corner relative to the map's parent coordinate frame.
104 ///
105 /// Note: either this or `components::RotationQuat` can be set to specify the grid map's rotation, but not both.
106 /// If both this and `components::RotationQuat` are set, this is ignored in favor of the quaternion.
107 std::optional<ComponentBatch> rotation_axis_angle;
108
109 /// Rotation of the lower-left corner of the grid map in space via quaternion.
110 ///
111 /// Together with `components::Translation3D`, this defines the pose of the
112 /// lower-left image corner relative to the map's parent coordinate frame.
113 std::optional<ComponentBatch> quaternion;
114
115 /// Opacity of the grid map texture after all image decoding and colormap application.
116 ///
117 /// Defaults to 1.0 (fully opaque).
118 std::optional<ComponentBatch> opacity;
119
120 /// Optional draw order for layering multiple grid maps that overlap in space.
121 ///
122 /// Higher values are drawn on top of lower values.
123 std::optional<ComponentBatch> draw_order;
124
125 /// Colormap to use for rendering single-channel grid maps.
126 ///
127 /// If not set, the grid map is shown using the underlying `components::ImageFormat`
128 /// interpretation.
129 std::optional<ComponentBatch> colormap;
130
131 public:
132 /// The name of the archetype as used in `ComponentDescriptor`s.
133 static constexpr const char ArchetypeName[] = "rerun.archetypes.GridMap";
134
135 /// `ComponentDescriptor` for the `data` field.
136 static constexpr auto Descriptor_data = ComponentDescriptor(
138 );
139 /// `ComponentDescriptor` for the `format` field.
140 static constexpr auto Descriptor_format = ComponentDescriptor(
142 );
143 /// `ComponentDescriptor` for the `cell_size` field.
146 );
147 /// `ComponentDescriptor` for the `translation` field.
149 ArchetypeName, "GridMap:translation",
151 );
152 /// `ComponentDescriptor` for the `rotation_axis_angle` field.
154 ArchetypeName, "GridMap:rotation_axis_angle",
156 );
157 /// `ComponentDescriptor` for the `quaternion` field.
159 ArchetypeName, "GridMap:quaternion",
161 );
162 /// `ComponentDescriptor` for the `opacity` field.
165 );
166 /// `ComponentDescriptor` for the `draw_order` field.
168 ArchetypeName, "GridMap:draw_order",
170 );
171 /// `ComponentDescriptor` for the `colormap` field.
174 );
175
176 public:
177 GridMap() = default;
178 GridMap(GridMap&& other) = default;
179 GridMap(const GridMap& other) = default;
180 GridMap& operator=(const GridMap& other) = default;
181 GridMap& operator=(GridMap&& other) = default;
182
183 /// Update only some specific fields of a `GridMap`.
185 return GridMap();
186 }
187
188 /// Clear all the fields of a `GridMap`.
190
191 /// The raw grid data.
193 data = ComponentBatch::from_loggable(_data, Descriptor_data).value_or_throw();
194 return std::move(*this);
195 }
196
197 /// This method makes it possible to pack multiple `data` in a single component batch.
198 ///
199 /// This only makes sense when used in conjunction with `columns`. `with_data` should
200 /// be used when logging a single row's worth of data.
202 data = ComponentBatch::from_loggable(_data, Descriptor_data).value_or_throw();
203 return std::move(*this);
204 }
205
206 /// The format of the grid's image data.
208 format = ComponentBatch::from_loggable(_format, Descriptor_format).value_or_throw();
209 return std::move(*this);
210 }
211
212 /// This method makes it possible to pack multiple `format` in a single component batch.
213 ///
214 /// This only makes sense when used in conjunction with `columns`. `with_format` should
215 /// be used when logging a single row's worth of data.
217 format = ComponentBatch::from_loggable(_format, Descriptor_format).value_or_throw();
218 return std::move(*this);
219 }
220
221 /// The scene unit size of a single grid cell (e.g. m / pixel).
223 cell_size =
224 ComponentBatch::from_loggable(_cell_size, Descriptor_cell_size).value_or_throw();
225 return std::move(*this);
226 }
227
228 /// This method makes it possible to pack multiple `cell_size` in a single component batch.
229 ///
230 /// This only makes sense when used in conjunction with `columns`. `with_cell_size` should
231 /// be used when logging a single row's worth of data.
233 cell_size =
234 ComponentBatch::from_loggable(_cell_size, Descriptor_cell_size).value_or_throw();
235 return std::move(*this);
236 }
237
238 /// Translation of the lower-left corner of the grid map in space.
239 ///
240 /// Together with `components::RotationAxisAngle` or `components::RotationQuat`, this defines the pose of the
241 /// lower-left image corner relative to the map's parent coordinate frame.
242 ///
243 /// If not set, the lower-left image corner is placed at origin of the map's parent coordinate frame.
246 .value_or_throw();
247 return std::move(*this);
248 }
249
250 /// This method makes it possible to pack multiple `translation` in a single component batch.
251 ///
252 /// This only makes sense when used in conjunction with `columns`. `with_translation` should
253 /// be used when logging a single row's worth of data.
256 ) && {
258 .value_or_throw();
259 return std::move(*this);
260 }
261
262 /// Rotation of the lower-left corner of the grid map in space via axis + angle.
263 ///
264 /// Together with `components::Translation3D`, this defines the pose of the
265 /// lower-left image corner relative to the map's parent coordinate frame.
266 ///
267 /// Note: either this or `components::RotationQuat` can be set to specify the grid map's rotation, but not both.
268 /// If both this and `components::RotationQuat` are set, this is ignored in favor of the quaternion.
270 const rerun::components::RotationAxisAngle& _rotation_axis_angle
271 ) && {
274 .value_or_throw();
275 return std::move(*this);
276 }
277
278 /// This method makes it possible to pack multiple `rotation_axis_angle` in a single component batch.
279 ///
280 /// This only makes sense when used in conjunction with `columns`. `with_rotation_axis_angle` should
281 /// be used when logging a single row's worth of data.
283 const Collection<rerun::components::RotationAxisAngle>& _rotation_axis_angle
284 ) && {
287 .value_or_throw();
288 return std::move(*this);
289 }
290
291 /// Rotation of the lower-left corner of the grid map in space via quaternion.
292 ///
293 /// Together with `components::Translation3D`, this defines the pose of the
294 /// lower-left image corner relative to the map's parent coordinate frame.
296 quaternion =
297 ComponentBatch::from_loggable(_quaternion, Descriptor_quaternion).value_or_throw();
298 return std::move(*this);
299 }
300
301 /// This method makes it possible to pack multiple `quaternion` in a single component batch.
302 ///
303 /// This only makes sense when used in conjunction with `columns`. `with_quaternion` should
304 /// be used when logging a single row's worth of data.
306 ) && {
307 quaternion =
308 ComponentBatch::from_loggable(_quaternion, Descriptor_quaternion).value_or_throw();
309 return std::move(*this);
310 }
311
312 /// Opacity of the grid map texture after all image decoding and colormap application.
313 ///
314 /// Defaults to 1.0 (fully opaque).
316 opacity = ComponentBatch::from_loggable(_opacity, Descriptor_opacity).value_or_throw();
317 return std::move(*this);
318 }
319
320 /// This method makes it possible to pack multiple `opacity` in a single component batch.
321 ///
322 /// This only makes sense when used in conjunction with `columns`. `with_opacity` should
323 /// be used when logging a single row's worth of data.
325 opacity = ComponentBatch::from_loggable(_opacity, Descriptor_opacity).value_or_throw();
326 return std::move(*this);
327 }
328
329 /// Optional draw order for layering multiple grid maps that overlap in space.
330 ///
331 /// Higher values are drawn on top of lower values.
333 draw_order =
334 ComponentBatch::from_loggable(_draw_order, Descriptor_draw_order).value_or_throw();
335 return std::move(*this);
336 }
337
338 /// This method makes it possible to pack multiple `draw_order` in a single component batch.
339 ///
340 /// This only makes sense when used in conjunction with `columns`. `with_draw_order` should
341 /// be used when logging a single row's worth of data.
343 ) && {
344 draw_order =
345 ComponentBatch::from_loggable(_draw_order, Descriptor_draw_order).value_or_throw();
346 return std::move(*this);
347 }
348
349 /// Colormap to use for rendering single-channel grid maps.
350 ///
351 /// If not set, the grid map is shown using the underlying `components::ImageFormat`
352 /// interpretation.
354 colormap =
355 ComponentBatch::from_loggable(_colormap, Descriptor_colormap).value_or_throw();
356 return std::move(*this);
357 }
358
359 /// This method makes it possible to pack multiple `colormap` in a single component batch.
360 ///
361 /// This only makes sense when used in conjunction with `columns`. `with_colormap` should
362 /// be used when logging a single row's worth of data.
364 colormap =
365 ComponentBatch::from_loggable(_colormap, Descriptor_colormap).value_or_throw();
366 return std::move(*this);
367 }
368
369 /// Partitions the component data into multiple sub-batches.
370 ///
371 /// Specifically, this transforms the existing `ComponentBatch` data into `ComponentColumn`s
372 /// instead, via `ComponentBatch::partitioned`.
373 ///
374 /// This makes it possible to use `RecordingStream::send_columns` to send columnar data directly into Rerun.
375 ///
376 /// The specified `lengths` must sum to the total length of the component batch.
378
379 /// Partitions the component data into unit-length sub-batches.
380 ///
381 /// This is semantically similar to calling `columns` with `std::vector<uint32_t>(n, 1)`,
382 /// where `n` is automatically guessed.
384 };
385
386} // namespace rerun::archetypes
387
388namespace rerun {
389 /// \private
390 template <typename T>
391 struct AsComponents;
392
393 /// \private
394 template <>
395 struct AsComponents<archetypes::GridMap> {
396 /// Serialize all set component batches.
397 static Result<Collection<ComponentBatch>> as_batches(const archetypes::GridMap& archetype);
398 };
399} // 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:82
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:282
GridMap with_translation(const rerun::components::Translation3D &_translation) &&
Translation of the lower-left corner of the grid map in space.
Definition grid_map.hpp:244
std::optional< ComponentBatch > quaternion
Rotation of the lower-left corner of the grid map in space via quaternion.
Definition grid_map.hpp:113
static constexpr auto Descriptor_rotation_axis_angle
ComponentDescriptor for the rotation_axis_angle field.
Definition grid_map.hpp:153
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:107
static GridMap update_fields()
Update only some specific fields of a GridMap.
Definition grid_map.hpp:184
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:363
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:305
std::optional< ComponentBatch > cell_size
The scene unit size of a single grid cell (e.g. m / pixel).
Definition grid_map.hpp:90
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:254
static constexpr const char ArchetypeName[]
The name of the archetype as used in ComponentDescriptors.
Definition grid_map.hpp:133
std::optional< ComponentBatch > colormap
Colormap to use for rendering single-channel grid maps.
Definition grid_map.hpp:129
static constexpr auto Descriptor_translation
ComponentDescriptor for the translation field.
Definition grid_map.hpp:148
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:324
std::optional< ComponentBatch > format
The format of the grid's image data.
Definition grid_map.hpp:87
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:295
std::optional< ComponentBatch > translation
Translation of the lower-left corner of the grid map in space.
Definition grid_map.hpp:98
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:232
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:216
static constexpr auto Descriptor_format
ComponentDescriptor for the format field.
Definition grid_map.hpp:140
std::optional< ComponentBatch > opacity
Opacity of the grid map texture after all image decoding and colormap application.
Definition grid_map.hpp:118
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:332
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:353
static constexpr auto Descriptor_quaternion
ComponentDescriptor for the quaternion field.
Definition grid_map.hpp:158
static constexpr auto Descriptor_draw_order
ComponentDescriptor for the draw_order field.
Definition grid_map.hpp:167
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:201
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:269
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:342
std::optional< ComponentBatch > data
The raw grid data.
Definition grid_map.hpp:84
GridMap with_format(const rerun::components::ImageFormat &_format) &&
The format of the grid's image data.
Definition grid_map.hpp:207
GridMap with_data(const rerun::components::ImageBuffer &_data) &&
The raw grid data.
Definition grid_map.hpp:192
static constexpr auto Descriptor_opacity
ComponentDescriptor for the opacity field.
Definition grid_map.hpp:163
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:123
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:315
static constexpr auto Descriptor_colormap
ComponentDescriptor for the colormap field.
Definition grid_map.hpp:172
static constexpr auto Descriptor_data
ComponentDescriptor for the data field.
Definition grid_map.hpp:136
static constexpr auto Descriptor_cell_size
ComponentDescriptor for the cell_size field.
Definition grid_map.hpp:144
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:222
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