Classes to implement a non abstract class for a robot with dynamic properties from an object factory. More...
#include <jrl/dynamics/dynamicrobot.hh>
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. | |
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. | |
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. | |
virtual | ~dynamicRobot () |
Destructor. | |
Kinematic chain | |
virtual void | rootJoint (CjrlJoint &inJoint) |
Set the root joint of the robot. | |
virtual CjrlJoint * | rootJoint () const |
Get the root joint of the robot. | |
virtual std::vector< CjrlJoint * > | jointVector () |
Get a vector containing all the joints. | |
virtual std::vector< CjrlJoint * > | jointsBetween (const CjrlJoint &inStartJoint, const CjrlJoint &inEndJoint) const |
Get the chain of joints between two joints. | |
virtual double | upperBoundDof (unsigned int inRankInConfiguration) |
Get the upper bound for ith dof. | |
virtual double | lowerBoundDof (unsigned int inRankInConfiguration) |
Get the lower bound for ith dof. | |
virtual double | upperBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig) |
Compute the upper bound for ith dof using other configuration values if possible. | |
virtual double | lowerBoundDof (unsigned int inRankInConfiguration, const vectorN &inConfig) |
Compute the lower bound for ith dof using other configuration values if possible. | |
virtual unsigned int | numberDof () const |
Get the number of degrees of freedom of the robot. | |
virtual void | setJointOrderInConfig (std::vector< CjrlJoint * > inJointVector) |
Set the joint ordering in the configuration vector. | |
Configuration, velocity and acceleration | |
virtual bool | currentConfiguration (const vectorN &inConfig) |
Set the current configuration of the robot. | |
virtual const vectorN & | currentConfiguration () const |
Get the current configuration of the robot. | |
virtual bool | currentVelocity (const vectorN &inVelocity) |
Set the current velocity of the robot. | |
virtual const vectorN & | currentVelocity () const |
Get the current velocity of the robot. | |
virtual bool | currentAcceleration (const vectorN &inAcceleration) |
Set the current acceleration of the robot. | |
virtual const vectorN & | currentAcceleration () const |
Get the current acceleration of the robot. | |
virtual const matrixNxP & | currentForces () const |
Get the current forces of the robot. | |
virtual const matrixNxP & | currentTorques () const |
Get the current torques of the robot. | |
virtual const vectorN & | currentJointTorques () const |
Get the current joint torques of the robot. | |
Forward kinematics and dynamics | |
virtual bool | computeForwardKinematics () |
Compute forward kinematics. | |
virtual bool | computeCenterOfMassDynamics () |
Compute the dynamics of the center of mass. | |
virtual const vector3d & | positionCenterOfMass () const |
Get the position of the center of mass. | |
virtual const vector3d & | velocityCenterOfMass () |
Get the velocity of the center of mass. | |
virtual const vector3d & | accelerationCenterOfMass () |
Get the acceleration of the center of mass. | |
virtual const vector3d & | linearMomentumRobot () |
Get the linear momentum of the robot. | |
virtual const vector3d & | derivativeLinearMomentum () |
Get the time-derivative of the linear momentum. | |
virtual const vector3d & | angularMomentumRobot () |
Get the angular momentum of the robot at the center of mass. | |
virtual const vector3d & | derivativeAngularMomentum () |
Get the time-derivative of the angular momentum at the center of mass. | |
virtual double | mass () const |
Get the total mass of the robot. | |
Control of the implementation | |
virtual bool | isSupported (const std::string &inProperty) |
Whether the specified property in implemented. | |
virtual bool | getProperty (const std::string &inProperty, std::string &outValue) |
Get property corresponding to command name. | |
virtual bool | setProperty (std::string &inProperty, const std::string &inValue) |
Set property corresponding to command name. | |
Inertia matrix related methods | |
virtual void | computeInertiaMatrix () |
Compute the inertia matrix of the robot according wrt ![]() | |
virtual const matrixNxP & | inertiaMatrix () const |
Get the inertia matrix of the robot according wrt ![]() | |
Actuated joints related methods. | |
virtual const std::vector < CjrlJoint * > & | getActuatedJoints () const |
Returns the list of actuated joints. | |
virtual void | setActuatedJoints (std::vector< CjrlJoint * > &lActuatedJoints) |
Specifies the list of actuated joints. | |
Protected Member Functions | |
void | setDynamicRobot (CjrlDynamicRobot *inDynamicRobot) |
Classes to implement a non abstract class for a robot with dynamic properties from an object factory.
jrlDelegate::dynamicRobot::dynamicRobot | ( | CjrlRobotDynamicsObjectFactory * | inObjectFactory | ) | [inline] |
jrlDelegate::dynamicRobot::dynamicRobot | ( | dynamicRobot * | inDRNA | ) | [inline] |
jrlDelegate::dynamicRobot::dynamicRobot | ( | ) | [inline] |
virtual jrlDelegate::dynamicRobot::~dynamicRobot | ( | ) | [inline, virtual] |
Destructor.
virtual const vector3d& jrlDelegate::dynamicRobot::accelerationCenterOfMass | ( | ) | [inline, virtual] |
Get the acceleration of the center of mass.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::accelerationCenterOfMass().
virtual const vector3d& jrlDelegate::dynamicRobot::angularMomentumRobot | ( | ) | [inline, virtual] |
Get the angular momentum of the robot at the center of mass.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::angularMomentumRobot().
virtual bool jrlDelegate::dynamicRobot::computeCenterOfMassDynamics | ( | ) | [inline, virtual] |
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().
virtual bool jrlDelegate::dynamicRobot::computeForwardKinematics | ( | ) | [inline, virtual] |
Compute forward kinematics.
Update the position, velocity and accelerations of each joint wrt ,
,
.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::computeForwardKinematics().
virtual void jrlDelegate::dynamicRobot::computeInertiaMatrix | ( | ) | [inline, virtual] |
Compute the inertia matrix of the robot according wrt .
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::computeInertiaMatrix().
virtual const vectorN& jrlDelegate::dynamicRobot::currentAcceleration | ( | ) | const [inline, virtual] |
Get the current acceleration of the robot.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::currentAcceleration().
virtual bool jrlDelegate::dynamicRobot::currentAcceleration | ( | const vectorN & | inAcceleration | ) | [inline, virtual] |
Set the current acceleration of the robot.
inAcceleration | the acceleration vector ![]() |
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::currentAcceleration().
virtual const vectorN& jrlDelegate::dynamicRobot::currentConfiguration | ( | ) | const [inline, virtual] |
Get the current configuration of the robot.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::currentConfiguration().
virtual bool jrlDelegate::dynamicRobot::currentConfiguration | ( | const vectorN & | inConfig | ) | [inline, virtual] |
Set the current configuration of the robot.
inConfig | the configuration vector ![]() |
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::currentConfiguration().
virtual const matrixNxP& jrlDelegate::dynamicRobot::currentForces | ( | ) | const [inline, virtual] |
Get the current forces of the robot.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::currentForces().
virtual const vectorN& jrlDelegate::dynamicRobot::currentJointTorques | ( | ) | const [inline, virtual] |
Get the current joint torques of the robot.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::currentJointTorques().
virtual const matrixNxP& jrlDelegate::dynamicRobot::currentTorques | ( | ) | const [inline, virtual] |
Get the current torques of the robot.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::currentTorques().
virtual const vectorN& jrlDelegate::dynamicRobot::currentVelocity | ( | ) | const [inline, virtual] |
Get the current velocity of the robot.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::currentVelocity().
virtual bool jrlDelegate::dynamicRobot::currentVelocity | ( | const vectorN & | inVelocity | ) | [inline, virtual] |
Set the current velocity of the robot.
inVelocity | the velocity vector ![]() |
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::currentVelocity().
virtual const vector3d& jrlDelegate::dynamicRobot::derivativeAngularMomentum | ( | ) | [inline, virtual] |
Get the time-derivative of the angular momentum at the center of mass.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::derivativeAngularMomentum().
virtual const vector3d& jrlDelegate::dynamicRobot::derivativeLinearMomentum | ( | ) | [inline, virtual] |
Get the time-derivative of the linear momentum.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::derivativeLinearMomentum().
virtual const std::vector<CjrlJoint*>& jrlDelegate::dynamicRobot::getActuatedJoints | ( | ) | const [inline, virtual] |
Returns the list of actuated joints.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::getActuatedJoints().
virtual bool jrlDelegate::dynamicRobot::getJacobian | ( | const CjrlJoint & | inStartJoint, | |
const CjrlJoint & | inEndJoint, | |||
const vector3d & | inFrameLocalPosition, | |||
matrixNxP & | outjacobian, | |||
unsigned int | offset = 0 , |
|||
bool | inIncludeStartFreeFlyer = true | |||
) | [inline, virtual] |
Compute and get position and orientation jacobian.
inStartJoint | First joint in the chain of joints influencing the jacobian. | |
inEndJoint | Joint where the control frame is located. | |
inFrameLocalPosition | Position of the control frame in inEndJoint local frame. |
outjacobian | computed jacobian matrix. |
offset | is the rank of first non zero outjacobian column. | |
inIncludeStartFreeFlyer | Option to include the contribution of a fictive freeflyer superposed with inStartJoint |
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::getJacobian().
virtual bool jrlDelegate::dynamicRobot::getJacobianCenterOfMass | ( | const CjrlJoint & | inStartJoint, | |
matrixNxP & | outjacobian, | |||
unsigned int | offset = 0 , |
|||
bool | inIncludeStartFreeFlyer = true | |||
) | [inline, virtual] |
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::getJacobianCenterOfMass().
virtual bool jrlDelegate::dynamicRobot::getOrientationJacobian | ( | const CjrlJoint & | inStartJoint, | |
const CjrlJoint & | inEndJoint, | |||
matrixNxP & | outjacobian, | |||
unsigned int | offset = 0 , |
|||
bool | inIncludeStartFreeFlyer = true | |||
) | [inline, virtual] |
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::getOrientationJacobian().
virtual bool jrlDelegate::dynamicRobot::getPositionJacobian | ( | const CjrlJoint & | inStartJoint, | |
const CjrlJoint & | inEndJoint, | |||
const vector3d & | inFrameLocalPosition, | |||
matrixNxP & | outjacobian, | |||
unsigned int | offset = 0 , |
|||
bool | inIncludeStartFreeFlyer = true | |||
) | [inline, virtual] |
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::getPositionJacobian().
virtual bool jrlDelegate::dynamicRobot::getProperty | ( | const std::string & | inProperty, | |
std::string & | outValue | |||
) | [inline, virtual] |
Get property corresponding to command name.
inProperty | name of the property. |
outValue | value of the property if implemented. |
References CjrlDynamicRobot::getProperty().
virtual bool jrlDelegate::dynamicRobot::getSpecializedInverseKinematics | ( | const CjrlJoint & | jointRoot, | |
const CjrlJoint & | jointEnd, | |||
const matrix4d & | jointRootPosition, | |||
const matrix4d & | jointEndPosition, | |||
vectorN & | q | |||
) | [inline, virtual] |
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.
[in] | jointRoot,: | The root of the joint chain for which the specialized inverse kinematics should be computed. |
[in] | jointEnd,: | The end of the joint chain for which the specialized inverse kinematics should be computed. |
[in] | jointRootPosition,: | The desired position of the root. |
[in] | jointEndPosition,: | The end position of the root. |
[out] | q,: | Result i.e. the articular values. |
Reimplemented from CjrlDynamicRobot.
References CjrlDynamicRobot::getSpecializedInverseKinematics().
virtual const matrixNxP& jrlDelegate::dynamicRobot::inertiaMatrix | ( | ) | const [inline, virtual] |
Get the inertia matrix of the robot according wrt .
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::inertiaMatrix().
virtual bool jrlDelegate::dynamicRobot::initialize | ( | ) | [inline, virtual] |
Initialize data-structure necessary to dynamic computations This function should be called after building the tree of joints.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::initialize().
virtual bool jrlDelegate::dynamicRobot::isSupported | ( | const std::string & | inProperty | ) | [inline, virtual] |
Whether the specified property in implemented.
Reimplemented from CjrlDynamicRobot.
References CjrlDynamicRobot::isSupported().
virtual std::vector<CjrlJoint*> jrlDelegate::dynamicRobot::jointsBetween | ( | const CjrlJoint & | inStartJoint, | |
const CjrlJoint & | inEndJoint | |||
) | const [inline, virtual] |
Get the chain of joints between two joints.
inStartJoint | First joint. | |
inEndJoint | Second joint. |
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::jointsBetween().
virtual std::vector< CjrlJoint* > jrlDelegate::dynamicRobot::jointVector | ( | ) | [inline, virtual] |
Get a vector containing all the joints.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::jointVector().
virtual const vector3d& jrlDelegate::dynamicRobot::linearMomentumRobot | ( | ) | [inline, virtual] |
Get the linear momentum of the robot.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::linearMomentumRobot().
virtual double jrlDelegate::dynamicRobot::lowerBoundDof | ( | unsigned int | inRankInConfiguration, | |
const vectorN & | inConfig | |||
) | [inline, virtual] |
Compute the lower bound for ith dof using other configuration values if possible.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::lowerBoundDof().
virtual double jrlDelegate::dynamicRobot::lowerBoundDof | ( | unsigned int | inRankInConfiguration | ) | [inline, virtual] |
Get the lower bound for ith dof.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::lowerBoundDof().
virtual double jrlDelegate::dynamicRobot::mass | ( | ) | const [inline, virtual] |
virtual unsigned int jrlDelegate::dynamicRobot::numberDof | ( | ) | const [inline, virtual] |
Get the number of degrees of freedom of the robot.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::numberDof().
virtual const vector3d& jrlDelegate::dynamicRobot::positionCenterOfMass | ( | ) | const [inline, virtual] |
Get the position of the center of mass.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::positionCenterOfMass().
virtual CjrlJoint* jrlDelegate::dynamicRobot::rootJoint | ( | ) | const [inline, virtual] |
Get the root joint of the robot.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::rootJoint().
virtual void jrlDelegate::dynamicRobot::rootJoint | ( | CjrlJoint & | inJoint | ) | [inline, virtual] |
Set the root joint of the robot.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::rootJoint().
virtual void jrlDelegate::dynamicRobot::setActuatedJoints | ( | std::vector< CjrlJoint * > & | lActuatedJoints | ) | [inline, virtual] |
Specifies the list of actuated joints.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::setActuatedJoints().
void jrlDelegate::dynamicRobot::setDynamicRobot | ( | CjrlDynamicRobot * | inDynamicRobot | ) | [inline, protected] |
Referenced by jrlDelegate::humanoidDynamicRobot::humanoidDynamicRobot().
virtual void jrlDelegate::dynamicRobot::setJointOrderInConfig | ( | std::vector< CjrlJoint * > | inJointVector | ) | [inline, virtual] |
Set the joint ordering in the configuration vector.
inJointVector | Vector 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().
virtual bool jrlDelegate::dynamicRobot::setProperty | ( | std::string & | inProperty, | |
const std::string & | inValue | |||
) | [inline, virtual] |
Set property corresponding to command name.
inProperty | name of the property. | |
inValue | value of the property. |
Reimplemented from CjrlDynamicRobot.
References CjrlDynamicRobot::setProperty().
virtual double jrlDelegate::dynamicRobot::upperBoundDof | ( | unsigned int | inRankInConfiguration, | |
const vectorN & | inConfig | |||
) | [inline, virtual] |
Compute the upper bound for ith dof using other configuration values if possible.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::upperBoundDof().
virtual double jrlDelegate::dynamicRobot::upperBoundDof | ( | unsigned int | inRankInConfiguration | ) | [inline, virtual] |
Get the upper bound for ith dof.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::upperBoundDof().
virtual const vector3d& jrlDelegate::dynamicRobot::velocityCenterOfMass | ( | ) | [inline, virtual] |
Get the velocity of the center of mass.
Implements CjrlDynamicRobot.
References CjrlDynamicRobot::velocityCenterOfMass().