Objects
Body types
RaiSim uses BodyType to describe whether a body or particle is integrated
as a dynamic state, moved kinematically, or treated as static collision
geometry. There are three available body types:
DYNAMIC: can have a velocity, has finite massKINEMATIC: can have a velocity, has infinite mass (e.g., conveyor belt)STATIC: cannot have a velocity, has infinite mass (e.g., wall)
SingleBodyObject instances can be any of the three body types.
ArticulatedSystem instances are dynamic, except fixed-base systems can
report static base bodies. DeformableObject particles are dynamic unless
they are pinned, in which case the pinned particle reports STATIC.
GranularSystem particles are dynamic unless they are marked fixed, in which
case the fixed particle reports STATIC.
You can get or set the body type using:
setBodyType(BodyType type)getBodyType()orgetBodyType(body_index)
For multi-body or multi-particle objects, pass the local body/particle index to
getBodyType(localIdx) when querying a specific element.
Object Identity And Indices
Every object has both a world index and a stable id:
getIndexInWorld()is the object’s current position inWorld::getObjects(). It is useful for iterating the current world state, but it can change when objects are removed and the world’s object list is compacted.getId()is assigned byWorldand remains stable for the lifetime of the object. Use it for runtime scene editing, visualizer bookkeeping, or application-side maps that must survive object-list compaction.
Local indices are separate from both of these. A SingleBodyObject has local
index 0. ArticulatedSystem local indices refer to links. DeformableObject
and GranularSystem local indices refer to particles.
Name
All objects can be named. These names are used by visualizers. raisim::World provides functionality to retrieve an object by name. Here is an example.
auto sphere = world.addSphere(1,1);
sphere->setName("sphere");
std::string name = sphere->getName();
auto same_sphere = world.getObject("sphere");
Types
The common base class is raisim::Object. Concrete object families include:
SingleBodyObject: primitive and mesh rigid bodies with one body index.ArticulatedSystem: URDF/MJCF-style multi-body robots and mechanisms.DeformableObject: XPBD/PBD cloth, shell, and coarse soft-body objects.GranularSystem: many spherical grains stored and stepped as one object.
- Articulated Systems
- TL;DR
- Introduction
- Creating an instance
- URDF modules (optional attachments)
- URDF loader details
- State Representation
- Joints
- URDF convention
- Kinematics
- Dynamics
- Inverse Dynamics
- PD Controller
- Integration Steps
- Get and Modify Robot Description in Code
- Apply External Forces/Torques
- Collision
- Types of Indices
- Closed-loop system
- API
- Single-Body Objects
- Deformable Objects
- Granular Media
- Overview
- API Surface
- Data Model
- Creating Granular Media
- Material Parameters
- Particle Materials And Boundary Materials
- Contact And Rigid-Body Interaction
- Boundaries
- Particle Lifecycle
- External Forces And Fixed Particles
- State, Statistics, And Diagnostics
- Save And Load
- Visualization
- Numerical Tuning
- Performance Model
- Limitations
- API Reference
Contacts And External Forces
getContacts() returns the contacts accumulated on an object during the last
world step. Contact point ids are local to that contact list and can be passed
to getContactPointVel(pointId, vel) to query the world-frame contact-point
velocity.
External forces and torques use local body or particle indices:
object->setExternalForce(localIdx, {0.0, 0.0, 5.0});
object->setExternalTorque(localIdx, {0.0, 0.0, 0.2});
object->clearExternalForcesAndTorques();
For rigid bodies and articulated links, setExternalForce(localIdx, pos, force)
applies a world-frame force at a body-frame position. For particle-like objects
such as deformables and granular systems, use the particle index as localIdx.
Threaded Visualization
Object exposes lockMutex/unlockMutex and lock/unlock for
applications that update object state while a visualizer or another thread is
reading it. Prefer std::scoped_lock in user code so exceptions or early
returns do not leave the object locked:
std::scoped_lock guard(*object);
object->setName("updated_name");
API
-
class Object
Subclassed by raisim::ArticulatedSystem, raisim::DeformableObject, raisim::GranularSystem, raisim::SingleBodyObject
Public Functions
-
size_t getIndexInWorld() const
get the world index. raisim::World::getObjects() returns a vector of object pointers. This is method returns the index of this object in the vector.
- Returns:
the world index
-
inline Id getId() const
Returns a stable object id assigned by the world. Unlike getIndexInWorld(), this id is not changed when world indices are compacted after removals.
-
const std::vector<Contact> &getContacts() const
get a vector of all contacts on the object.
- Returns:
contacts on the body
-
virtual void setExternalForce(size_t localIdx, const Vec<3> &force) = 0
apply forces at the Center of Mass
-
virtual void setExternalTorque(size_t localIdx, const Vec<3> &torque) = 0
apply torque on a body
-
virtual void setExternalForce(size_t localIdx, const Vec<3> &pos, const Vec<3> &force) = 0
apply force (expressed in the world frame) at specific location of the body (expressed in the body frame)
-
virtual void setConstraintForce(size_t localIdx, const Vec<3> &pos, const Vec<3> &force) = 0
apply spring force (expressed in the world frame) at specific location of the body (expressed in the body frame)
-
virtual ObjectType getObjectType() const = 0
get the object type. Possible types are SPHERE, BOX, CYLINDER, CONE, CAPSULE, MESH, HALFSPACE, COMPOUND, HEIGHTMAP, ARTICULATED_SYSTEM
- Returns:
the object type
-
inline virtual BodyType getBodyType(size_t localIdx) const
get the object body type. Available types are: DYNAMIC (movable and finite mass), STATIC (not movable and infinite mass), KINETIC (movable and infinite mass)
- Returns:
the body type
-
inline virtual BodyType getBodyType() const
get the object body type. Available types are: DYNAMIC (movable and finite mass), STATIC (not movable and infinite mass), KINETIC (movable and infinite mass).
- Returns:
the body type
-
virtual void getContactPointVel(size_t pointId, Vec<3> &vel) const = 0
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
-
inline void setName(const std::string &name)
set the name of the object. You can retrieve an object by name using raisim::World::getObject()
- Parameters:
name – [in] name of the object.
-
inline const std::string &getName() const
get the name of the object
- Returns:
name of the object
-
inline const std::vector<Vec<3>> &getExternalForce() const
- Returns:
External forces currently applied for visualization (world frame).
-
inline const std::vector<Vec<3>> &getExternalForcePosition() const
- Returns:
Positions where external forces are applied (world frame).
-
inline const std::vector<Vec<3>> &getExternalTorque() const
- Returns:
External torques currently applied for visualization (world frame).
-
inline const std::vector<Vec<3>> &getExternalTorquePosition() const
- Returns:
Positions where external torques are applied (world frame).
-
inline void lockMutex()
locks chart mutex. This can be used if you use raisim in a multi-threaded environment.
-
inline void unlockMutex()
unlock chart mutex. This can be used if you use raisim in a multi-threaded environment.
-
size_t getIndexInWorld() const