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.
-
inline explicit Box()¶
Default constructor.
Public Members
-
float x¶
Dimensions of the box [m].
-
inline explicit Box(float x, float y, float z)¶
-
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.
-
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 constructor.
-
explicit Convex(const std::filesystem::path &path, std::optional<float> scale)¶
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(uintptr_t vertices_buffer, size_t size)¶
Construct a convex object using a buffer of vertices.
This constructor is primarily used for WebAssembly (Wasm) bindings, where the vertex data is provided directly as a buffer.
- Parameters:
vertices_buffer – Pointer to the buffer containing vertex data.
size – Number of vertices in the buffer.
-
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::optional<FileReference> file_reference¶
Optional file reference from which the convex object was loaded.
-
std::vector<Vector> vertices¶
List of vertices that define the convex mesh.
Public Static Functions
-
static std::vector<Convex> load_from_file(const std::filesystem::path &path, std::optional<float> scale = std::nullopt)¶
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.
-
static Convex reference_studio_file(const std::filesystem::path &path, std::optional<float> scale = std::nullopt)¶
Create a reference to a Studio file.
- Parameters:
path – The path to the Studio file.
scale – Optional scale to apply when referencing the file.
- Returns:
A Convex object that references the specified Studio file.
Public Static Attributes
-
static std::filesystem::path base_path¶
Base path for file operations.
-
class Triangle¶
-
explicit Convex()¶
-
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.
-
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.
-
inline explicit Sphere()¶
Default constructor.
Public Members
-
float radius¶
Radius of the sphere [m].
-
inline explicit Sphere(float radius)¶
-
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 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.
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, 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.
-
explicit Obstacle()¶