![]() |
- 3.0.2 rigid body dynamics module.
|
Namespaces | |
| internal | |
| TARGET_NS | |
| TestIrb4600 | |
| tpl | |
Classes | |
| class | ActuatorDynamics |
| class | ActuatorDynamicsSymplectic |
| class | CoordinateBase |
| class | Dynamics |
| This class implements the equations of motion of a Rigid Body System. More... | |
| class | EEContactModel |
| A soft contact model that only uses end-effector positions/velocities to compute the contact force. More... | |
| class | EndEffector |
| class | FixBaseAccSystem |
| A simple fix base robot system which is purely kinematic and actuated at ACCELERATION level. More... | |
| class | FixBaseFDSystem |
| A fix base rigid body system that uses forward dynamics. More... | |
| class | FixBaseFDSystemSymplectic |
| A fix base rigid body system that uses forward dynamics. More... | |
| class | FixBaseNLOC |
| NLOC for fixed base systems without an explicit contact model. More... | |
| class | FixBaseRobotState |
| whole fix base robot state, i.e. Joint state, Actuator Dynamics (and fix-base pose) More... | |
| class | FixBaseSystemBase |
| Base class for fix-base robot systems. More... | |
| class | FixBaseVelSystem |
| A simple fix base robot system which is purely kinematic and actuated at VELOCITY level. More... | |
| class | FloatingBaseFDSystem |
| A floating base rigid body system that uses forward dynamics. The input vector is assumed to consist of joint torques and end-effector forces expressed in the world. More... | |
| class | FloatingBaseNLOCContactModel |
| NLOC for floating base systems with an explicit contact model. More... | |
| class | FloatingBaseRobotState |
| whole robot state, i.e. RBDState and Actuator Dynamics More... | |
| class | FloatingBaseSLQ |
| SLQ for floating base systems without an explicit contact model. The contact constraint is enforced via a cost function. More... | |
| class | FloatingBaseTransforms |
| class | HyAInverseKinematics |
| class | IDControllerFB |
| class | IKConstraintsContainer |
| Inverse Kinematics constraint container. More... | |
| class | IKCostEvaluator |
| Inverse Kinematics cost evaluator for NLP. More... | |
| class | IKNLP |
| class | IKNLPSolverIpopt |
| class | InfiniteHorizonLQRwithInverseDynamics |
| class | InverseKinematicsBase |
| struct | InverseKinematicsSettings |
| class | Irb4600InverseKinematics |
| class | JacobiSingularity |
| A class computing codition numbers and singular velues of a Jacobian. More... | |
| class | JointAcceleration |
| joint acceleration More... | |
| class | JointLimitConstraints |
| Inverse Kinematics joint limit constraints. More... | |
| class | JointPositionPIDController |
| A joint position controller using a PID controller for all joints. More... | |
| class | JointState |
| joint state and joint velocity More... | |
| class | Kinematics |
| A general class for computing Kinematic properties. More... | |
| class | OperationalModel |
This is the class for the operational space model which gives access to the operational model parameter. The model is assumed to have the following form: where is the acceleration of the operational space coordinate. More... | |
| class | OperationalModelBase |
| class | ProjectedDynamics |
| class | ProjectedFDSystem |
| A floating base rigid body system that uses forward dynamics. The input vector is assumed to consist of joint torques and end-effector forces expressed in the world. More... | |
| class | QuadrotorWithLoadFDSystem |
| class | RBDAcceleration |
| joint acceleration and base acceleration More... | |
| class | RBDDataMap |
| A very simple container to associate N generic data item T. More... | |
| class | RbdLinearizer |
| class | RBDState |
| joint states and base states More... | |
| class | RBDSystem |
| This is a common interface class for an RBDSystem. More... | |
| class | RobCoGenContainer |
| Container class containing all robcogen classes. More... | |
| class | SEADynamicsFirstOrder |
| class | SecondOrderActuatorDynamics |
| class | SelectionMatrix |
| Selection Matrix for a Rigid Body Dynamics System. More... | |
| class | SimpleArmTrajectoryGenerator |
| class | SpatialForceVector |
| A spatial force vector This vector contains a torque (angular) in the upper three rows and a linear force in the lower three rows. More... | |
| class | TermTaskspaceGeometricJacobian |
| A costfunction term that defines a cost on a task-space pose, for fix-base robots only. More... | |
| class | WholeBodyController |
Typedefs | |
| using | SingleDOFTrajectoryGenerator = tpl::SingleDOFTrajectoryGenerator< double > |
| template<class RBDContainer , size_t NUM_CONTACTPOINTS> | |
| using | OperationalModelRBD = tpl::OperationalModelRBD< RBDContainer, NUM_CONTACTPOINTS, double > |
| template<typename Kinematics , size_t OUTPUTS, size_t NJOINTS> | |
| using | ConstraintJacobian = tpl::ConstraintJacobian< Kinematics, OUTPUTS, NJOINTS, double > |
| template<size_t NUM_JOINTS> | |
| using | FrameJacobian = tpl::FrameJacobian< NUM_JOINTS, double > |
| template<size_t NUM_OUTPUTS, size_t NUM_JOINTS> | |
| using | JacobianBase = tpl::JacobianBase< NUM_OUTPUTS, NUM_JOINTS, double > |
| template<size_t NUM_OUTPUTS, size_t NUM_JOINTS> | |
| using | OperationalJacobianBase = tpl::OperationalJacobianBase< NUM_OUTPUTS, NUM_JOINTS, double > |
| typedef tpl::RigidBodyAcceleration< double > | RigidBodyAcceleration |
| typedef tpl::RigidBodyPose< double > | RigidBodyPose |
| typedef tpl::RigidBodyState< double > | RigidBodyState |
| typedef tpl::RigidBodyVelocities< double > | RigidBodyVelocities |
Functions | |
| template<typename T , size_t N> | |
| std::ostream & | operator<< (std::ostream &out, const RBDDataMap< T, N > &map) |
| using ct::rbd::SingleDOFTrajectoryGenerator = typedef tpl::SingleDOFTrajectoryGenerator<double> |
| using ct::rbd::OperationalModelRBD = typedef tpl::OperationalModelRBD<RBDContainer, NUM_CONTACTPOINTS, double> |
| using ct::rbd::ConstraintJacobian = typedef tpl::ConstraintJacobian<Kinematics, OUTPUTS, NJOINTS, double> |
| using ct::rbd::FrameJacobian = typedef tpl::FrameJacobian<NUM_JOINTS, double> |
| using ct::rbd::JacobianBase = typedef tpl::JacobianBase<NUM_OUTPUTS, NUM_JOINTS, double> |
| using ct::rbd::OperationalJacobianBase = typedef tpl::OperationalJacobianBase<NUM_OUTPUTS, NUM_JOINTS, double> |
| typedef tpl::RigidBodyAcceleration<double> ct::rbd::RigidBodyAcceleration |
| typedef tpl::RigidBodyPose<double> ct::rbd::RigidBodyPose |
| typedef tpl::RigidBodyState<double> ct::rbd::RigidBodyState |
| typedef tpl::RigidBodyVelocities<double> ct::rbd::RigidBodyVelocities |
|
inline |