Single-Body Objects

raisim::SingleBodyObject is an object with only one rigid body. raisim::Compound is also a SingleBodyObject because its components move together as one rigid body. All SingleBodyObjects have 6 degrees of freedom: 3 for position and 3 for orientation.

Primitives

The following five primitive shapes are supported in RaiSim.

../_images/SingleBodyObjects.png

Compound

An example can be found here.

raisim::Compound has multiple primitive shapes that are rigidly attached to each other to form a single rigid body. The shapes do not have to overlap to stay attached.

A compound object can be added to the world using the method raisim::World::addCompound. This method takes a vector of children, which have their own shape, material, position, and orientation. The shape can be specified by a geometric type (i.e., raisim::ObjectType) and its size parameters (objectParam). The objectParam follows a standard way to represent the size of a primitive in RaiSim:

  • Sphere: radius, 0, 0, 0

  • Box: x, y, z, 0

  • Capsule and cylinder: radius, height, 0, 0

The objectParam is an instance of raisim::Vec<4>. All shapes require fewer than four parameters and the unused elements (i.e., the zeroes above) are ignored.

The trans member defines the position and orientation of the child in the body frame. It is a struct with public rot and pos members.

The mass, COM, and inertia arguments specify the dynamical properties of the combined body.

Mesh

mesh

raisim::Mesh represents a single-body object defined by a triangle mesh. It is commonly used for props, scanned objects, and imported object models. Meshes are added via raisim::World::addMesh.

Public mesh collision modes

The public addMesh API exposes three collision representations:

  • MeshCollisionMode::CONVEXIFY: CoACD convex decomposition. This creates multiple convex collision parts from one mesh. This is the default.

  • MeshCollisionMode::CONVEX_HULL: one convex hull built from the mesh.

  • MeshCollisionMode::ORIGINAL_MESH: the original non-convex triangle mesh.

Original non-convex triangle mesh collision is useful for imported visual meshes that are invalid CoACD input, but it is usually slower and less robust than convex collision geometry.

Default convexify

The shortest overload uses CoACD convex decomposition by default and estimates inertia/COM from the scaled axis-aligned bounding box. If CoACD cannot process the mesh, RaiSim warns and falls back to original non-convex triangle mesh collision:

auto* mesh = world.addMesh(meshFile, mass, scale);

The explicit-inertia overload is also convexified by default:

auto* mesh = world.addMesh(meshFile, mass, inertia, com, scale);

Explicit collision modes

Use MeshCollisionMode::CONVEX_HULL for the cheapest convex mesh collider:

auto* mesh = world.addMesh(meshFile, mass, scale, "",
                           raisim::MeshCollisionMode::CONVEX_HULL);

Use MeshCollisionMode::ORIGINAL_MESH when you intentionally want the non-convex triangle mesh:

auto* mesh = world.addMesh(meshFile, mass, scale, "",
                           raisim::MeshCollisionMode::ORIGINAL_MESH);

You can still pass MeshCollisionMode::CONVEXIFY explicitly when you want to make the default choice visible at the call site:

auto* mesh = world.addMesh(meshFile, mass, scale, "",
                           raisim::MeshCollisionMode::CONVEXIFY);

Custom CoACD options

Tune CoacdOptions when you need more or fewer convex parts. Lower thresholds and larger maxConvexHull values can preserve more shape detail, but they increase build time and can make contact processing slower.

raisim::CoacdOptions options;
options.threshold = 0.08;
options.maxConvexHull = 8;
options.sampleResolution = 1200;
options.mctsIteration = 80;

auto* mesh = world.addMesh(meshFile, mass, scale, "",
                           raisim::MeshCollisionMode::CONVEXIFY,
                           raisim::CollisionGroup(1),
                           raisim::CollisionGroup(-1),
                           options);

You can also pass options directly:

auto* mesh = world.addMesh(meshFile, mass, scale, "", options);

CoACD input requirements

The bundled CoACD integration is intentionally small and does not include heavy preprocessing dependencies. It works best with closed, reasonably manifold meshes.

If MeshCollisionMode::CONVEXIFY fails, RaiSim prints a warning and falls back to original non-convex triangle mesh collision for that object. This keeps imported visual meshes such as robot body panels usable when they are not valid CoACD input. The fallback is a compatibility path, not the preferred high-performance collider: it can be slower and less robust than convex hulls or CoACD parts, especially for dynamic object stacks or dense contact scenes. For performance-critical simulation, use a cleaner manifold mesh, a preprocessed convex collision asset, or the default MeshCollisionMode::CONVEX_HULL path.

CoACD cache files

Successful MeshCollisionMode::CONVEXIFY calls write an OBJ cache beside the source mesh. This keeps repeated runs cheap: the first call pays the CoACD decomposition cost, while later calls with the same parameters load the saved convex parts directly.

The file name starts with raisim_coacd_ and includes the source mesh stem, scale, and CoACD option values, for example:

raisim_coacd_model_scale_1_threshold_0_08_maxhull_8_..._realmetric_0.obj

The cache stores each convex part as a separate OBJ group named raisim_coacd_part_N. On later addMesh calls with the same source mesh and CoACD parameters, RaiSim loads these groups instead of running CoACD again. The loaded convex parts are expected to match the generated parts exactly.

If the source mesh is newer than the cache file, RaiSim recomputes the decomposition and overwrites the cache. Different CoACD settings produce different cache file names, so changing options such as threshold, maxConvexHull, sampleResolution, or mctsIteration does not reuse an incompatible cache.

For a 16k-triangle YCB apple mesh using the default CoACD options, a local timing run took about 4.3 seconds on the first uncached call and about 49 ms on the second cached call. Exact timings are machine- and mesh-dependent, but large meshes should see the largest benefit.

These files are generated artifacts and are ignored by the repository .gitignore rules via raisim_coacd_*. Delete the corresponding raisim_coacd_* file manually if you want to force a fresh decomposition without editing the source mesh.

Inspection helpers

raisim::Mesh exposes the generated convex parts for debugging and visualization:

const auto& parts = mesh->getCoacdConvexParts();
std::cout << mesh->getCollisionBodyCount() << std::endl;

When CoACD falls back to original non-convex mesh collision, getCoacdConvexParts() is empty and getCollisionBodyCount() returns 1.

The rayrai example rayrai_coacd_mesh_approximation displays original meshes next to colored convex decomposition parts.

Mesh collision is supported for mesh formats handled by Assimp. Keep collision meshes reasonably sized for performance.

SingleBodyObject API (Parent class)

class SingleBodyObject : public raisim::Object

this class is only for inheritance

Subclassed by raisim::Box, raisim::Capsule, raisim::Compound, raisim::Cone, raisim::Cylinder, raisim::Ground, raisim::HeightMap, raisim::Mesh, raisim::Sphere

Public Functions

inline Eigen::Vector4d getQuaternion() const

returns the quaternion in Eigen::Vector4d

Returns:

the orientation of the object

inline void getQuaternion(Vec<4> &quat) const

returns the quaternion in raisim::Vec<4>

Parameters:

quat[out] the orientation of the object

inline Eigen::Matrix3d getRotationMatrix() const

returns the rotation matrix in Eigen::Matrix3d

Returns:

the orientation of the object

inline void getRotationMatrix(Mat<3, 3> &rotation) const

returns the quaternion in raisim::Mat<3,3>

Parameters:

rotation[out] the orientation of the object

inline Eigen::Vector3d getPosition() const

returns the body position in Eigen::Vector3d. Currently, all body positions are the same as the COM position

Returns:

the position of the object

inline Eigen::Vector3d getComPosition() const

returns the body position in Eigen::Vector3d. Currently, all body positions are the same as the COM position

Returns:

the position of the object

inline const raisim::Vec<3> &getComPosition_rs() const

returns the body position in raisim::Vec<3>. Currently, all body positions are the same as the COM position

Returns:

the position of the object

inline const raisim::Vec<3> &getBodyToComPosition_rs() const

returns the body position in raisim::Vec<3>. Currently, all body positions are the same as the COM position

Returns:

the position of the object

inline Eigen::Vector3d getLinearVelocity() const

returns the linear velocity

Returns:

the linear velocity of the object

inline void getLinearVelocity(Vec<3> &linVel)

returns the linear velocity

Parameters:

linVel[out] the linear velocity of the object

inline Eigen::Vector3d getAngularVelocity() const

returns the angular velocity

Returns:

the angular velocity of the object

inline void getAngularVelocity(Vec<3> &angVel)

returns the angular velocity

Parameters:

angVel[out] the angular velocity of the object

inline virtual void getPosition(size_t localIdx, Vec<3> &pos_w) const final

returns position vector.

Parameters:
  • localIdx[in] this should be always 0 (this method is just to keep the same api as the ArticulatedSystem class)

  • pos_w[out] the position vector of the object

inline virtual void getOrientation(size_t localIdx, Mat<3, 3> &rot) const final

returns the orientation of the object

Parameters:
  • localIdx[in] local idx should be always 0 (this method is just to keep the same api as the ArticulatedSystem class)

  • rot[out] the rotation matrix of the object

inline const Mat<3, 3> &getOrientation() const

returns the rotation matrix

Returns:

rotation matrix

double getKineticEnergy() const

returns the kinetic energy

Returns:

the kinetic energy of the object

double getPotentialEnergy(const Vec<3> &gravity) const

returns the potential energy w.r.t. z=0 and the given gravitational acceleration

Parameters:

gravity[in] gravitational acceleration

Returns:

the potential energy of the object

double getEnergy(const Vec<3> &gravity) const

equivalent to getKineticEnergy() + getPotentialEnergy(gravity)

Parameters:

gravity[in] gravitational acceleration

Returns:

the sum of the potential and gravitational energy of the object

Eigen::Vector3d getLinearMomentum() const

returns the linear momentum of the object

Returns:

the linear momentum of the object

virtual double getMass(size_t localIdx = 0) const override

returns the mass of the object. The localIdx is unused

Returns:

the mass of the object

inline void setMass(double mass)

set the mass of the object.

Parameters:

mass[in] set the mass of the object

inline Eigen::Matrix3d getInertiaMatrix_B() const

get the inertia matrix in the body frame. This value is constant.

Returns:

the inertia matrix in the body frame

inline Eigen::Matrix3d getInertiaMatrix_W() const

get the inertia matrix in the world frame. This value changes as the body rotates.

Returns:

the inertia matrix in the world frame

inline const raisim::Mat<3, 3> &getInertiaMatrix_B_rs() const

get the inertia matrix in the body frame (raisim matrix type). This value is constant.

Returns:

the inertia matrix in the body frame

inline const raisim::Mat<3, 3> &getInertiaMatrix_W_rs() const

get the inertia matrix in the world frame (raisim matrix type). This value changes as the body rotates.

Returns:

the inertia matrix in the world frame

virtual ObjectType getObjectType() const final

get the object type. Possible types are SPHERE, BOX, CYLINDER, CONE, CAPSULE, MESH, HALFSPACE, COMPOUND, HEIGHTMAP, ARTICULATED_SYSTEM

Returns:

the object type

virtual void setPosition(const Eigen::Ref<const Eigen::Vector3d, Eigen::Unaligned> &originPosition)

Set position of the object (using Eigen)

Parameters:

originPosition[in] Position

virtual void setPosition(double x, double y, double z)

Set position of the object (using three doubles)

Parameters:
  • x[in] x position

  • y[in] y position

  • z[in] z position

inline virtual void setOrientation(const Eigen::Quaterniond &quaternion)

Set orientation of the object (using Eigen::Quaterniond)

Parameters:

quaternion[in] quaternion

inline virtual void setOrientation(const Eigen::Vector4d &quaternion)

Set orientation of the object (using Eigen::Vector4d)

Parameters:

quaternion[in] quaternion

inline virtual void setOrientation(const Vec<4> &quaternion)

Set orientation of the object (using raisim::Vec<4>)

Parameters:

quaternion[in] quaternion

inline virtual void setOrientation(double w, double x, double y, double z)

Set orientation of the object (using doubles)

Parameters:
  • w[in] w

  • x[in] w

  • y[in] w

  • z[in] w

inline virtual void setOrientation(const Eigen::Matrix3d &rotationMatrix)

Set orientation of the object (using Eigen::Matrix3d)

Parameters:

rotationMatrix[in] rotation matrix

inline virtual void setOrientation(const Mat<3, 3> &rotationMatrix)

Set orientation of the object (using raisim::Mat<3,3>)

Parameters:

rotationMatrix[in] rotation matrix

inline virtual void setPose(const Eigen::Vector3d &originPosition, const Eigen::Quaterniond &quaternion)

Set both the position and orientation of the object (using Eigen::Vector3d and Eigen::Quaterniond)

Parameters:
  • originPosition[in] position

  • quaternion[in] quaternion

inline virtual void setPose(const Eigen::Vector3d &originPosition, const Eigen::Vector4d &quaternion)

Set both the position and orientation of the object (using Eigen::Vector3d and Eigen::Vector4d)

Parameters:
  • originPosition[in] position

  • quaternion[in] quaternion

inline virtual void setPose(const Eigen::Vector3d &originPosition, const Eigen::Matrix3d &rotationMatrix)

Set both the position and orientation of the object (using Eigen::Vector3d and Eigen::Matrix3d)

Parameters:
  • originPosition[in] position

  • rotationMatrix[in] rotation matrix

void setInertia(const Eigen::Ref<const Eigen::Matrix3d, Eigen::Unaligned> &inertia)

Set inertia of the object (using Eigen::Matrix3d)

Parameters:

inertia[in] inertia of the object

inline const Vec<3> &getCom()

get the center of mass position

Returns:

the position of the center of mass

inline void setCom(const Vec<3> &com)

set the center of mass position

Parameters:

com[in] the position of the center of mass

inline virtual void setVelocity(const Eigen::Ref<const Eigen::Vector3d, Eigen::Unaligned> &linearVelocity, const Eigen::Ref<const Eigen::Vector3d, Eigen::Unaligned> &angularVelocity)

set both the linear and angular velocity of the object (using Eigen::Vector3d)

Parameters:
  • linearVelocity[in] the linear velocity of the object

  • angularVelocity[in] the angular velocity of the object

inline virtual void setVelocity(double dx, double dy, double dz, double wx, double wy, double wz)

set both the linear and angular velocity of the object (using 6 doubles)

Parameters:
  • dx[in] the x-axis linear velocity of the object

  • dy[in] the y-axis linear velocity of the object

  • dz[in] the z-axis linear velocity of the object

  • wx[in] the x-axis angular velocity of the object

  • wy[in] the y-axis angular velocity of the object

  • wz[in] the z-axis angular velocity of the object

inline void setLinearVelocity(const Vec<3> &linearVelocity)

set only the linear velocity

Parameters:

linearVelocity[in] the linear velocity

inline void setAngularVelocity(const Vec<3> &angularVelocity)

set only the angular velocity

Parameters:

angularVelocity[in] the angular velocity

virtual void setExternalForce(size_t localIdx, const Vec<3> &force) final

set external force on the object

Parameters:
  • localIdx[in] this should always be 0 (because the single body object only has one body)

  • force[in] force acting on the center of the mass (expressed in the world frame)

virtual void setExternalTorque(size_t localIdx, const Vec<3> &torque) final

set external torque on the object

Parameters:
  • localIdx[in] this should always be 0 (because the single body object only has one body)

  • torque[in] torque acting on body (expressed in the world frame)

virtual void setExternalForce(size_t localIdx, const Vec<3> &pos, const Vec<3> &force) final

set external force on the object

Parameters:
  • localIdx[in] this should always be 0 (because the single body object only has one body)

  • pos[in] the application point of the force (expressed in the world frame)

  • force[in] force acting on the center of the mass (expressed in the world frame)

virtual void setConstraintForce(size_t localIdx, const Vec<3> &pos, const Vec<3> &force) final

should not be used by the users

virtual void getPosition(size_t localIdx, const Vec<3> &pos_b, Vec<3> &pos_w) const final

Get position of a point on the body

Parameters:
  • localIdx[in] this should always be 0 (because the single body object only has one body)

  • pos_b[in] the position of the body

  • pos_w[out] the corresponding position in the world

inline void getPosition(Vec<3> &pos_w)

Get the geometric center of the object

Parameters:

pos_w[out] the geometric center

virtual void getContactPointVel(size_t pointId, Vec<3> &vel) const final

get the contact point velocity in the world frame.

Parameters:
  • pointId[in] the contact index. This is an index of a contact in the contact vector that you can retrieve from getContacts().

  • vel[out] the contact point velocity in the world frame

void setLinearDamping(double damping)

Set the linear damping that the object experiences due to air

Parameters:

damping[in] the damping coefficient in the body frame

void setAngularDamping(Vec<3> damping)

Set the angular damping that the object experiences due to air (proportional to the angular velocity).

Parameters:

damping[in] the damping coefficient in the body frame

virtual void setBodyType(BodyType type)

set the body type. Dynamic means that object is free to move. Kinematic means that the object can have velocity but has an infinite mass (like a conveyor belt). Static means that the object cannot move and has an infinite mass.

Parameters:

type[in] the body type

CollisionGroup getCollisionGroup()

get the current collision group of the object. Read the “Contact and Collision” to learn what the collision group is.

Returns:

the collision group

CollisionGroup getCollisionMask()

get the current collision mast of the object. Read the “Contact and Collision” to learn what the collision mast is.

Returns:

the collision mast

inline void setAppearance(const std::string &appearance)

set the appearance of the object. This works in both RaisimUnity and RaisimUnreal. But depending on the visualizer, they might do different things. You can specify the color by name like “blue”, “green”, “red” You can also specify the color by a string like “0, 0.5, 0.5, 1.0”, which represent the RGBA values

Parameters:

appearance[in] the appearance of the object

inline const std::string &getAppearance() const

get the current appearance of the object

Returns:

appearance

inline virtual void clearExternalForcesAndTorques() override

delete all external forces and torques specified on the object. This method is called at the end of every frame.

Compound API

class Compound : public raisim::SingleBodyObject

Public Functions

inline const std::vector<CompoundObjectChild> &getObjList()

returns the children of the compound

Returns:

the children of the compound

inline const std::vector<CollisionBodyHandle> &getCollisionBodyList()

returns the collision list of the compound

Returns:

the collision list of the compound

virtual void setBodyType(BodyType type) final

set the body type. Dynamic means that object is free to move. Kinematic means that the object can have velocity but has an infinite mass (like a conveyor belt). Static means that the object cannot move and has an infinite mass.

Parameters:

type[in] the body type

struct CompoundObjectChild

Public Members

std::string childCompound

Child compound name (reserved, currently unused).

ObjectType objectType

Child object type.

Vec<4> objectParam

Child shape parameters.

std::string material

Material name for contacts.

std::string appearance

Appearance material name for visualization.

Transformation trans

Transform from compound frame to child frame.

Sphere API

class Sphere : public raisim::SingleBodyObject

Public Functions

explicit Sphere(double radius, double mass)

NOTE body frame origin of Sphere is C.O.M of Sphere

double getRadius() const

returns the radius of the sphere

Returns:

the radius of the sphere

Box API

class Box : public raisim::SingleBodyObject

Public Functions

Box(double xLength, double yLength, double zLength, double mass)

NOTE body origin of Box is C.O.M of Box

inline Vec<3> getDim()

returns the dimension of the box

Returns:

the box dimensions

Capsule API

class Capsule : public raisim::SingleBodyObject

Public Functions

Capsule(double radius, double height, double mass)

NOTE body origin of Capsule is C.O.M of Capsule

double getRadius() const

returns the radius of the capsule

Returns:

the radius of the capsule

double getHeight() const

returns the height of the capsule

Returns:

the height of the capsule

Cylinder API

class Cylinder : public raisim::SingleBodyObject

Public Functions

Cylinder(double radius, double height, double mass)

NOTE body frame origin of Cylinder is C.O.M of Cylinder

double getRadius() const

returns the radius of the cylinder

Returns:

the radius of the cylinder

double getHeight() const

returns the height of the cylinder

Returns:

the height of the cylinder

Ground API

class Ground : public raisim::SingleBodyObject

Public Functions

inline double getHeight() const

returns the height of the plane

Returns:

the height

virtual void setPosition(const Eigen::Ref<const Eigen::Vector3d, Eigen::Unaligned> &originPosition) override

Set position of the object (using Eigen)

Parameters:

originPosition[in] Position

virtual void setPosition(double x, double y, double z) override

Set position of the object (using three doubles)

Parameters:
  • x[in] x position

  • y[in] y position

  • z[in] z position

Mesh API

class Mesh : public raisim::SingleBodyObject

Public Functions

virtual void setBodyType(BodyType type) override

set the body type. Dynamic means that object is free to move. Kinematic means that the object can have velocity but has an infinite mass (like a conveyor belt). Static means that the object cannot move and has an infinite mass.

Parameters:

type[in] the body type

struct ConvexPart