wbc
wbc::VelocitySceneQP Class Reference

Velocity-based implementation of the WBC Scene. It sets up and solves the following problem: More...

#include <VelocitySceneQP.hpp>

Inheritance diagram for wbc::VelocitySceneQP:
wbc::VelocityScene wbc::Scene

Public Member Functions

 VelocitySceneQP (RobotModelPtr robot_model, QPSolverPtr solver, const double dt)
 WbcVelocityScene.
 
virtual ~VelocitySceneQP ()
 
virtual const HierarchicalQPupdate ()
 Update the wbc scene.
 
void setHessianRegularizer (const double reg)
 setHessianRegularizer
 
double getHessianRegularizer ()
 Return the current value of hessian regularizer.
 
- Public Member Functions inherited from wbc::VelocityScene
 VelocityScene (RobotModelPtr robot_model, QPSolverPtr solver, const double dt)
 
virtual ~VelocityScene ()
 
virtual const base::commands::Joints & solve (const HierarchicalQP &hqp)
 Solve the given optimization problem.
 
virtual const TasksStatusupdateTasksStatus ()
 Compute y and y_solution for each task. y_solution denotes the task velocity that can be achieved with the solution generated by the solver and y denotes the actual joint velocity achieved by the robot. Both values can be used to evaluate the performance of WBC.
 
- Public Member Functions inherited from wbc::Scene
 Scene (RobotModelPtr robot_model, QPSolverPtr solver, const double dt)
 
 ~Scene ()
 
virtual bool configure (const std::vector< TaskConfig > &config)
 Configure the WBC scene. Create tasks and sort them by priority.
 
void setReference (const std::string &task_name, const base::samples::Joints &ref)
 Set reference input for a joint space task.
 
void setReference (const std::string &task_name, const base::samples::RigidBodyStateSE3 &ref)
 Set reference input for a cartesian space task.
 
void setTaskWeights (const std::string &task_name, const base::VectorXd &weights)
 Set Task weights input for a task.
 
void setTaskActivation (const std::string &task_name, double activation)
 Set Task activation for a task.
 
TaskPtr getTask (const std::string &name)
 Return a Particular task. Throw if the task does not exist.
 
bool hasTask (const std::string &name)
 True in case the given task exists.
 
const TasksStatusgetTasksStatus () const
 Returns all tasks as vector.
 
void getHierarchicalQP (HierarchicalQP &_hqp)
 Return tasks sorted by priority for the solver.
 
const base::commands::Joints & getSolverOutput () const
 Get current solver output.
 
const base::VectorXd & getSolverOutputRaw () const
 Get current solver output in raw values.
 
void setJointWeights (const JointWeights &weights)
 set Joint weights by given name
 
const JointWeightsgetJointWeights () const
 Get Joint weights as Named vector.
 
const JointWeightsgetActuatedJointWeights () const
 Get Joint weights as Named vector.
 
RobotModelPtr getRobotModel ()
 Return the current robot model.
 
QPSolverPtr getSolver ()
 Return the current solver.
 
std::vector< TaskConfiggetWbcConfig ()
 Return task configuration.
 

Protected Attributes

base::VectorXd s_vals
 
base::VectorXd tmp
 
base::MatrixXd sing_vect_r
 
base::MatrixXd U
 
double hessian_regularizer
 
- Protected Attributes inherited from wbc::VelocityScene
base::VectorXd q
 
base::VectorXd qd
 
base::VectorXd qdd
 
- Protected Attributes inherited from wbc::Scene
RobotModelPtr robot_model
 
QPSolverPtr solver
 
std::vector< std::vector< TaskPtr > > tasks
 
std::vector< std::vector< ConstraintPtr > > constraints
 
TasksStatus tasks_status
 
HierarchicalQP hqp
 
std::vector< int > n_task_variables_per_prio
 
bool configured
 
base::commands::Joints solver_output_joints
 
JointWeights joint_weights
 
JointWeights actuated_joint_weights
 
std::vector< TaskConfigwbc_config
 
base::VectorXd solver_output
 

Static Protected Attributes

static SceneRegistry< VelocitySceneQPreg
 
- Static Protected Attributes inherited from wbc::VelocityScene
static SceneRegistry< VelocityScenereg
 

Additional Inherited Members

- Static Public Member Functions inherited from wbc::Scene
static void sortTaskConfig (const std::vector< TaskConfig > &config, std::vector< std::vector< TaskConfig > > &sorted_config)
 Sort task config by the priorities of the tasks.
 
static uint getNTaskVariables (const std::vector< TaskConfig > &config)
 Return number of tasks per priority, given the task config.
 
static std::vector< int > getNTaskVariablesPerPrio (const std::vector< TaskConfig > &config)
 Return number of tasks per priority, given the task config.
 
- Protected Member Functions inherited from wbc::VelocityScene
virtual TaskPtr createTask (const TaskConfig &config)
 Create a task and add it to the WBC scene.
 
- Protected Member Functions inherited from wbc::Scene
void clearTasks ()
 Delete all tasks and free memory.
 

Detailed Description

Velocity-based implementation of the WBC Scene. It sets up and solves the following problem:

\[ \begin{array}{ccc} minimize & \| \mathbf{J}_w\dot{\mathbf{q}} - \mathbf{v}_d\|_2& \\ \mathbf{\dot{q}} & & \\ & & \\ s.t. & \mathbf{J}_{c,i}\dot{\mathbf{q}}=0, \, \forall i & \\ & \dot{\mathbf{q}}_{m} \leq \dot{\mathbf{q}} \leq \dot{\mathbf{q}}_{M} & \\ \end{array} \]

In contrast to the VelocityScene class, the tasks are formulated within the cost function instead of modeling them as tasks. The problem is solved with respect to a number of rigid contacts \(\mathbf{J}_{c,i}\dot{\mathbf{q}}=0, \, \forall i \) and under consideration of the joint velocity limits of the robot.

\(\dot{\mathbf{q}}\) - Vector of robot joint velocities
\(\mathbf{v}_{d}\) - Desired Spatial velocities of all tasks stacked in a vector
\(\mathbf{J}\) - Task Jacobians of all tasks stacked in a single matrix
\(\mathbf{J}_w = \mathbf{W}\mathbf{J}\) - Weighted task Jacobians
\(\mathbf{W}\) - Diagonal task weight matrix
\(\dot{\mathbf{q}}_{m},\dot{\mathbf{q}}_{M}\) - Joint velocity limits
\(\mathbf{J}_{c,i}\) - Contact Jcaobian of i-th contact point

Constructor & Destructor Documentation

◆ VelocitySceneQP()

wbc::VelocitySceneQP::VelocitySceneQP ( RobotModelPtr robot_model,
QPSolverPtr solver,
const double dt )

WbcVelocityScene.

Parameters
robot_modelPointer to the robot model
solverSolver used to solver the qp optimization problem

◆ ~VelocitySceneQP()

virtual wbc::VelocitySceneQP::~VelocitySceneQP ( )
inlinevirtual

Member Function Documentation

◆ getHessianRegularizer()

double wbc::VelocitySceneQP::getHessianRegularizer ( )
inline

Return the current value of hessian regularizer.

◆ setHessianRegularizer()

void wbc::VelocitySceneQP::setHessianRegularizer ( const double reg)
inline

setHessianRegularizer

Parameters
regThis value is added to the diagonal of the Hessian matrix inside the QP to reduce the risk of infeasibility. Default is 1e-8

◆ update()

const HierarchicalQP & wbc::VelocitySceneQP::update ( )
virtual

Update the wbc scene.

Reimplemented from wbc::VelocityScene.

Member Data Documentation

◆ hessian_regularizer

double wbc::VelocitySceneQP::hessian_regularizer
protected

◆ reg

SceneRegistry< VelocitySceneQP > wbc::VelocitySceneQP::reg
staticprotected

◆ s_vals

base::VectorXd wbc::VelocitySceneQP::s_vals
protected

◆ sing_vect_r

base::MatrixXd wbc::VelocitySceneQP::sing_vect_r
protected

◆ tmp

base::VectorXd wbc::VelocitySceneQP::tmp
protected

◆ U

base::MatrixXd wbc::VelocitySceneQP::U
protected

The documentation for this class was generated from the following files: