Rerun C++ SDK
Loading...
Searching...
No Matches
rerun::archetypes::GridMap Struct Reference

Archetype: A 2D grid map stored as raster data in an image buffer, with a cell size in scene units and pose. More...

#include <rerun/archetypes/grid_map.hpp>

Public Member Functions

 GridMap (GridMap &&other)=default
 
 GridMap (const GridMap &other)=default
 
GridMapoperator= (const GridMap &other)=default
 
GridMapoperator= (GridMap &&other)=default
 
GridMap with_data (const rerun::components::ImageBuffer &_data) &&
 The raw grid data.
 
GridMap with_many_data (const Collection< rerun::components::ImageBuffer > &_data) &&
 This method makes it possible to pack multiple data in a single component batch.
 
GridMap with_format (const rerun::components::ImageFormat &_format) &&
 The format of the grid's image data.
 
GridMap with_many_format (const Collection< rerun::components::ImageFormat > &_format) &&
 This method makes it possible to pack multiple format in a single component batch.
 
GridMap with_cell_size (const rerun::components::CellSize &_cell_size) &&
 The scene unit size of a single grid cell (e.g. m / pixel).
 
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.
 
GridMap with_translation (const rerun::components::Translation3D &_translation) &&
 Translation of the lower-left corner of the grid map in space.
 
GridMap with_many_translation (const Collection< rerun::components::Translation3D > &_translation) &&
 This method makes it possible to pack multiple translation in a single component batch.
 
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.
 
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.
 
GridMap with_quaternion (const rerun::components::RotationQuat &_quaternion) &&
 Rotation of the lower-left corner of the grid map in space via quaternion.
 
GridMap with_many_quaternion (const Collection< rerun::components::RotationQuat > &_quaternion) &&
 This method makes it possible to pack multiple quaternion in a single component batch.
 
GridMap with_opacity (const rerun::components::Opacity &_opacity) &&
 Opacity of the grid map texture after all image decoding and colormap application.
 
GridMap with_many_opacity (const Collection< rerun::components::Opacity > &_opacity) &&
 This method makes it possible to pack multiple opacity in a single component batch.
 
GridMap with_draw_order (const rerun::components::DrawOrder &_draw_order) &&
 Optional draw order for layering multiple grid maps that overlap in space.
 
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.
 
GridMap with_colormap (const rerun::components::Colormap &_colormap) &&
 Colormap to use for rendering single-channel grid maps.
 
GridMap with_many_colormap (const Collection< rerun::components::Colormap > &_colormap) &&
 This method makes it possible to pack multiple colormap in a single component batch.
 
Collection< ComponentColumncolumns (const Collection< uint32_t > &lengths_)
 Partitions the component data into multiple sub-batches.
 
Collection< ComponentColumncolumns ()
 Partitions the component data into unit-length sub-batches.
 

Static Public Member Functions

static GridMap update_fields ()
 Update only some specific fields of a GridMap.
 
static GridMap clear_fields ()
 Clear all the fields of a GridMap.
 

Public Attributes

std::optional< ComponentBatchdata
 The raw grid data.
 
std::optional< ComponentBatchformat
 The format of the grid's image data.
 
std::optional< ComponentBatchcell_size
 The scene unit size of a single grid cell (e.g. m / pixel).
 
std::optional< ComponentBatchtranslation
 Translation of the lower-left corner of the grid map in space.
 
std::optional< ComponentBatchrotation_axis_angle
 Rotation of the lower-left corner of the grid map in space via axis + angle.
 
std::optional< ComponentBatchquaternion
 Rotation of the lower-left corner of the grid map in space via quaternion.
 
std::optional< ComponentBatchopacity
 Opacity of the grid map texture after all image decoding and colormap application.
 
std::optional< ComponentBatchdraw_order
 Optional draw order for layering multiple grid maps that overlap in space.
 
std::optional< ComponentBatchcolormap
 Colormap to use for rendering single-channel grid maps.
 

Static Public Attributes

static constexpr const char ArchetypeName [] = "rerun.archetypes.GridMap"
 The name of the archetype as used in ComponentDescriptors.
 
static constexpr auto Descriptor_data
 ComponentDescriptor for the data field.
 
static constexpr auto Descriptor_format
 ComponentDescriptor for the format field.
 
static constexpr auto Descriptor_cell_size
 ComponentDescriptor for the cell_size field.
 
static constexpr auto Descriptor_translation
 ComponentDescriptor for the translation field.
 
static constexpr auto Descriptor_rotation_axis_angle
 ComponentDescriptor for the rotation_axis_angle field.
 
static constexpr auto Descriptor_quaternion
 ComponentDescriptor for the quaternion field.
 
static constexpr auto Descriptor_opacity
 ComponentDescriptor for the opacity field.
 
static constexpr auto Descriptor_draw_order
 ComponentDescriptor for the draw_order field.
 
static constexpr auto Descriptor_colormap
 ComponentDescriptor for the colormap field.
 

Detailed Description

Archetype: A 2D grid map stored as raster data in an image buffer, with a cell size in scene units and pose.

This archetype is intended for robotics applications like occupancy maps or navigation costmaps.

Example

Simple occupancy grid map

#include <rerun.hpp>
#include <vector>
int main(int argc, char* argv[]) {
const auto rec = rerun::RecordingStream("rerun_example_grid_map");
rec.spawn().exit_on_failure();
const size_t width = 64;
const size_t height = 64;
const float cell_size = 0.1f;
// Create a synthetic image with ROS `nav_msgs/OccupancyGrid` cell value conventions:
// -1 (255) unknown, 0 free, 100 occupied.
std::vector<uint8_t> grid(width * height, 255);
for (size_t y = 8; y <56; ++y) {
for (size_t x = 8; x <56; ++x) {
grid[y * width + x] = 0;
}
}
for (size_t y = 20; y <44; ++y) {
for (size_t x = 20; x <44; ++x) {
grid[y * width + x] = 100;
}
}
rec.log(
"world/map",
{width, height},
rerun::ColorModel::L,
rerun::ChannelDatatype::U8
))
{-(static_cast<float>(width) * cell_size) / 2.0f,
-(static_cast<float>(height) * cell_size) / 2.0f,
0.0f}
)
);
}
A RecordingStream handles everything related to logging data into Rerun.
Definition recording_stream.hpp:73
@ RvizMap
The classic RViz "Map" grid-map colormap intended for occupancy-style SLAM grid maps.
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_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 > cell_size
The scene unit size of a single grid cell (e.g. m / pixel).
Definition grid_map.hpp:90
GridMap with_colormap(const rerun::components::Colormap &_colormap) &&
Colormap to use for rendering single-channel grid maps.
Definition grid_map.hpp:353
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
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: 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

This type is unstable and may change significantly in a way that the data won't be backwards compatible.

Member Function Documentation

◆ with_many_data()

GridMap rerun::archetypes::GridMap::with_many_data ( const Collection< rerun::components::ImageBuffer > &  _data) &&
inline

This method makes it possible to pack multiple data in a single component batch.

This only makes sense when used in conjunction with columns. with_data should be used when logging a single row's worth of data.

◆ with_many_format()

GridMap rerun::archetypes::GridMap::with_many_format ( const Collection< rerun::components::ImageFormat > &  _format) &&
inline

This method makes it possible to pack multiple format in a single component batch.

This only makes sense when used in conjunction with columns. with_format should be used when logging a single row's worth of data.

◆ with_many_cell_size()

GridMap rerun::archetypes::GridMap::with_many_cell_size ( const Collection< rerun::components::CellSize > &  _cell_size) &&
inline

This method makes it possible to pack multiple cell_size in a single component batch.

This only makes sense when used in conjunction with columns. with_cell_size should be used when logging a single row's worth of data.

◆ with_translation()

GridMap rerun::archetypes::GridMap::with_translation ( const rerun::components::Translation3D _translation) &&
inline

Translation of the lower-left corner of the grid map in space.

Together with components::RotationAxisAngle or components::RotationQuat, this defines the pose of the lower-left image corner relative to the map's parent coordinate frame.

If not set, the lower-left image corner is placed at origin of the map's parent coordinate frame.

◆ with_many_translation()

GridMap rerun::archetypes::GridMap::with_many_translation ( const Collection< rerun::components::Translation3D > &  _translation) &&
inline

This method makes it possible to pack multiple translation in a single component batch.

This only makes sense when used in conjunction with columns. with_translation should be used when logging a single row's worth of data.

◆ with_rotation_axis_angle()

GridMap rerun::archetypes::GridMap::with_rotation_axis_angle ( const rerun::components::RotationAxisAngle _rotation_axis_angle) &&
inline

Rotation of the lower-left corner of the grid map in space via axis + angle.

Together with components::Translation3D, this defines the pose of the lower-left image corner relative to the map's parent coordinate frame.

Note: either this or components::RotationQuat can be set to specify the grid map's rotation, but not both. If both this and components::RotationQuat are set, this is ignored in favor of the quaternion.

◆ with_many_rotation_axis_angle()

GridMap rerun::archetypes::GridMap::with_many_rotation_axis_angle ( const Collection< rerun::components::RotationAxisAngle > &  _rotation_axis_angle) &&
inline

This method makes it possible to pack multiple rotation_axis_angle in a single component batch.

This only makes sense when used in conjunction with columns. with_rotation_axis_angle should be used when logging a single row's worth of data.

◆ with_quaternion()

GridMap rerun::archetypes::GridMap::with_quaternion ( const rerun::components::RotationQuat _quaternion) &&
inline

Rotation of the lower-left corner of the grid map in space via quaternion.

Together with components::Translation3D, this defines the pose of the lower-left image corner relative to the map's parent coordinate frame.

◆ with_many_quaternion()

GridMap rerun::archetypes::GridMap::with_many_quaternion ( const Collection< rerun::components::RotationQuat > &  _quaternion) &&
inline

This method makes it possible to pack multiple quaternion in a single component batch.

This only makes sense when used in conjunction with columns. with_quaternion should be used when logging a single row's worth of data.

◆ with_opacity()

GridMap rerun::archetypes::GridMap::with_opacity ( const rerun::components::Opacity _opacity) &&
inline

Opacity of the grid map texture after all image decoding and colormap application.

Defaults to 1.0 (fully opaque).

◆ with_many_opacity()

GridMap rerun::archetypes::GridMap::with_many_opacity ( const Collection< rerun::components::Opacity > &  _opacity) &&
inline

This method makes it possible to pack multiple opacity in a single component batch.

This only makes sense when used in conjunction with columns. with_opacity should be used when logging a single row's worth of data.

◆ with_draw_order()

GridMap rerun::archetypes::GridMap::with_draw_order ( const rerun::components::DrawOrder _draw_order) &&
inline

Optional draw order for layering multiple grid maps that overlap in space.

Higher values are drawn on top of lower values.

◆ with_many_draw_order()

GridMap rerun::archetypes::GridMap::with_many_draw_order ( const Collection< rerun::components::DrawOrder > &  _draw_order) &&
inline

This method makes it possible to pack multiple draw_order in a single component batch.

This only makes sense when used in conjunction with columns. with_draw_order should be used when logging a single row's worth of data.

◆ with_colormap()

GridMap rerun::archetypes::GridMap::with_colormap ( const rerun::components::Colormap _colormap) &&
inline

Colormap to use for rendering single-channel grid maps.

If not set, the grid map is shown using the underlying components::ImageFormat interpretation.

◆ with_many_colormap()

GridMap rerun::archetypes::GridMap::with_many_colormap ( const Collection< rerun::components::Colormap > &  _colormap) &&
inline

This method makes it possible to pack multiple colormap in a single component batch.

This only makes sense when used in conjunction with columns. with_colormap should be used when logging a single row's worth of data.

◆ columns() [1/2]

Collection< ComponentColumn > rerun::archetypes::GridMap::columns ( const Collection< uint32_t > &  lengths_)

Partitions the component data into multiple sub-batches.

Specifically, this transforms the existing ComponentBatch data into ComponentColumns instead, via ComponentBatch::partitioned.

This makes it possible to use RecordingStream::send_columns to send columnar data directly into Rerun.

The specified lengths must sum to the total length of the component batch.

◆ columns() [2/2]

Collection< ComponentColumn > rerun::archetypes::GridMap::columns ( )

Partitions the component data into unit-length sub-batches.

This is semantically similar to calling columns with std::vector<uint32_t>(n, 1), where n is automatically guessed.

Member Data Documentation

◆ translation

std::optional<ComponentBatch> rerun::archetypes::GridMap::translation

Translation of the lower-left corner of the grid map in space.

Together with components::RotationAxisAngle or components::RotationQuat, this defines the pose of the lower-left image corner relative to the map's parent coordinate frame.

If not set, the lower-left image corner is placed at origin of the map's parent coordinate frame.

◆ rotation_axis_angle

std::optional<ComponentBatch> rerun::archetypes::GridMap::rotation_axis_angle

Rotation of the lower-left corner of the grid map in space via axis + angle.

Together with components::Translation3D, this defines the pose of the lower-left image corner relative to the map's parent coordinate frame.

Note: either this or components::RotationQuat can be set to specify the grid map's rotation, but not both. If both this and components::RotationQuat are set, this is ignored in favor of the quaternion.

◆ quaternion

std::optional<ComponentBatch> rerun::archetypes::GridMap::quaternion

Rotation of the lower-left corner of the grid map in space via quaternion.

Together with components::Translation3D, this defines the pose of the lower-left image corner relative to the map's parent coordinate frame.

◆ opacity

std::optional<ComponentBatch> rerun::archetypes::GridMap::opacity

Opacity of the grid map texture after all image decoding and colormap application.

Defaults to 1.0 (fully opaque).

◆ draw_order

std::optional<ComponentBatch> rerun::archetypes::GridMap::draw_order

Optional draw order for layering multiple grid maps that overlap in space.

Higher values are drawn on top of lower values.

◆ colormap

std::optional<ComponentBatch> rerun::archetypes::GridMap::colormap

Colormap to use for rendering single-channel grid maps.

If not set, the grid map is shown using the underlying components::ImageFormat interpretation.

◆ Descriptor_data

constexpr auto rerun::archetypes::GridMap::Descriptor_data
staticconstexpr
Initial value:
= ComponentDescriptor(
ArchetypeName, "GridMap:data", Loggable<rerun::components::ImageBuffer>::ComponentType
)
static constexpr const char ArchetypeName[]
The name of the archetype as used in ComponentDescriptors.
Definition grid_map.hpp:133

ComponentDescriptor for the data field.

◆ Descriptor_format

constexpr auto rerun::archetypes::GridMap::Descriptor_format
staticconstexpr
Initial value:
= ComponentDescriptor(
ArchetypeName, "GridMap:format", Loggable<rerun::components::ImageFormat>::ComponentType
)

ComponentDescriptor for the format field.

◆ Descriptor_cell_size

constexpr auto rerun::archetypes::GridMap::Descriptor_cell_size
staticconstexpr
Initial value:
= ComponentDescriptor(
ArchetypeName, "GridMap:cell_size", Loggable<rerun::components::CellSize>::ComponentType
)

ComponentDescriptor for the cell_size field.

◆ Descriptor_translation

constexpr auto rerun::archetypes::GridMap::Descriptor_translation
staticconstexpr
Initial value:
= ComponentDescriptor(
ArchetypeName, "GridMap:translation",
Loggable<rerun::components::Translation3D>::ComponentType
)

ComponentDescriptor for the translation field.

◆ Descriptor_rotation_axis_angle

constexpr auto rerun::archetypes::GridMap::Descriptor_rotation_axis_angle
staticconstexpr
Initial value:
= ComponentDescriptor(
ArchetypeName, "GridMap:rotation_axis_angle",
Loggable<rerun::components::RotationAxisAngle>::ComponentType
)

ComponentDescriptor for the rotation_axis_angle field.

◆ Descriptor_quaternion

constexpr auto rerun::archetypes::GridMap::Descriptor_quaternion
staticconstexpr
Initial value:
= ComponentDescriptor(
ArchetypeName, "GridMap:quaternion",
Loggable<rerun::components::RotationQuat>::ComponentType
)

ComponentDescriptor for the quaternion field.

◆ Descriptor_opacity

constexpr auto rerun::archetypes::GridMap::Descriptor_opacity
staticconstexpr
Initial value:
= ComponentDescriptor(
ArchetypeName, "GridMap:opacity", Loggable<rerun::components::Opacity>::ComponentType
)

ComponentDescriptor for the opacity field.

◆ Descriptor_draw_order

constexpr auto rerun::archetypes::GridMap::Descriptor_draw_order
staticconstexpr
Initial value:
= ComponentDescriptor(
ArchetypeName, "GridMap:draw_order",
Loggable<rerun::components::DrawOrder>::ComponentType
)

ComponentDescriptor for the draw_order field.

◆ Descriptor_colormap

constexpr auto rerun::archetypes::GridMap::Descriptor_colormap
staticconstexpr
Initial value:
= ComponentDescriptor(
ArchetypeName, "GridMap:colormap", Loggable<rerun::components::Colormap>::ComponentType
)

ComponentDescriptor for the colormap field.


The documentation for this struct was generated from the following file: