wbc
wbc Namespace Reference

Namespaces

namespace  types
 

Classes

class  AccelerationSceneReducedTSID
 Acceleration-based implementation of the WBC Scene. It sets up and solves the following problem: More...
 
class  AccelerationSceneTSID
 Acceleration-based implementation of the WBC Scene. It sets up and solves the following problem: More...
 
class  CartesianPotentialFieldsController
 The PotentialFieldsController class implements a multi potential field controller in Cartesian space. More...
 
class  CoMAccelerationTask
 Implementation of a CoM velocity task. More...
 
class  CoMVelocityTask
 Implementation of a CoM velocity task. More...
 
class  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. More...
 
class  ContactForceTask
 
class  ContactsAccelerationConstraint
 Abstract class to represent a generic hard constraint for a WBC optimization problem. More...
 
class  ContactsFrictionPointConstraint
 
class  ContactsFrictionSurfaceConstraint
 
class  ContactsVelocityConstraint
 Abstract class to represent a generic hard constraint for a WBC optimization problem. More...
 
class  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. More...
 
class  EiquadprogSolver
 The EiquadprogSolver class is a wrapper for the qp-solver eiquadprog (see https://github.com/stack-of-tasks/eiquadprog). It solves problems of shape: More...
 
struct  HierarchicalQP
 Describes a hierarchy of quadratic programs. More...
 
class  HPIPMSolver
 
class  JointAccelerationTask
 Implementation of a Joint velocity task. More...
 
class  JointIntegrator
 The JointIntegrator class implements different numerical integrators. More...
 
class  JointLimitAvoidanceController
 
class  JointLimitsAccelerationConstraint
 Abstract class to represent a generic hard constraint for a WBC optimization problem. More...
 
class  JointLimitsVelocityConstraint
 Abstract class to represent a generic hard constraint for a WBC optimization problem. More...
 
class  JointPosPDController
 The JointPosPDController class implements a PD Controller with feed forward on the base-Joints type. The following control schemes are available: More...
 
class  JointVelocityTask
 Implementation of a Joint velocity task. More...
 
class  OsqpSolver
 The OsqpSolver solves convex quadratic programs (QPs) of the form. More...
 
class  PIDController
 The PIDController class implements an n-dimensional PID controller. More...
 
class  PIDCtrlParams
 
class  PlanarPotentialField
 Planar Potential field. The gradient will be constant on planes parallel to the plane defined by x0 (origin) and n (surface normal) More...
 
class  PluginLoader
 Helper class to load the robot model, solver and scene plugins. More...
 
class  PotentialField
 Base class for potential fields. More...
 
struct  PotentialFieldInfo
 
class  PotentialFieldsController
 Eigen class for potential field controllers. More...
 
class  ProxQPSolver
 The ProxQPSolver class is a wrapper for the qp-solver prox-qp (see https://github.com/Simple-Robotics/proxsuite). It solves problems of shape: More...
 
class  QPOASESSolver
 The QPOASESSolver class is a wrapper for the qp-solver qpoases (see https://www.coin-or.org/qpOASES/doc/3.0/manual.pdf). It solves problems of shape: More...
 
class  QPSolver
 Base class for all QP solvers. More...
 
struct  QPSolverFactory
 
struct  QPSolverRegistry
 
class  QPSwiftSolver
 
struct  QuadraticProgram
 Describes a quadratic program of the form. More...
 
class  RadialPotentialField
 Radial Potential field. The computed gradient will be constant on volumnes with constant radius around the center of the potential field: More...
 
class  RigidbodyDynamicsConstraint
 Abstract class to represent a generic hard constraint for a WBC optimization problem. More...
 
class  RobotModel
 Interface for all robot models. This has to provide all kinematics and dynamics information that is required for WBC. Conventions and usage: More...
 
struct  RobotModelConfig
 Robot Model configuration class, containts information like urdf file, type of robot model to be loaded, etc. More...
 
struct  RobotModelFactory
 
class  RobotModelHyrodyn
 
class  RobotModelPinocchio
 
class  RobotModelRBDL
 
struct  RobotModelRegistry
 
class  Scene
 Base class for all wbc scenes. More...
 
struct  SceneFactory
 
struct  SceneRegistry
 
class  SpatialAccelerationTask
 Implementation of a Cartesian acceleration task. More...
 
class  SpatialVelocityTask
 Implementation of a Cartesian velocity task. More...
 
class  Task
 Abstract class to represent a generic task for a WBC optimization problem. More...
 
class  TaskConfig
 Defines a task in the whole body control problem. More...
 
class  URDFTools
 
class  VelocitySceneQP
 Velocity-based implementation of the WBC Scene. It sets up and solves the following problem: More...
 
class  WrenchPIDController
 CartesianForcePIDController implements a PID Controller on a Wrench data type. More...
 

Typedefs

typedef std::shared_ptr< ContactsAccelerationConstraintContactsAccelerationConstraintPtr
 
typedef std::shared_ptr< ContactsVelocityConstraintContactsVelocityConstraintPtr
 
typedef std::shared_ptr< EffortLimitsAccelerationConstraintEffortLimitsAccelerationConstraintPtr
 
typedef std::shared_ptr< JointLimitsAccelerationConstraintJointLimitsAccelerationConstraintPtr
 
typedef std::shared_ptr< JointLimitsVelocityConstraintJointLimitsVelocityConstraintPtr
 
typedef std::shared_ptr< RigidbodyDynamicsConstraintRigidbodyDynamicsConstraintPtr
 
using JointPosPDControllerPtr = std::shared_ptr<JointPosPDController>
 
typedef std::shared_ptr< PlanarPotentialFieldPlanarPotentialFieldPtr
 
typedef std::shared_ptr< PotentialFieldPotentialFieldPtr
 
typedef std::shared_ptr< ConstraintConstraintPtr
 
typedef std::shared_ptr< QPSolverQPSolverPtr
 
typedef std::shared_ptr< RobotModelRobotModelPtr
 
typedef std::shared_ptr< SceneScenePtr
 
using TaskPtr = std::shared_ptr<Task>
 
typedef std::shared_ptr< CoMAccelerationTaskCoMAccelerationTaskPtr
 
typedef std::shared_ptr< CoMVelocityTaskCoMVelocityTaskPtr
 
typedef std::shared_ptr< ContactForceTaskContactForceTaskPtr
 
using JointAccelerationTaskPtr = std::shared_ptr<JointAccelerationTask>
 
typedef std::shared_ptr< JointVelocityTaskJointVelocityTaskPtr
 
using SpatialAccelerationTaskPtr = std::shared_ptr<SpatialAccelerationTask>
 
typedef std::shared_ptr< SpatialVelocityTaskSpatialVelocityTaskPtr
 

Enumerations

enum  TaskType {
  unset = -1 , spatial_velocity , spatial_acceleration , com_velocity ,
  com_acceleration , joint_velocity , joint_acceleration , contact_force
}
 

Functions

template<typename T>
QPSolvercreateT ()
 
template<typename T>
RobotModelcreateT ()
 
template<typename T, typename RobotModelPtr, typename QPSolverPtr>
ScenecreateT (RobotModelPtr robot_model, QPSolverPtr solver, const double dt)
 
void printRbs (types::RigidBodyState rbs)
 
types::JointState makeRandomJointState (uint n)
 
types::RigidBodyState makeRandomFloatingBaseState ()
 
void testFK (RobotModelPtr robot_model, const string &tip_frame, bool verbose)
 
void testSpaceJacobian (RobotModelPtr robot_model, const string &tip_frame, bool verbose)
 
void testBodyJacobian (RobotModelPtr robot_model, const string &tip_frame, bool verbose)
 
void testCoMJacobian (RobotModelPtr robot_model, bool verbose)
 
void testInverseDynamics (RobotModelPtr robot_model, bool verbose)
 
void testFK (RobotModelPtr robot_model, const std::string &tip_frame, bool verbose=false)
 
void testSpaceJacobian (RobotModelPtr robot_model, const std::string &tip_frame, bool verbose=false)
 
void testBodyJacobian (RobotModelPtr robot_model, const std::string &tip_frame, bool verbose=false)
 
void testDynamics (RobotModelPtr robot_model, bool verbose)
 

Typedef Documentation

◆ CoMAccelerationTaskPtr

◆ CoMVelocityTaskPtr

typedef std::shared_ptr<CoMVelocityTask> wbc::CoMVelocityTaskPtr

◆ ConstraintPtr

typedef std::shared_ptr<Constraint> wbc::ConstraintPtr

◆ ContactForceTaskPtr

typedef std::shared_ptr<ContactForceTask> wbc::ContactForceTaskPtr

◆ ContactsAccelerationConstraintPtr

◆ ContactsVelocityConstraintPtr

◆ EffortLimitsAccelerationConstraintPtr

◆ JointAccelerationTaskPtr

◆ JointLimitsAccelerationConstraintPtr

◆ JointLimitsVelocityConstraintPtr

◆ JointPosPDControllerPtr

◆ JointVelocityTaskPtr

typedef std::shared_ptr<JointVelocityTask> wbc::JointVelocityTaskPtr

◆ PlanarPotentialFieldPtr

◆ PotentialFieldPtr

typedef std::shared_ptr<PotentialField> wbc::PotentialFieldPtr

◆ QPSolverPtr

typedef std::shared_ptr<QPSolver> wbc::QPSolverPtr

◆ RigidbodyDynamicsConstraintPtr

◆ RobotModelPtr

typedef std::shared_ptr<RobotModel> wbc::RobotModelPtr

◆ ScenePtr

typedef std::shared_ptr<Scene> wbc::ScenePtr

◆ SpatialAccelerationTaskPtr

◆ SpatialVelocityTaskPtr

◆ TaskPtr

using wbc::TaskPtr = std::shared_ptr<Task>

Enumeration Type Documentation

◆ TaskType

Enumerator
unset 
spatial_velocity 
spatial_acceleration 
com_velocity 
com_acceleration 
joint_velocity 
joint_acceleration 
contact_force 

Function Documentation

◆ createT() [1/3]

template<typename T>
QPSolver * wbc::createT ( )

◆ createT() [2/3]

template<typename T>
RobotModel * wbc::createT ( )

◆ createT() [3/3]

template<typename T, typename RobotModelPtr, typename QPSolverPtr>
Scene * wbc::createT ( RobotModelPtr robot_model,
QPSolverPtr solver,
const double dt )

◆ makeRandomFloatingBaseState()

types::RigidBodyState wbc::makeRandomFloatingBaseState ( )

◆ makeRandomJointState()

types::JointState wbc::makeRandomJointState ( uint n)

◆ printRbs()

void wbc::printRbs ( types::RigidBodyState rbs)

◆ testBodyJacobian() [1/2]

void wbc::testBodyJacobian ( RobotModelPtr robot_model,
const std::string & tip_frame,
bool verbose = false )

◆ testBodyJacobian() [2/2]

void wbc::testBodyJacobian ( RobotModelPtr robot_model,
const string & tip_frame,
bool verbose )

◆ testCoMJacobian()

void wbc::testCoMJacobian ( RobotModelPtr robot_model,
bool verbose )

◆ testDynamics()

void wbc::testDynamics ( RobotModelPtr robot_model,
bool verbose )

◆ testFK() [1/2]

void wbc::testFK ( RobotModelPtr robot_model,
const std::string & tip_frame,
bool verbose = false )

◆ testFK() [2/2]

void wbc::testFK ( RobotModelPtr robot_model,
const string & tip_frame,
bool verbose )

◆ testInverseDynamics()

void wbc::testInverseDynamics ( RobotModelPtr robot_model,
bool verbose )

◆ testSpaceJacobian() [1/2]

void wbc::testSpaceJacobian ( RobotModelPtr robot_model,
const std::string & tip_frame,
bool verbose = false )

◆ testSpaceJacobian() [2/2]

void wbc::testSpaceJacobian ( RobotModelPtr robot_model,
const string & tip_frame,
bool verbose )