wbc
|
▼Cwbc::Constraint | Abstract class to represent a generic hard (linear) constraint for a WBC optimization problem. the constraint belongs to one of three types: equality Ax = b inequality lb <= Ax <= ub bounds lb <= x <= ub |
Cwbc::ContactsAccelerationConstraint | Abstract class to represent a generic hard constraint for a WBC optimization problem |
Cwbc::ContactsFrictionPointConstraint | |
Cwbc::ContactsFrictionSurfaceConstraint | |
Cwbc::ContactsVelocityConstraint | Abstract class to represent a generic hard constraint for a WBC optimization problem |
Cwbc::EffortLimitsAccelerationConstraint | Effort limits constraint for reduced TSID scene since torques are not part of qp, torque limits are enforced through acceleration and external forces limits using the linear dependecy given by the dynamic model |
Cwbc::JointLimitsAccelerationConstraint | Abstract class to represent a generic hard constraint for a WBC optimization problem |
Cwbc::JointLimitsVelocityConstraint | Abstract class to represent a generic hard constraint for a WBC optimization problem |
Cwbc::RigidbodyDynamicsConstraint | Abstract class to represent a generic hard constraint for a WBC optimization problem |
Cwbc::types::Contact | Describes a rigid contact between a robot link and the environment. This can be either a point or surface contact |
Cwbc::HierarchicalQP | Describes a hierarchy of quadratic programs |
Cwbc::types::JointCommand | |
Cwbc::JointIntegrator | Implements different numerical integrators |
Cwbc::types::JointLimits | |
Cwbc::JointPosPDController | Implements a PD Controller with feed forward on the base-Joints type. The following control schemes are available: |
Cwbc::types::JointState | Describes either the state or the command for a set of joints, i.e., its actual or target position, velocity, acceleration and effort |
Cwbc::types::Limits | |
Clogger | |
Cwbc::RobotModel::Matrix | |
▼Cwbc::PIDController | Implements an n-dimensional PID controller |
Cwbc::WrenchPIDController | CartesianForcePIDController implements a PID Controller on a Wrench data type |
Cwbc::PIDCtrlParams | |
Cwbc::PluginLoader | Helper class to load the robot model, solver and scene plugins |
Cwbc::RobotModel::Pose | |
Cwbc::types::Pose | |
▼Cwbc::PotentialField | Base class for potential fields |
Cwbc::PlanarPotentialField | Planar Potential field. The gradient will be constant on planes parallel to the plane defined by x0 (origin) and n (surface normal) |
Cwbc::RadialPotentialField | Radial Potential field. The computed gradient will be constant on volumnes with constant radius around the center of the potential field: |
Cwbc::PotentialFieldInfo | |
▼Cwbc::PotentialFieldsController | Eigen class for potential field controllers |
Cwbc::CartesianPotentialFieldsController | The PotentialFieldsController class implements a multi potential field controller in Cartesian space |
Cwbc::JointLimitAvoidanceController | |
▼Cwbc::QPSolver | Base class for all QP solvers |
Cwbc::EiquadprogSolver | Wrapper for the qp-solver eiquadprog (see https://github.com/stack-of-tasks/eiquadprog). It solves problems of shape: |
Cwbc::HPIPMSolver | |
Cwbc::OsqpSolver | The OsqpSolver solves convex quadratic programs (QPs) of the form |
Cwbc::ProxQPSolver | Wrapper for the qp-solver prox-qp (see https://github.com/Simple-Robotics/proxsuite). It solves problems of shape: |
Cwbc::QPOASESSolver | Wrapper for the qp-solver qpoases (see https://www.coin-or.org/qpOASES/doc/3.0/manual.pdf). It solves problems of shape: |
Cwbc::QPSwiftSolver | |
▼Cwbc::QPSolverFactory | |
Cwbc::QPSolverRegistry< wbc::EiquadprogSolver > | |
Cwbc::QPSolverRegistry< wbc::HPIPMSolver > | |
Cwbc::QPSolverRegistry< wbc::OsqpSolver > | |
Cwbc::QPSolverRegistry< wbc::ProxQPSolver > | |
Cwbc::QPSolverRegistry< wbc::QPOASESSolver > | |
Cwbc::QPSolverRegistry< wbc::QPSwiftSolver > | |
Cwbc::QPSolverRegistry< T > | |
Cwbc::QuadraticProgram | Describes a quadratic program of the form |
Cwbc::RobotModel::RigidBodyState | |
Cwbc::types::RigidBodyState | |
▼Cwbc::RobotModel | Interface for all robot models. This has to provide all kinematics and dynamics information that is required for WBC. Conventions and usage: |
Cwbc::RobotModelHyrodyn | |
Cwbc::RobotModelPinocchio | |
Cwbc::RobotModelRBDL | |
Cwbc::RobotModelConfig | Robot Model configuration class, containts information like urdf file, type of robot model to be loaded, etc |
▼Cwbc::RobotModelFactory | |
Cwbc::RobotModelRegistry< wbc::RobotModelHyrodyn > | |
Cwbc::RobotModelRegistry< wbc::RobotModelPinocchio > | |
Cwbc::RobotModelRegistry< wbc::RobotModelRBDL > | |
Cwbc::RobotModelRegistry< T > | |
▼Cwbc::Scene | Base class for all wbc scenes |
Cwbc::AccelerationSceneReducedTSID | Acceleration-based implementation of the WBC Scene. It sets up and solves the following problem: |
Cwbc::AccelerationSceneTSID | Acceleration-based implementation of the WBC Scene. It sets up and solves the following problem: |
Cwbc::VelocitySceneQP | Velocity-based implementation of the WBC Scene. It sets up and solves the following problem: |
▼Cwbc::SceneFactory | |
Cwbc::SceneRegistry< wbc::AccelerationSceneReducedTSID > | |
Cwbc::SceneRegistry< wbc::AccelerationSceneTSID > | |
Cwbc::SceneRegistry< wbc::VelocitySceneQP > | |
Cwbc::SceneRegistry< T > | |
Cwbc::RobotModel::SpatialAcceleration | |
Cwbc::types::SpatialAcceleration | |
▼Cwbc::Task | Abstract class to represent a generic task for a WBC optimization problem |
Cwbc::CoMAccelerationTask | Implementation of a CoM velocity task |
Cwbc::CoMVelocityTask | Implementation of a CoM velocity task |
Cwbc::ContactForceTask | |
Cwbc::JointAccelerationTask | Implementation of a Joint velocity task |
Cwbc::JointVelocityTask | Implementation of a Joint velocity task |
Cwbc::SpatialAccelerationTask | Implementation of a Cartesian acceleration task |
Cwbc::SpatialVelocityTask | Implementation of a Cartesian velocity task |
Cwbc::TaskConfig | Defines a task in the whole body control problem |
Cwbc::RobotModel::Twist | |
Cwbc::types::Twist | |
Cwbc::URDFTools | |
Cwbc::RobotModel::Vector | |
Cwbc::types::Wrench |