This documentation was created for API version 2.2.0.
Here is a list of changes introduced by the different versions and what adjustements have to be made to migrate.
3.1.3 -> 3.2.0 (05. May 2022)
- Merging RBDL-ORB and RBDL \o/
- Performance improvements of single DOF revolute joints around coordinate
axes.
- Removed Model::X_J. All joints now have to compute X_lambda
directly,
especially CustomJoints
3.1.2 -> 3.1.3 (30. September 2021)
- casadi math backend added
tanh support
3.0.0 -> 3.1.0 (13. August 2021)
- introducing the casadi math backend, rbdl-casadi is build as a seperated library that can be installed parallel to rbdl
- added install of cmake config files, so projects building on rbdl do not need to write their own FindRBDL.cmake files anymore
2.6.0 -> 3.0.0 (24. September 2019)
- Replaced aborting behaviour with actual error handling by providing an error
base class and some more specific error types derived from it
(contributed by Felix Richter)
- Removed SimpleMath library to reduce code complexety
(contributed by Felix Richter)
- Refactored the constraint system to be polymorphic
(contributed by Matthew J. Millard)
- Python Wrapper has been updated to support python3 and python2 and the
api has been extended to include the muscle addons functionality
2.5.0 -> 2.6.0
- Added support for closed-loop models by replacing Contacts API by a new
Constraints API. Loop constraints can be stabilized using Baumgarte
stabilization. Special thanks to Davide Corradi for this contribution!
- New constraint type CustomConstraint: a versatile interface to define
more general types of constraints (e.g. time dependent), contributed by
Matthew J. Millard.
- New joint type JointTypeHelical that can be used for screwing motions
(translations and simultaneous rotations), contributed by Stuart Anderson.
- Added support to specify external forces on bodies on constrained forward
- Changed Quaternion multiplication behaviour for a more standard
convention: multiplying q1 (1,0,0,0) with q2 (0,1,0,0) results now in
(0,0,1,0) instead of the previous (0,0,-1,0).
- Removed Model::SetFloatingBaseBody(). Use JointTypeFloatingBase instead.
- LuaModel: extended specification to support ConstraintSets.
2.4.1 -> 2.5.0
- Added an experimental Cython based Python wrapper of RBDL. The API is
very close to the C++ API. For a brief glimpse of the API see the file
python/test_wrapper.py.
- Matthew Millard added CustomJoints which allow to create different joint
types completely by user code. They are implemented as proxy joints for
which their behaviour is specified using virtual functions.
the joint space inertia matrix with a vector in O(n) time.
- Added JointTypeFloatingBase which uses TX,TY,TZ and a spherical joint for
the floating base joint.
- Loading of floating base URDF models must now be specified as a third
- Added the URDF code from Bullet3 which gets used when ROS is not found.
Otherwise use the URDF libraries found via Catkin.
that compute both linear and angular quantities
- Removed Model::SetFloatingBase (body). Use a 6-DoF joint or
JointTypeFloatingBase instead.
- Fixed building issues when building DLL with MSVC++.
2.4.0 -> 2.4.1 (20 April 2016)
This is a bugfix release that maintains binary compatibility and only fixes
erroneous behaviour.
criterion would be evaluated too early and thus report convergence too
early. This was reported independently by Kevin Stein, Yun Fei, and Davide
Corradi. Thanks for the reports!
(thanks to Sébastien Barthélémy for reporting!)
2.3.3 -> 2.4.0 (23 February 2015)
- Added sparse range-space method ForwardDynamicsContactsRangeSpaceSparse()
and ComputeContactImpulsesRangeSpaceSparse()
- Added null-space method ForwardDynamicsContactsNullSpace()
and ComputeContactImpulsesNullSpace()
- Renamed ForwardDynamicsContactsLagrangian() to
ForwardDynamicsContactsDirect() and
ComputeContactImpulsesLagrangian() to ComputeContactImpulsesDirect()
- Removed/Fixed CalcAngularMomentum(). The function produced wrong values. The
Caller has to ensure that the matrix was set to zero before using this
function.
optionally reduce memory allocations
- Added JointTypeTranslationXYZ, JointTypeEulerXYZ, and JointTypeEulerYXZ
which are equivalent to the emulated multidof joints but faster.
- Added CalcContactJacobian()
- Added solving of linear systems using standard Householder QR
- URDFReader: Fixed various issues and using faster joints for floating
base models
- Various performance improvements
2.3.2 -> 2.3.3 (21 October 2014)
- critical: fixed ForwardDynamicsContacts with constraints on a body
hat is attached with a fixed joint. Previous versions simply crashed.
Thanks to Yue Hu for reporting!
at build time
- build system: fixed roblems especially building of the URDFreader
- build system: all CMake variables for RBDL are now prefixed with RBDL_
- FindRBDL.cmake now can use components to search for the LuaModel or
URDFReader addon
2.3.1 -> 2.3.2 (29 August 2014)
- critical: fixed ForwardDynamicsContacts when using 3-dof joints
- critical: fixed CompositeRigidBodyDynamics when using 3-dof joints (thanks to Henning Koch!)
2.3.0 -> 2.3.1 (13 July 2014)
- critical: fixed angular momentum computation. Version 2.3.0 produced wrong
results. Thanks to Hilario Tome and Benjamin Michaud for reporting!
- critical: fixed JointTypeEulerZYX. Previous versions produce wrong
results!
- fixed library version number for the LuaModel addon. It now uses version
2.3 instead of the wrong 2.2.
2.2.2 -> 2.3.0 (14 March 2014)
- disabled clearing of joint space inertia matrix in CRBA.
It is expected that the matrix is cleared by the user when neccessary.
- Added experimental joint type JointTypeEulerZYX. It does not emulate
multiple degrees of freedom using virtual bodies instead it uses a 3 DoF
motion subspace. Performance is better for the
- Using Eigen3's default column-major ordering for matrices when using
Eigen3. This should have no effect for the user unless matrix elements
are accessed using the .data()[i] operator of Eigen3's matrix class. However
if .data()[i] is used the access indices have to be adjusted.
- added functions to compute kinetic and potential energy and the
computation of the center of mass and its linear velocity:
RigidBodyDynamics::Utils::CalcAngularMomentum
2.2.1 -> 2.2.2 (06 November 2013)
- adjusted default constructor for Body. It now has the identity matrix as
inertia, instead of a zero matrix.
- LuaModel: made sure that the Body value is optional and uses the default
Body constructor if not defined.
2.2.0 -> 2.2.1 04 (November 2013)
- properly exporting LuaTables++ functions when using LuaModel addon
Fixes linking
- fixed exported library version (now at 2.2 as expected)
2.1.0 -> 2.2.0 (28 October 2013)
- added spherical joints that do not suffer from singularities:
Use joint type JointTypeSpherical
- added Model::q_size, and Model::qdot_size that report the sizes including
all 4 Quaternion parameters when spherical joints are used.
User is advised to use Model::q_size and Model::qdot_size instead of
Model::dof_count.
- removed "constraint_" prefix from constraint impulses, forces and
accelerations from the ConstraintSets:
renaming required if values are queried
- Contact impulses: specification of a contact velocity after a collision:
added ConstraintSet::v_plus which can be set for the desired constraint
velocity after a collision. Previously it used the values stored in
ConstraintSet::constraint_acceleration.
User has to store desired exit velocities manually in CS::v_plus
2.0.1 -> 2.1.0 (29 September 2013)
- made codebase compatible to Debian
Binary symbol export was changed. No change in user code required,
however everything needs to be recompiled and linked.
- Removed Lua 5.2 source
When building the addon LuaModel, one hast to have it installed on the
system already.
- Removed UnitTest++ sources
When building tests one has to have it installed on the system already.
2.0.0 -> 2.0.1 (05 September 2013)
- fixed compiler errors on some older compilers
No change required when using RBDL version 2.0.0.
- fixed CMake configurations for examples
No change required when using RBDL version 2.0.0.
1.X.Y -> 2.0.0 (18 July 2013)
- removed Model::Init():
All initialization is now done in the default constructor in Model(). To
be compatible with the new API simply remove any calls to Model::Init().
- removed Eigen3 sources:
Eigen3 is no more included in RBDL instead it uses the Eigen3 library
that is installed on the system. If you want to use RBDL with Eigen3
you have to install it on your system yourself.
- inverted sign of contact forces/impulses:
ConstraintSet::constraint_force and ConstraintSet::constraint_impulse are
now the forces or impulses that are acting on the constrained body by the
constraint.
1.0.0 -> 1.1.0 (20 February 2013)
- removed constructor Body (mass, com, length, gyration_radii)
This constructor did some erroneous calculations to compute the real
radii of gyration. It was removed as the two remaining constructors are
properly tested and are more general.
May Merging RBDL ORB and RBDL o Performance improvements of single DOF revolute joints around coordinate axes Removed Model::X_J All joints now have to compute X_lambda directly
RBDL_DLLAPI void ForwardDynamicsContactsKokkevis(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, ConstraintSet &CS, Math::VectorNd &QDDotOutput)
Computes forward dynamics that accounts for active contacts in ConstraintSet.
RBDL_DLLAPI void CalcMInvTimesTau(Model &model, const Math::VectorNd &Q, const Math::VectorNd &Tau, Math::VectorNd &QDDot, bool update_kinematics=true)
Computes the effect of multiplying the inverse of the joint space inertia matrix with a vector in lin...
RBDL_DLLAPI void NonlinearEffects(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, Math::VectorNd &Tau, std::vector< Math::SpatialVector > *f_ext=NULL)
Computes the coriolis forces.
RBDL_DLLAPI void ForwardDynamicsLagrangian(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, const Math::VectorNd &Tau, Math::VectorNd &QDDot, Math::LinearSolver linear_solver=Math::LinearSolverColPivHouseholderQR, std::vector< Math::SpatialVector > *f_ext=NULL, Math::MatrixNd *H=NULL, Math::VectorNd *C=NULL)
Computes forward dynamics by building and solving the full Lagrangian equation.
RBDL_DLLAPI void CompositeRigidBodyAlgorithm(Model &model, const Math::VectorNd &Q, Math::MatrixNd &H, bool update_kinematics=true)
Computes the joint space inertia matrix by using the Composite Rigid Body Algorithm.
RBDL_DLLAPI Matrix3d CalcBodyWorldOrientation(Model &model, const VectorNd &Q, const unsigned int body_id, bool update_kinematics)
Returns the orientation of a given body as 3x3 matrix.
RBDL_DLLAPI void CalcBodySpatialJacobian(Model &model, const VectorNd &Q, unsigned int body_id, MatrixNd &G, bool update_kinematics)
Computes the spatial jacobian for a body.
RBDL_DLLAPI void CalcPointJacobian6D(Model &model, const VectorNd &Q, unsigned int body_id, const Vector3d &point_position, MatrixNd &G, bool update_kinematics)
Computes a 6-D Jacobian for a point on a body.
RBDL_DLLAPI SpatialVector CalcPointAcceleration6D(Model &model, const VectorNd &Q, const VectorNd &QDot, const VectorNd &QDDot, unsigned int body_id, const Vector3d &point_position, bool update_kinematics)
Computes linear and angular acceleration of a point on a body.
RBDL_DLLAPI void CalcPointJacobian(Model &model, const VectorNd &Q, unsigned int body_id, const Vector3d &point_position, MatrixNd &G, bool update_kinematics)
Computes the point jacobian for a point on a body.
RBDL_DLLAPI bool InverseKinematics(Model &model, const VectorNd &Qinit, const std::vector< unsigned int > &body_id, const std::vector< Vector3d > &body_point, const std::vector< Vector3d > &target_pos, VectorNd &Qres, double step_tol, double lambda, unsigned int max_iter)
Computes the inverse kinematics iteratively using a damped Levenberg-Marquardt method (also known as ...
RBDL_DLLAPI Math::SpatialVector CalcPointVelocity6D(Model &model, const Math::VectorNd &Q, const Math::VectorNd &QDot, unsigned int body_id, const Math::Vector3d &point_position, bool update_kinematics)
Computes angular and linear velocity of a point that is fixed on a body.
RBDL_ADDON_DLLAPI bool LuaModelReadFromLuaState(lua_State *L, Model *model, bool verbose=false)
Reads a model from a lua_State.
RBDL_ADDON_DLLAPI bool URDFReadFromString(const char *model_xml_string, Model *model, bool floating_base, bool verbose=false)
RBDL_ADDON_DLLAPI bool URDFReadFromFile(const char *filename, Model *model, bool floating_base, bool verbose=false)
RBDL_DLLAPI Scalar CalcKineticEnergy(Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, bool update_kinematics)
Computes the kinetic energy of the full model.
RBDL_DLLAPI void CalcCenterOfMass(Model &model, const Math::VectorNd &q, const Math::VectorNd &qdot, const Math::VectorNd *qddot, Scalar &mass, Math::Vector3d &com, Math::Vector3d *com_velocity, Math::Vector3d *com_acceleration, Math::Vector3d *angular_momentum, Math::Vector3d *change_of_angular_momentum, bool update_kinematics)
Computes the Center of Mass (COM) and optionally its linear velocity.
RBDL_DLLAPI Scalar CalcPotentialEnergy(Model &model, const Math::VectorNd &q, bool update_kinematics)
Computes the potential energy of the full model.
MX_Xd_scalar tanh(const MX_Xd_scalar &x)
RBDL_DLLAPI void rbdl_print_version()