ObstaclesΒΆ

struct BoxΒΆ

A box collision object.

The Box struct represents a simple 3D rectangular collision object. It is defined by its dimensions along the x, y, and z axes, which correspond to the width, depth, and height of the box, respectively.

Public Functions

inline explicit Box(float x, float y, float z)ΒΆ

Construct a box of size x, y, z along the respective axes.

Parameters:
  • x – The width of the box along the x-axis.

  • y – The depth of the box along the y-axis.

  • z – The height of the box along the z-axis.

explicit Box() = defaultΒΆ

Default constructor.

Public Members

float xΒΆ

Dimensions of the box [m].

struct CapsuleΒΆ

A capsule collision object.

The Capsule struct represents a simple 3D collision object shaped like a capsule (a cylinder with hemispherical ends). It is defined by its radius and length along the z-axis. Capsules are commonly used in collision detection due to their computational efficiency.

Public Functions

inline explicit Capsule(float radius, float length)ΒΆ

Construct a capsule with the given radius and length.

Parameters:
  • radius – The radius of the capsule.

  • length – The length of the capsule along the z-axis.

explicit Capsule() = defaultΒΆ

Default constructor.

Public Members

float radiusΒΆ

Radius of the capsule [m].

float lengthΒΆ

Length of the capsule along the z-axis [m].

struct ConvexΒΆ

A convex mesh collision object.

The Convex struct represents a 3D convex mesh, often used for collision detection. It supports loading from files, direct vertex and triangle specification, and provides utility functions like bounding box computation.

Public Functions

explicit Convex() = defaultΒΆ

Default constructor.

explicit Convex(const std::filesystem::path &path, std::optional<float> scale)ΒΆ

Deprecated:

Construct a convex object by loading from a file.

Parameters:
  • path – The path to the file (*.obj).

  • scale – Optional scale to apply when loading the object.

explicit Convex(const std::vector<std::array<float, 3>> &verts, const std::vector<std::array<size_t, 3>> &triangs)ΒΆ

Construct a convex object from given vertices and triangles.

Parameters:
  • verts – List of vertex positions.

  • triangs – List of triangles, each defined by three vertex indices.

std::array<double, 3> get_bounding_box_minimum() constΒΆ

Get the minimum bounding box corner.

Returns:

A 3D vector representing the minimum corner of the bounding box.

std::array<double, 3> get_bounding_box_maximum() constΒΆ

Get the maximum bounding box corner.

Returns:

A 3D vector representing the maximum corner of the bounding box.

Public Members

std::vector<Vector> verticesΒΆ

List of vertices that define the convex mesh.

std::vector<Triangle> trianglesΒΆ

List of triangles that define the convex mesh surface.

std::optional<FileReference> file_referenceΒΆ

Deprecated:

Optional file reference from which the convex object was loaded.

Public Static Functions

static std::vector<Convex> load_from_file(const std::filesystem::path &path, std::optional<float> scale = std::nullopt)ΒΆ

Deprecated:

Load convex objects from a file.

Parameters:
  • path – The path to the file (*.obj).

  • scale – Optional scale to apply when loading the object.

Returns:

A vector of Convex objects loaded from the file.

Public Static Attributes

static std::filesystem::path base_pathΒΆ

Deprecated:

Base path for file operations.

class TriangleΒΆ
struct CylinderΒΆ

A cylinder collision object.

The Cylinder struct represents a 3D cylindrical collision object. It is defined by its radius and length along the z-axis.

Public Functions

inline explicit Cylinder(float radius, float length)ΒΆ

Construct a cylinder with the given radius and length.

Parameters:
  • radius – The radius of the cylinder.

  • length – The length of the cylinder along the z-axis.

explicit Cylinder() = defaultΒΆ

Default constructor.

Public Members

float radiusΒΆ

Radius of the cylinder [m].

float lengthΒΆ

Length of the cylinder along the z-axis [m].

struct DepthMapΒΆ

A depth map collision object.

The DepthMap struct represents a 3D collision object based on a depth map, which is essentially a grid of depth values.

Public Functions

inline explicit DepthMap(const Matrix &depths, float x, float y)ΒΆ

Construct a depth map with the given data.

Parameters:
  • depths – The matrix of depth values.

  • x – The size of the depth map along the x-axis.

  • y – The size of the depth map along the y-axis.

explicit DepthMap() = defaultΒΆ

Default constructor.

Public Members

Matrix depthsΒΆ

Matrix containing the depth values at evenly spaced grid points.

float xΒΆ

Size along the x-axis [m].

float yΒΆ

Size along the y-axis [m].

float max_depth = {1e2}ΒΆ

Maximum depth to check for collisions [m].

This value sets the maximum depth that will be considered during collision checking. Any depth greater than this value will be ignored. The default value is 100 meters.

struct MeshFileΒΆ

A collision object loaded from a file.

Public Functions

explicit MeshFile() = defaultΒΆ

Default constructor.

explicit MeshFile(const std::filesystem::path &path, std::optional<float> scale = std::nullopt)ΒΆ

Load a file obstacle.

Parameters:
  • path – The path to the collision file (*.obj).

  • scale – Optional scale to apply when loading the object.

explicit MeshFile(const std::filesystem::path &visual_path, const std::filesystem::path &collision_path, std::optional<float> scale = std::nullopt)ΒΆ

Load a file obstacle.

Parameters:
  • visual_path – The path to the visual file.

  • collision_path – The path to the collision file (*.obj).

  • scale – Optional scale to apply when loading the object.

Public Members

FileReference original_referenceΒΆ

The reference to the original file.

FileReference visual_referenceΒΆ

The reference to a visual file.

FileReference collision_referenceΒΆ

The reference to the collision file.

std::vector<Convex> collisionΒΆ

The convex obstacles for collision.

float scale = {1.0}ΒΆ

Scale of the object.

bool inside_project = {false}ΒΆ

Indicates if the file is part of a Jacobi Studio project. Then, the file content is not uploaded when referencing the file in Studio live.

Public Static Attributes

static std::filesystem::path base_pathΒΆ

Base path for file operations.

struct PointCloudΒΆ

A point cloud collision object.

The PointCloud struct represents a 3D collision object based on a point cloud, which is a set of [x, y, z] points.

Public Functions

inline explicit PointCloud(const Matrix &points, double resolution = 0.01)ΒΆ

Construct a point cloud with the given data.

Parameters:
  • points – The matrix (std::vector<std::array<float, 3>>) containing [x, y, z] points.

  • resolution – The resolution of the Octree that will be constructed from the point cloud and used for collision checking.

explicit PointCloud() = defaultΒΆ

Default constructor.

Public Members

double resolutionΒΆ

The resolution of the Octree that will be constructed from the point cloud and used for collision checking.

Matrix pointsΒΆ

Matrix containing [x, y, z] points.

struct SphereΒΆ

A sphere collision object.

The Sphere struct represents a 3D spherical collision object, defined by its radius, which determines its size in all directions.

Public Functions

inline explicit Sphere(float radius)ΒΆ

Construct a sphere with the given radius.

Initializes the sphere with the specified radius.

Parameters:

radius – The radius of the sphere.

explicit Sphere() = defaultΒΆ

Default constructor.

Public Members

float radiusΒΆ

Radius of the sphere [m].

class Obstacle : public jacobi::ElementΒΆ

An environment obstacle.

The Obstacle class represents an object in an environment that can be used for both visualization and collision detection. Obstacles can have various geometric shapes and properties, and can be associated with a robot or be independent within the environment.

Public Functions

explicit Obstacle() = defaultΒΆ

Default constructor.

Obstacle with_origin(const Frame &origin) constΒΆ

Clone the current obstacle and set the new origin.

Creates a copy of the current obstacle and updates its origin to the provided frame. This function is useful for creating modified versions of an obstacle without altering the original object.

Parameters:

origin – The new pose (origin) for the cloned obstacle.

Returns:

Obstacle A new Obstacle instance with the updated origin.

Obstacle with_name(const std::string &name) constΒΆ

Clone the current obstacle and update some parameters.

Creates a copy of the current obstacle and updates its name. This function is useful for creating modified versions of an obstacle without altering the original object.

Parameters:

name – The new name for the cloned obstacle.

Returns:

Obstacle A new Obstacle instance with the updated origin.

Public Members

Color colorΒΆ

The hex-string representation of the obstacle’s color, without the leading #.

This string defines the color of the obstacle for visualization purposes, formatted as a hex code (e.g., β€œFF5733” for orange).

std::optional<FileReference> visualΒΆ

Optional reference to the visual file.

This optional reference points to an external visual file that represents the obstacle. If provided, this file will be used for rendering the obstacle’s appearance.

Geometry collisionΒΆ

The object for collision checking (and/or visualization).

This variant holds the geometric representation of the obstacle. It can be any of the supported shapes, including Box, Capsule, Convex, ConvexVector, Cylinder, DepthMap, PointCloud or Sphere.

bool for_visual = {true}ΒΆ

Whether this obstacle is used for visualization.

If true, the obstacle will be rendered in the environment’s visualization in Studio. By default, this is set to true.

bool for_collision = {true}ΒΆ

Whether this obstacle is used for collision checking.

If true, the obstacle will be considered in collision detection calculations. By default, this is set to true.

float safety_margin = {0.0}ΒΆ

An additional obstacle-specific safety margin for collision checking (on top of the environment’s global safety margin).

This margin adds an extra buffer around the obstacle during collision detection. It is specific to this obstacle and is added on top of any global safety margins.

Robot *robot = {nullptr}ΒΆ

Pointer to the associated robot, if any.