Loading...
Searching...
No Matches
jrlDelegate::dynamicRobot Class Reference

Classes to implement a non abstract class for a robot with dynamic properties from an object factory. More...

#include <jrl/dynamics/dynamicrobot.hh>

Inheritance diagram for jrlDelegate::dynamicRobot:
Collaboration diagram for jrlDelegate::dynamicRobot:

Public Member Functions

virtual bool getJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)
 Compute and get position and orientation jacobian. More...
 
virtual bool getPositionJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)
 
virtual bool getOrientationJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)
 
virtual bool getJacobianCenterOfMass (const CjrlJoint &inStartJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)
 
virtual bool getSpecializedInverseKinematics (const CjrlJoint &jointRoot, const CjrlJoint &jointEnd, const matrix4d &jointRootPosition, const matrix4d &jointEndPosition, vectorN &q)
 Compute Speciliazed InverseKinematics between two joints. More...
 
Initialization
 dynamicRobot (CjrlRobotDynamicsObjectFactory *inObjectFactory)
 
 dynamicRobot (dynamicRobot *inDRNA)
 
 dynamicRobot ()
 
virtual bool initialize ()
 Initialize data-structure necessary to dynamic computations This function should be called after building the tree of joints. More...
 
virtual ~dynamicRobot ()
 Destructor. More...
 
Kinematic chain
virtual void rootJoint (CjrlJoint &inJoint)
 Set the root joint of the robot. More...
 
virtual CjrlJointrootJoint () const
 Get the root joint of the robot. More...
 
virtual std::vector< CjrlJoint * > jointVector ()
 Get a vector containing all the joints. More...
 
virtual std::vector< CjrlJoint * > jointsBetween (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint) const
 Get the chain of joints between two joints. More...
 
virtual double upperBoundDof (unsigned int inRankInConfiguration)
 Get the upper bound for ith dof. More...
 
virtual double lowerBoundDof (unsigned int inRankInConfiguration)
 Get the lower bound for ith dof. More...
 
virtual double upperBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)
 Compute the upper bound for ith dof using other configuration values if possible. More...
 
virtual double lowerBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)
 Compute the lower bound for ith dof using other configuration values if possible. More...
 
virtual double upperVelocityBoundDof (unsigned int inRankInConfiguration)
 Get the upper velocity bound for ith dof. More...
 
virtual double lowerVelocityBoundDof (unsigned int inRankInConfiguration)
 Get the lower velocity bound for ith dof. More...
 
virtual double upperTorqueBoundDof (unsigned int inRankInConfiguration)
 Get the upper torque bound for ith dof. More...
 
virtual double lowerTorqueBoundDof (unsigned int inRankInConfiguration)
 Get the lower torque bound for ith dof. More...
 
virtual unsigned int numberDof () const
 Get the number of degrees of freedom of the robot. More...
 
virtual void setJointOrderInConfig (std::vector< CjrlJoint * > inJointVector)
 Set the joint ordering in the configuration vector. More...
 
Configuration, velocity and acceleration
virtual bool currentConfiguration (const vectorN &inConfig)
 Set the current configuration of the robot. More...
 
virtual const vectorNcurrentConfiguration () const
 Get the current configuration of the robot. More...
 
virtual bool currentVelocity (const vectorN &inVelocity)
 Set the current velocity of the robot. More...
 
virtual const vectorNcurrentVelocity () const
 Get the current velocity of the robot. More...
 
virtual bool currentAcceleration (const vectorN &inAcceleration)
 Set the current acceleration of the robot. More...
 
virtual const vectorNcurrentAcceleration () const
 Get the current acceleration of the robot. More...
 
virtual const matrixNxPcurrentForces () const
 Get the current forces of the robot. More...
 
virtual const matrixNxPcurrentTorques () const
 Get the current torques of the robot. More...
 
virtual const vectorNcurrentJointTorques () const
 Get the current joint torques of the robot. More...
 
Forward kinematics and dynamics
virtual bool computeForwardKinematics ()
 Compute forward kinematics. More...
 
virtual bool computeCenterOfMassDynamics ()
 Compute the dynamics of the center of mass. More...
 
virtual const vector3dpositionCenterOfMass () const
 Get the position of the center of mass. More...
 
virtual const vector3dvelocityCenterOfMass ()
 Get the velocity of the center of mass. More...
 
virtual const vector3daccelerationCenterOfMass ()
 Get the acceleration of the center of mass. More...
 
virtual const vector3dlinearMomentumRobot ()
 Get the linear momentum of the robot. More...
 
virtual const vector3dderivativeLinearMomentum ()
 Get the time-derivative of the linear momentum. More...
 
virtual const vector3dangularMomentumRobot ()
 Get the angular momentum of the robot at the center of mass. More...
 
virtual const vector3dderivativeAngularMomentum ()
 Get the time-derivative of the angular momentum at the center of mass. More...
 
virtual double mass () const
 Get the total mass of the robot. More...
 
Control of the implementation
virtual bool isSupported (const std::string &inProperty)
 Whether the specified property in implemented. More...
 
virtual bool getProperty (const std::string &inProperty, std::string &outValue)
 Get property corresponding to command name. More...
 
virtual bool setProperty (std::string &inProperty, const std::string &inValue)
 Set property corresponding to command name. More...
 
Inertia matrix related methods
virtual void computeInertiaMatrix ()
 Compute the inertia matrix of the robot according wrt ${\bf q}$. More...
 
virtual const matrixNxPinertiaMatrix () const
 Get the inertia matrix of the robot according wrt ${\bf q}$. More...
 
Actuated joints related methods.
virtual const std::vector< CjrlJoint * > & getActuatedJoints () const
 Returns the list of actuated joints. More...
 
virtual void setActuatedJoints (std::vector< CjrlJoint * > &lActuatedJoints)
 Specifies the list of actuated joints. More...
 
- Public Member Functions inherited from CjrlDynamicRobot
virtual bool getJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
 
virtual bool getPositionJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, const vector3d &inFrameLocalPosition, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
 
virtual bool getOrientationJacobian (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
 
virtual bool getJacobianCenterOfMass (const CjrlJoint &inStartJoint, matrixNxP &outjacobian, unsigned int offset=0, bool inIncludeStartFreeFlyer=true)=0
 
virtual bool getSpecializedInverseKinematics (const CjrlJoint &, const CjrlJoint &, const matrix4d &, const matrix4d &, vectorN &)
 
virtual bool initialize ()=0
 
virtual ~CjrlDynamicRobot ()
 
virtual void rootJoint (CjrlJoint &inJoint)=0
 
virtual CjrlJointrootJoint () const=0
 
virtual std::vector< CjrlJoint * > jointVector ()=0
 
virtual std::vector< CjrlJoint * > jointsBetween (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint) const=0
 
virtual double upperBoundDof (unsigned int inRankInConfiguration)=0
 
virtual double lowerBoundDof (unsigned int inRankInConfiguration)=0
 
virtual double upperBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)=0
 
virtual double lowerBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)=0
 
virtual double upperVelocityBoundDof (unsigned int inRankInConfiguration)=0
 
virtual double lowerVelocityBoundDof (unsigned int inRankInConfiguration)=0
 
virtual double upperTorqueBoundDof (unsigned int inRankInConfiguration)=0
 
virtual double lowerTorqueBoundDof (unsigned int inRankInConfiguration)=0
 
virtual unsigned int numberDof () const=0
 
virtual void setJointOrderInConfig (std::vector< CjrlJoint * > inJointVector)=0
 
virtual bool currentConfiguration (const vectorN &inConfig)=0
 
virtual const vectorNcurrentConfiguration () const=0
 
virtual bool currentVelocity (const vectorN &inVelocity)=0
 
virtual const vectorNcurrentVelocity () const=0
 
virtual bool currentAcceleration (const vectorN &inAcceleration)=0
 
virtual const vectorNcurrentAcceleration () const=0
 
virtual const matrixNxPcurrentForces () const=0
 
virtual const matrixNxPcurrentTorques () const=0
 
virtual const vectorNcurrentJointTorques () const=0
 
virtual bool computeForwardKinematics ()=0
 
virtual bool computeCenterOfMassDynamics ()=0
 
virtual const vector3dpositionCenterOfMass () const=0
 
virtual const vector3dvelocityCenterOfMass ()=0
 
virtual const vector3daccelerationCenterOfMass ()=0
 
virtual const vector3dlinearMomentumRobot ()=0
 
virtual const vector3dderivativeLinearMomentum ()=0
 
virtual const vector3dangularMomentumRobot ()=0
 
virtual const vector3dderivativeAngularMomentum ()=0
 
virtual double mass () const=0
 
virtual bool isSupported (const std::string &)
 
virtual bool getProperty (const std::string &, std::string &) const
 
virtual bool setProperty (std::string &, const std::string &)
 
virtual void computeInertiaMatrix ()=0
 
virtual const matrixNxPinertiaMatrix () const=0
 
virtual const std::vector< CjrlJoint * > & getActuatedJoints () const=0
 
virtual void setActuatedJoints (std::vector< CjrlJoint * > &lActuatedJoints)=0
 
virtual bool initialize ()=0
 
virtual ~CjrlDynamicRobot ()
 
virtual void rootJoint (CjrlJoint &inJoint)=0
 
virtual CjrlJointrootJoint () const=0
 
virtual std::vector< CjrlJoint * > jointVector ()=0
 
virtual std::vector< CjrlJoint * > jointsBetween (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint) const=0
 
virtual double upperBoundDof (unsigned int inRankInConfiguration)=0
 
virtual double lowerBoundDof (unsigned int inRankInConfiguration)=0
 
virtual double upperBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)=0
 
virtual double lowerBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig)=0
 
virtual double upperVelocityBoundDof (unsigned int inRankInConfiguration)=0
 
virtual double lowerVelocityBoundDof (unsigned int inRankInConfiguration)=0
 
virtual double upperTorqueBoundDof (unsigned int inRankInConfiguration)=0
 
virtual double lowerTorqueBoundDof (unsigned int inRankInConfiguration)=0
 
virtual unsigned int numberDof () const=0
 
virtual void setJointOrderInConfig (std::vector< CjrlJoint * > inJointVector)=0
 
virtual bool currentConfiguration (const vectorN &inConfig)=0
 
virtual const vectorNcurrentConfiguration () const=0
 
virtual bool currentVelocity (const vectorN &inVelocity)=0
 
virtual const vectorNcurrentVelocity () const=0
 
virtual bool currentAcceleration (const vectorN &inAcceleration)=0
 
virtual const vectorNcurrentAcceleration () const=0
 
virtual const matrixNxPcurrentForces () const=0
 
virtual const matrixNxPcurrentTorques () const=0
 
virtual const vectorNcurrentJointTorques () const=0
 
virtual bool computeForwardKinematics ()=0
 
virtual bool computeCenterOfMassDynamics ()=0
 
virtual const vector3dpositionCenterOfMass () const=0
 
virtual const vector3dvelocityCenterOfMass ()=0
 
virtual const vector3daccelerationCenterOfMass ()=0
 
virtual const vector3dlinearMomentumRobot ()=0
 
virtual const vector3dderivativeLinearMomentum ()=0
 
virtual const vector3dangularMomentumRobot ()=0
 
virtual const vector3dderivativeAngularMomentum ()=0
 
virtual double mass () const=0
 
virtual bool isSupported (const std::string &)
 
virtual bool getProperty (const std::string &, std::string &) const
 
virtual bool setProperty (std::string &, const std::string &)
 
virtual void computeInertiaMatrix ()=0
 
virtual const matrixNxPinertiaMatrix () const=0
 
virtual const std::vector< CjrlJoint * > & getActuatedJoints () const=0
 
virtual void setActuatedJoints (std::vector< CjrlJoint * > &lActuatedJoints)=0
 

Protected Member Functions

void setDynamicRobot (CjrlDynamicRobot *inDynamicRobot)
 

Detailed Description

Classes to implement a non abstract class for a robot with dynamic properties from an object factory.

Constructor & Destructor Documentation

◆ dynamicRobot() [1/3]

jrlDelegate::dynamicRobot::dynamicRobot ( CjrlRobotDynamicsObjectFactory inObjectFactory)
inline

◆ dynamicRobot() [2/3]

jrlDelegate::dynamicRobot::dynamicRobot ( dynamicRobot inDRNA)
inline

◆ dynamicRobot() [3/3]

jrlDelegate::dynamicRobot::dynamicRobot ( )
inline

◆ ~dynamicRobot()

virtual jrlDelegate::dynamicRobot::~dynamicRobot ( )
inlinevirtual

Destructor.

Member Function Documentation

◆ accelerationCenterOfMass()

virtual const vector3d & jrlDelegate::dynamicRobot::accelerationCenterOfMass ( )
inlinevirtual

Get the acceleration of the center of mass.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::accelerationCenterOfMass().

◆ angularMomentumRobot()

virtual const vector3d & jrlDelegate::dynamicRobot::angularMomentumRobot ( )
inlinevirtual

Get the angular momentum of the robot at the center of mass.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::angularMomentumRobot().

◆ computeCenterOfMassDynamics()

virtual bool jrlDelegate::dynamicRobot::computeCenterOfMassDynamics ( )
inlinevirtual

Compute the dynamics of the center of mass.

Compute the linear and angular momentum and their time derivatives, at the center of mass.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::computeCenterOfMassDynamics().

◆ computeForwardKinematics()

virtual bool jrlDelegate::dynamicRobot::computeForwardKinematics ( )
inlinevirtual

Compute forward kinematics.

Update the position, velocity and accelerations of each joint wrt ${\bf {q}}$, ${\bf \dot{q}}$, ${\bf \ddot{q}}$.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::computeForwardKinematics().

◆ computeInertiaMatrix()

virtual void jrlDelegate::dynamicRobot::computeInertiaMatrix ( )
inlinevirtual

Compute the inertia matrix of the robot according wrt ${\bf q}$.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::computeInertiaMatrix().

◆ currentAcceleration() [1/2]

virtual const vectorN & jrlDelegate::dynamicRobot::currentAcceleration ( ) const
inlinevirtual

Get the current acceleration of the robot.

Returns
the acceleration vector ${\bf \ddot{q}}$.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::currentAcceleration().

◆ currentAcceleration() [2/2]

virtual bool jrlDelegate::dynamicRobot::currentAcceleration ( const vectorN inAcceleration)
inlinevirtual

Set the current acceleration of the robot.

Parameters
inAccelerationthe acceleration vector ${\bf \ddot{q}}$.
Returns
true if success, false if failure (the dimension of the input vector does not fit the number of degrees of freedom of the robot).

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::currentAcceleration().

◆ currentConfiguration() [1/2]

virtual const vectorN & jrlDelegate::dynamicRobot::currentConfiguration ( ) const
inlinevirtual

Get the current configuration of the robot.

Returns
the configuration vector ${\bf q}$.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::currentConfiguration().

◆ currentConfiguration() [2/2]

virtual bool jrlDelegate::dynamicRobot::currentConfiguration ( const vectorN inConfig)
inlinevirtual

Set the current configuration of the robot.

Parameters
inConfigthe configuration vector ${\bf q}$.
Returns
true if success, false if failure (the dimension of the input vector does not fit the number of degrees of freedom of the robot).

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::currentConfiguration().

◆ currentForces()

virtual const matrixNxP & jrlDelegate::dynamicRobot::currentForces ( ) const
inlinevirtual

Get the current forces of the robot.

Returns
the force vector ${\bf f}$.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::currentForces().

◆ currentJointTorques()

virtual const vectorN & jrlDelegate::dynamicRobot::currentJointTorques ( ) const
inlinevirtual

Get the current joint torques of the robot.

Returns
the torque vector ${\bf \tau }$.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::currentJointTorques().

◆ currentTorques()

virtual const matrixNxP & jrlDelegate::dynamicRobot::currentTorques ( ) const
inlinevirtual

Get the current torques of the robot.

Returns
the torque vector ${\bf \tau }$.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::currentTorques().

◆ currentVelocity() [1/2]

virtual const vectorN & jrlDelegate::dynamicRobot::currentVelocity ( ) const
inlinevirtual

Get the current velocity of the robot.

Returns
the velocity vector ${\bf \dot{q}}$.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::currentVelocity().

◆ currentVelocity() [2/2]

virtual bool jrlDelegate::dynamicRobot::currentVelocity ( const vectorN inVelocity)
inlinevirtual

Set the current velocity of the robot.

Parameters
inVelocitythe velocity vector ${\bf \dot{q}}$.
Returns
true if success, false if failure (the dimension of the input vector does not fit the number of degrees of freedom of the robot).

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::currentVelocity().

◆ derivativeAngularMomentum()

virtual const vector3d & jrlDelegate::dynamicRobot::derivativeAngularMomentum ( )
inlinevirtual

Get the time-derivative of the angular momentum at the center of mass.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::derivativeAngularMomentum().

◆ derivativeLinearMomentum()

virtual const vector3d & jrlDelegate::dynamicRobot::derivativeLinearMomentum ( )
inlinevirtual

Get the time-derivative of the linear momentum.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::derivativeLinearMomentum().

◆ getActuatedJoints()

virtual const std::vector< CjrlJoint * > & jrlDelegate::dynamicRobot::getActuatedJoints ( ) const
inlinevirtual

Returns the list of actuated joints.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::getActuatedJoints().

◆ getJacobian()

virtual bool jrlDelegate::dynamicRobot::getJacobian ( const CjrlJoint inStartJoint,
const CjrlJoint inEndJoint,
const vector3d inFrameLocalPosition,
matrixNxP outjacobian,
unsigned int  offset = 0,
bool  inIncludeStartFreeFlyer = true 
)
inlinevirtual

Compute and get position and orientation jacobian.

Parameters
inStartJointFirst joint in the chain of joints influencing the jacobian.
inEndJointJoint where the control frame is located.
inFrameLocalPositionPosition of the control frame in inEndJoint local frame.
Return values
outjacobiancomputed jacobian matrix.
Parameters
offsetis the rank of first non zero outjacobian column.
inIncludeStartFreeFlyerOption to include the contribution of a fictive freeflyer superposed with inStartJoint
Returns
false if matrix has inadequate size. Number of columns in matrix outJacobian must be at least numberDof() if inIncludeStartFreeFlyer = true. It must be at least numberDof()-6 otherwise.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::getJacobian().

◆ getJacobianCenterOfMass()

virtual bool jrlDelegate::dynamicRobot::getJacobianCenterOfMass ( const CjrlJoint inStartJoint,
matrixNxP outjacobian,
unsigned int  offset = 0,
bool  inIncludeStartFreeFlyer = true 
)
inlinevirtual

◆ getOrientationJacobian()

virtual bool jrlDelegate::dynamicRobot::getOrientationJacobian ( const CjrlJoint inStartJoint,
const CjrlJoint inEndJoint,
matrixNxP outjacobian,
unsigned int  offset = 0,
bool  inIncludeStartFreeFlyer = true 
)
inlinevirtual

◆ getPositionJacobian()

virtual bool jrlDelegate::dynamicRobot::getPositionJacobian ( const CjrlJoint inStartJoint,
const CjrlJoint inEndJoint,
const vector3d inFrameLocalPosition,
matrixNxP outjacobian,
unsigned int  offset = 0,
bool  inIncludeStartFreeFlyer = true 
)
inlinevirtual

◆ getProperty()

virtual bool jrlDelegate::dynamicRobot::getProperty ( const std::string &  inProperty,
std::string &  outValue 
)
inlinevirtual

Get property corresponding to command name.

Parameters
inPropertyname of the property.
Return values
outValuevalue of the property if implemented.
Note
The returned string needs to be cast into the right type (double, int,...).

References CjrlDynamicRobot::getProperty().

◆ getSpecializedInverseKinematics()

virtual bool jrlDelegate::dynamicRobot::getSpecializedInverseKinematics ( const CjrlJoint jointRoot,
const CjrlJoint jointEnd,
const matrix4d jointRootPosition,
const matrix4d jointEndPosition,
vectorN q 
)
inlinevirtual

Compute Speciliazed InverseKinematics between two joints.

Specialized means that this method can be re implemented to be extremly efficient and used the particularity of your robot. For instance in some case, it is possible to use an exact inverse kinematics to compute a set of articular value.

This method does not intend to replace an architecture computing inverse kinematics through the Jacobian.

jointRootPosition and jointEndPosition have to be expressed in the same frame.

Parameters
[in]jointRootThe root of the joint chain for which the specialized inverse kinematics should be computed.
[in]jointEndThe end of the joint chain for which the specialized inverse kinematics should be computed.
[in]jointRootPositionThe desired position of the root.
[in]jointEndPositionThe end position of the root.
[out]qResult i.e. the articular values.

Reimplemented from CjrlDynamicRobot.

References CjrlDynamicRobot::getSpecializedInverseKinematics().

◆ inertiaMatrix()

virtual const matrixNxP & jrlDelegate::dynamicRobot::inertiaMatrix ( ) const
inlinevirtual

Get the inertia matrix of the robot according wrt ${\bf q}$.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::inertiaMatrix().

◆ initialize()

virtual bool jrlDelegate::dynamicRobot::initialize ( )
inlinevirtual

Initialize data-structure necessary to dynamic computations This function should be called after building the tree of joints.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::initialize().

◆ isSupported()

virtual bool jrlDelegate::dynamicRobot::isSupported ( const std::string &  inProperty)
inlinevirtual

Whether the specified property in implemented.

Reimplemented from CjrlDynamicRobot.

References CjrlDynamicRobot::isSupported().

◆ jointsBetween()

virtual std::vector< CjrlJoint * > jrlDelegate::dynamicRobot::jointsBetween ( const CjrlJoint inStartJoint,
const CjrlJoint inEndJoint 
) const
inlinevirtual

Get the chain of joints between two joints.

Parameters
inStartJointFirst joint.
inEndJointSecond joint.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::jointsBetween().

◆ jointVector()

virtual std::vector< CjrlJoint * > jrlDelegate::dynamicRobot::jointVector ( )
inlinevirtual

Get a vector containing all the joints.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::jointVector().

◆ linearMomentumRobot()

virtual const vector3d & jrlDelegate::dynamicRobot::linearMomentumRobot ( )
inlinevirtual

Get the linear momentum of the robot.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::linearMomentumRobot().

◆ lowerBoundDof() [1/2]

virtual double jrlDelegate::dynamicRobot::lowerBoundDof ( unsigned int  inRankInConfiguration)
inlinevirtual

Get the lower bound for ith dof.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::lowerBoundDof().

◆ lowerBoundDof() [2/2]

virtual double jrlDelegate::dynamicRobot::lowerBoundDof ( unsigned int  inRankInConfiguration,
const vectorN inConfig 
)
inlinevirtual

Compute the lower bound for ith dof using other configuration values if possible.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::lowerBoundDof().

◆ lowerTorqueBoundDof()

virtual double jrlDelegate::dynamicRobot::lowerTorqueBoundDof ( unsigned int  inRankInConfiguration)
inlinevirtual

Get the lower torque bound for ith dof.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::lowerTorqueBoundDof().

◆ lowerVelocityBoundDof()

virtual double jrlDelegate::dynamicRobot::lowerVelocityBoundDof ( unsigned int  inRankInConfiguration)
inlinevirtual

Get the lower velocity bound for ith dof.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::lowerVelocityBoundDof().

◆ mass()

virtual double jrlDelegate::dynamicRobot::mass ( ) const
inlinevirtual

Get the total mass of the robot.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::mass().

◆ numberDof()

virtual unsigned int jrlDelegate::dynamicRobot::numberDof ( ) const
inlinevirtual

Get the number of degrees of freedom of the robot.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::numberDof().

◆ positionCenterOfMass()

virtual const vector3d & jrlDelegate::dynamicRobot::positionCenterOfMass ( ) const
inlinevirtual

Get the position of the center of mass.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::positionCenterOfMass().

◆ rootJoint() [1/2]

virtual CjrlJoint * jrlDelegate::dynamicRobot::rootJoint ( ) const
inlinevirtual

Get the root joint of the robot.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::rootJoint().

◆ rootJoint() [2/2]

virtual void jrlDelegate::dynamicRobot::rootJoint ( CjrlJoint inJoint)
inlinevirtual

Set the root joint of the robot.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::rootJoint().

◆ setActuatedJoints()

virtual void jrlDelegate::dynamicRobot::setActuatedJoints ( std::vector< CjrlJoint * > &  lActuatedJoints)
inlinevirtual

Specifies the list of actuated joints.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::setActuatedJoints().

◆ setDynamicRobot()

void jrlDelegate::dynamicRobot::setDynamicRobot ( CjrlDynamicRobot inDynamicRobot)
inlineprotected

◆ setJointOrderInConfig()

virtual void jrlDelegate::dynamicRobot::setJointOrderInConfig ( std::vector< CjrlJoint * >  inJointVector)
inlinevirtual

Set the joint ordering in the configuration vector.

Parameters
inJointVectorVector of the robot joints

Specifies the order of the joints in the configuration vector. The vector should contain all the joints of the current robot.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::setJointOrderInConfig().

◆ setProperty()

virtual bool jrlDelegate::dynamicRobot::setProperty ( std::string &  inProperty,
const std::string &  inValue 
)
inlinevirtual

Set property corresponding to command name.

Parameters
inPropertyname of the property.
inValuevalue of the property.
Note
The value string is obtained by writing the corresponding value in a string (operator<<).

Reimplemented from CjrlDynamicRobot.

References CjrlDynamicRobot::setProperty().

◆ upperBoundDof() [1/2]

virtual double jrlDelegate::dynamicRobot::upperBoundDof ( unsigned int  inRankInConfiguration)
inlinevirtual

Get the upper bound for ith dof.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::upperBoundDof().

◆ upperBoundDof() [2/2]

virtual double jrlDelegate::dynamicRobot::upperBoundDof ( unsigned int  inRankInConfiguration,
const vectorN inConfig 
)
inlinevirtual

Compute the upper bound for ith dof using other configuration values if possible.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::upperBoundDof().

◆ upperTorqueBoundDof()

virtual double jrlDelegate::dynamicRobot::upperTorqueBoundDof ( unsigned int  inRankInConfiguration)
inlinevirtual

Get the upper torque bound for ith dof.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::upperTorqueBoundDof().

◆ upperVelocityBoundDof()

virtual double jrlDelegate::dynamicRobot::upperVelocityBoundDof ( unsigned int  inRankInConfiguration)
inlinevirtual

Get the upper velocity bound for ith dof.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::upperVelocityBoundDof().

◆ velocityCenterOfMass()

virtual const vector3d & jrlDelegate::dynamicRobot::velocityCenterOfMass ( )
inlinevirtual

Get the velocity of the center of mass.

Implements CjrlDynamicRobot.

References CjrlDynamicRobot::velocityCenterOfMass().