RobWorkProject  23.9.11-
Classes | Typedefs | Enumerations | Enumerator | Functions
Dynamics

Classes

class  BeamBody
 A deformable body composed of a sequence of connected rigid bodies. More...
 
struct  BodyInfo
 Body info holds the values that determine the dynamic behavior of the body, such as mass and inertia. More...
 
class  Body
 The body interface describe the basic interface of some physical entity in the virtual world. That is as a minimum the body has a geometric description, and a material identity. More...
 
class  Constraint
 A constraint is a mathematical model that constrain the movement between two arbitrary bodies in a dynamic simulation. More...
 
class  ContactCluster
 calculates contact clusters More...
 
class  ContactDataMap
 This class is a storage component for storing collision/contact data information. More...
 
class  ContactPoint
 representation of a contact point More...
 
class  DynamicDevice
 base class for dynamic devices that has dynamic state values such as velocity and acceleration. More...
 
class  DynamicUtil
 Utility functions for calculating dynamic properties. More...
 
struct  WorkCellDimension
 the WorkCellDimension describe a center and the box halflengths of the space that the WorkCell expands. More...
 
class  DynamicWorkCell
 the DynamicWorkcell class is a container class for dynamic information/data in a workcell, much like WorkCell is a container class for the kinematic information/data in a workcell More...
 
class  FixedBody
 a body with a fixed position, zero velocity and zero force. More...
 
class  FixedLink
 
class  KinematicBody
 a kinematic body is a body that effects the motion of other objects but it is not directly affected itself. More...
 
class  KinematicDevice
 a kinematic device is able to influence the simulated environment but the device is not influenced by any external force as is the RigidDevice. More...
 
class  Link
 The Link is a body that is part of a dynamic device where joints are used to constrain the movement of links. More...
 
struct  FrictionData
 Definition of a friction model. More...
 
class  MaterialDataMap
 A map of materials and friction models defined between materials. More...
 
class  RigidBody
 A body is an abstraction over some physical object in the scene. The body class is an abstract class that allows interaction by adding gravity, forces and impulses. The integration scheme used to update the velocity and position of the body is defined by the class that inherit the body interface. More...
 
class  RigidDevice
 the Rigid device is composed of a set of links where one or multiple constraints (joints) connect the links. The RigidDevice has motors on all active joints. These motors can be operated in either velocity control mode or force control mode. More...
 
class  ScapePoseFormat
 saving object poses in Scape format. More...
 
class  BodyController
 The body controller is a pure interface through which bodies are controlled. More...
 
class  TactileArraySensor
 the TactileMatrixSensor class combines a TactileMatrix data type with the actual shape of a tactile sensor. The shape is described with a matrix of 3d vertices. Such that tactil (0,0) maps to the quad defined by the four vertices {(0,0),(0,1),(1,1),(1,0)}. Notice that the normal is defined by sequence of the vertices and that the normal defines the direction of tactile sensing. More...
 
class  FiniteStateSampler
 a state sampler that will sample a finite set of states. The nr of samples is not necesdarilly finite since states are allowed to be sampled multiple times. More...
 

Typedefs

typedef std::pair< std::string, rw::math::QFrictionParam
 Definition of a parameter for a friction model.
 
typedef rw::core::Ptr< RigidDevicePtr
 Smart pointer type for a dynamic device.
 

Enumerations

enum  FrictionType { Coulomb , Custom }
 Predefined friction types.
 
enum  MotorControlMode { Force , Velocity }
 Possible control modes for the motors in each joint. More...
 

Functions

 RigidDevice (dynamics::Body::Ptr base, const std::vector< std::pair< BodyInfo, rw::models::Object::Ptr >> &objects, rw::models::JointDevice::Ptr dev)
 Construct new kinematic device. More...
 
virtual ~RigidDevice ()
 Destructor.
 
void setMotorForceLimits (const rw::math::Q &force)
 set the force limits of all motors of this device More...
 
rw::math::Q getMotorForceLimits ()
 get the force limits of all motors of this device
 
rw::math::Q getJointVelocities (const rw::kinematics::State &state)
 get velocities of all motorized joints More...
 
double getJointVelocity (int i, const rw::kinematics::State &state)
 Get the velocity of a motorized joint. More...
 
void setJointVelocities (const rw::math::Q &q, rw::kinematics::State &state)
 set the joint velocities More...
 
void setJointVelocity (double vel, int i, rw::kinematics::State &state)
 Set the velocity of a motorized joint. More...
 
std::vector< MotorControlModegetMotorModes (const rw::kinematics::State &state)
 get the modes of all motors
 
MotorControlMode getMotorMode (int i, const rw::kinematics::State &state)
 Get the control mode for a single motor. More...
 
rw::math::Q getMotorTargets (const rw::kinematics::State &state)
 get the target off all motors More...
 
double getMotorTarget (int i, const rw::kinematics::State &state)
 Get the target for a single motor. More...
 
void setMotorTargets (const rw::math::Q &q, rw::kinematics::State &state)
 set target of all motors More...
 
void setMotorForceTargets (const rw::math::Q &force, rw::kinematics::State &state)
 Set force targets for all motors. More...
 
void setMotorVelocityTargets (const rw::math::Q &vel, rw::kinematics::State &state)
 Set velocity targets for all motors. More...
 
void setMotorTarget (double q, int i, rw::kinematics::State &state)
 set the target of motor i. the target may be a desired force or a desired velocity depending on the current mode of the motor. More...
 
void setMotorForceTarget (double force, int i, rw::kinematics::State &state)
 Set force target for a single motor. More...
 
void setMotorVelocityTarget (double vel, int i, rw::kinematics::State &state)
 Set velocity target for a single motor. More...
 
rw::models::JointDevice::Ptr getJointDevice ()
 Get the kinematic model of the device. More...
 
const std::vector< Body::Ptr > & getLinks ()
 Get the links of the device. More...
 

Detailed Description

Enumeration Type Documentation

◆ MotorControlMode

Possible control modes for the motors in each joint.

Enumerator
Force 

For force control.

Velocity 

For velocity control.

Function Documentation

◆ getJointDevice()

rw::models::JointDevice::Ptr getJointDevice ( )
inline

Get the kinematic model of the device.

Returns
the kinematic model.

◆ getJointVelocities()

rw::math::Q getJointVelocities ( const rw::kinematics::State state)
virtual

get velocities of all motorized joints

Parameters
state[in] the state.
Returns
the joint velocities.

Implements DynamicDevice.

◆ getJointVelocity()

double getJointVelocity ( int  i,
const rw::kinematics::State state 
)

Get the velocity of a motorized joint.

Parameters
i[in] the joint to get velocity for.
state[in] the state.
Returns
the velocity for the given joint.

◆ getLinks()

const std::vector<Body::Ptr>& getLinks ( )
inlinevirtual

Get the links of the device.

Returns
the links.

Implements DynamicDevice.

◆ getMotorMode()

MotorControlMode getMotorMode ( int  i,
const rw::kinematics::State state 
)

Get the control mode for a single motor.

Parameters
i[in] the joint number.
state[in] the state.
Returns
the control mode.

◆ getMotorTarget()

double getMotorTarget ( int  i,
const rw::kinematics::State state 
)

Get the target for a single motor.

Parameters
i[in] the joint number.
state[in] the state.
Returns
the current target.

◆ getMotorTargets()

rw::math::Q getMotorTargets ( const rw::kinematics::State state)

get the target off all motors

Parameters
state[in]
Returns

◆ RigidDevice()

RigidDevice ( dynamics::Body::Ptr  base,
const std::vector< std::pair< BodyInfo, rw::models::Object::Ptr >> &  objects,
rw::models::JointDevice::Ptr  dev 
)

Construct new kinematic device.

Parameters
base[in] base of the device.
objects[in] vector of links. Each links is given as the dynamic body parameters and the object geometry.
dev[in] the kinematic model.

◆ setJointVelocities()

void setJointVelocities ( const rw::math::Q q,
rw::kinematics::State state 
)
virtual

set the joint velocities

Parameters
q[in] joint velocities
state[in] the state in which to set the velocities
Returns

Implements DynamicDevice.

◆ setJointVelocity()

void setJointVelocity ( double  vel,
int  i,
rw::kinematics::State state 
)

Set the velocity of a motorized joint.

Parameters
vel[in] the velocity.
i[in] the joint to set velocity for.
state[in] the state in which to set the velocity.

◆ setMotorForceLimits()

void setMotorForceLimits ( const rw::math::Q force)

set the force limits of all motors of this device

Parameters
force[in] vector or force limits

◆ setMotorForceTarget()

void setMotorForceTarget ( double  force,
int  i,
rw::kinematics::State state 
)

Set force target for a single motor.

Parameters
force[in] the force target.
i[in] the index of the motor.
state[out] the state to update with target.

◆ setMotorForceTargets()

void setMotorForceTargets ( const rw::math::Q force,
rw::kinematics::State state 
)

Set force targets for all motors.

Parameters
force[in] the force targets.
state[out] the state to update with target.

◆ setMotorTarget()

void setMotorTarget ( double  q,
int  i,
rw::kinematics::State state 
)

set the target of motor i. the target may be a desired force or a desired velocity depending on the current mode of the motor.

Parameters
q[in] the target value in either force[N]/torque[Nm] or velocity [m/s]/[rad/s]
i[in] the index of the motor
state[in/out]

◆ setMotorTargets()

void setMotorTargets ( const rw::math::Q q,
rw::kinematics::State state 
)

set target of all motors

Parameters
q[in] target of motors in either force[N]/torque[Nm] or velocity [m/s]/[rad/s]
state[in/out]

◆ setMotorVelocityTarget()

void setMotorVelocityTarget ( double  vel,
int  i,
rw::kinematics::State state 
)

Set velocity target for a single motor.

Parameters
vel[in] the velocity target.
i[in] the index of the motor.
state[out] the state to update with target.

◆ setMotorVelocityTargets()

void setMotorVelocityTargets ( const rw::math::Q vel,
rw::kinematics::State state 
)
virtual

Set velocity targets for all motors.

Parameters
vel[in] the velocity targets.
state[out] the state to update with target.

Reimplemented from DynamicDevice.