A collection of Matlab/Octave functions that wraps the functionalities of (mainly) the iDyntree class KinDynComputations
. For further information on the single wrapper, refer to the description included in each function.
For a Matlab/Octave user, it may be sometimes counterintuitive to use C++ based formalism inside Matlab/Octave. Furthermore, there are common iDyntree functions that require several lines of code in order to be used correctly. E.g. see the getRobotState
function:
basePose_iDyntree = iDynTree.Transform();
jointPos_iDyntree = iDynTree.VectorDynSize(KinDynModel.NDOF);
baseVel_iDyntree = iDynTree.Twist();
jointVel_iDyntree = iDynTree.VectorDynSize(KinDynModel.NDOF);
gravityVec_iDyntree = iDynTree.Vector3();
KinDynModel.kinDynComp.getRobotState(basePose_iDyntree,jointPos_iDyntree,baseVel_iDyntree,jointVel_iDyntree,gravityVec_iDyntree);
baseRotation_iDyntree = basePose_iDyntree.getRotation;
baseOrigin_iDyntree = basePose_iDyntree.getPosition;
baseRotation = baseRotation_iDyntree.toMatlab;
baseOrigin = baseOrigin_iDyntree.toMatlab;
jointPos = jointPos_iDyntree.toMatlab;
baseVel = baseVel_iDyntree.toMatlab;
jointVel = jointVel_iDyntree.toMatlab;
basePose = [baseRotation, baseOrigin;
0, 0, 0, 1];
The purpose of the wrapper is therefore to provide a simpler and easy-to-use interface for Matlab/Octave users who wants to use iDyntree inside Matlab/Octave, also helping in designing code which is less error-prone and easier to debug (e.g. in case the interface of an iDyntree function will change in the future).
- getJointPos
- getJointVel
- getCentroidalTotalMomentum
- getRobotState
- getWorldBaseTransform
- getBaseTwist
- getModelVel
- getFrameVelocityRepresentation
- getNrOfDegreesOfFreedom
- getFloatingBase
- getFrameIndex
- getFrameName
- getWorldTransform
- getWorldTransformsAsHomogeneous
- getRelativeTransform
- getRelativeJacobian
- getFreeFloatingMassMatrix
- getFrameBiasAcc
- getFrameFreeFloatingJacobian
- getCenterOfMassPosition
- generalizedBiasForces
- generalizedGravityForces
- getCenterOfMassJacobian
- getCenterOfMassVelocity
Not proper wrappers, they wrap more than one method of the class each. Requirements: compile iDyntree with Irrlicht (IDYNTREE_USES_IRRLICHT = ON)
.
Warning: the visualizer class may be deprecated in a future release.
Not actual wrappers, they use the iDynTreeWrappers in combination with the MATLAB patch plotting functions to visualize the robot.
Disclaimers:
- This visualization has not been tested with Octave.
- At the moment, there is no support for
.dae
mesh file format.