|
Rerun C++ SDK
|
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 | |
| GridMap & | operator= (const GridMap &other)=default |
| GridMap & | operator= (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< ComponentColumn > | columns (const Collection< uint32_t > &lengths_) |
| Partitions the component data into multiple sub-batches. | |
| Collection< ComponentColumn > | columns () |
| 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< ComponentBatch > | data |
| The raw grid data. | |
| std::optional< ComponentBatch > | format |
| The format of the grid's image data. | |
| std::optional< ComponentBatch > | cell_size |
| The scene unit size of a single grid cell (e.g. m / pixel). | |
| std::optional< ComponentBatch > | translation |
| Translation of the lower-left corner of the grid map in space. | |
| std::optional< ComponentBatch > | rotation_axis_angle |
| Rotation of the lower-left corner of the grid map in space via axis + angle. | |
| std::optional< ComponentBatch > | quaternion |
| Rotation of the lower-left corner of the grid map in space via quaternion. | |
| std::optional< ComponentBatch > | opacity |
| Opacity of the grid map texture after all image decoding and colormap application. | |
| std::optional< ComponentBatch > | draw_order |
| Optional draw order for layering multiple grid maps that overlap in space. | |
| std::optional< ComponentBatch > | colormap |
| 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. | |
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.
⚠ This type is unstable and may change significantly in a way that the data won't be backwards compatible.
|
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.
|
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.
|
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.
|
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.
|
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.
|
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.
|
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.
|
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.
|
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.
|
inline |
Opacity of the grid map texture after all image decoding and colormap application.
Defaults to 1.0 (fully opaque).
|
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.
|
inline |
Optional draw order for layering multiple grid maps that overlap in space.
Higher values are drawn on top of lower values.
|
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.
|
inline |
Colormap to use for rendering single-channel grid maps.
If not set, the grid map is shown using the underlying components::ImageFormat interpretation.
|
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.
| 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.
| 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.
| 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.
| 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.
| 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.
| 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).
| 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.
| 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.
|
staticconstexpr |
ComponentDescriptor for the data field.
|
staticconstexpr |
ComponentDescriptor for the format field.
|
staticconstexpr |
ComponentDescriptor for the cell_size field.
|
staticconstexpr |
ComponentDescriptor for the translation field.
|
staticconstexpr |
ComponentDescriptor for the rotation_axis_angle field.
|
staticconstexpr |
ComponentDescriptor for the quaternion field.
|
staticconstexpr |
ComponentDescriptor for the opacity field.
|
staticconstexpr |
ComponentDescriptor for the draw_order field.
|
staticconstexpr |
ComponentDescriptor for the colormap field.