ChppGikSolver Class Reference

Compute the joints updates for a hierarchy of simultaneous tasks. More...

#include <hpp/gik/core/solver.hh>

Public Member Functions

 ChppGikSolver (CjrlDynamicRobot &inRobot)
 Constructor. More...
 
void rootJoint (CjrlJoint &inRootJoint)
 Select the root joint. More...
 
bool weights (const vectorN &inWeights)
 Set weights on the degrees of freedom. More...
 
void prepare (std::vector< CjrlGikStateConstraint *> &inTasks)
 Deprecated. More...
 
void solve (std::vector< CjrlGikStateConstraint *> &inTasks, double lambda, const std::vector< double > &inSRcoefs)
 Compute a solution to the input vector of linear systems. More...
 
void solve (std::vector< CjrlGikStateConstraint *> &inTasks, double lambda)
 Compute a solution to the input vector of linear systems. More...
 
 ~ChppGikSolver ()
 Destructor. More...
 
Retrieving the solution
const vectorNsolution ()
 Get the full solution configuration including the root configuration. More...
 
const vectorNsolutionJointConfiguration ()
 Get the new joint configuration excluding the root joint. More...
 
const std::pair< vector3d, vector3d > & solutionRootConfiguration ()
 Get the new pose of the root as a 6d vector: X Y Z ROLL PITCH YAW. More...
 
const matrix4dsolutionRootPose ()
 Get the new pose of the root as a homogenous matrix. More...
 

Detailed Description

Compute the joints updates for a hierarchy of simultaneous tasks.

Constructor & Destructor Documentation

◆ ChppGikSolver()

ChppGikSolver::ChppGikSolver ( CjrlDynamicRobot &  inRobot)

Constructor.

Parameters
inRobotrobot

◆ ~ChppGikSolver()

ChppGikSolver::~ChppGikSolver ( )

Destructor.

Member Function Documentation

◆ prepare()

void ChppGikSolver::prepare ( std::vector< CjrlGikStateConstraint *> &  inTasks)

Deprecated.

Does nothing.

◆ rootJoint()

void ChppGikSolver::rootJoint ( CjrlJoint &  inRootJoint)

Select the root joint.

◆ solution()

const vectorN& ChppGikSolver::solution ( )

Get the full solution configuration including the root configuration.

Returns
a vector of size robot()->numberDof()

◆ solutionJointConfiguration()

const vectorN& ChppGikSolver::solutionJointConfiguration ( )

Get the new joint configuration excluding the root joint.

Returns
a vector of size robot()->numberDof()-6

◆ solutionRootConfiguration()

const std::pair<vector3d,vector3d>& ChppGikSolver::solutionRootConfiguration ( )

Get the new pose of the root as a 6d vector: X Y Z ROLL PITCH YAW.

Returns
a pair of vectors: first vector is [X Y Z], second is [ROLL PITCH YAW]

◆ solutionRootPose()

const matrix4d& ChppGikSolver::solutionRootPose ( )

Get the new pose of the root as a homogenous matrix.

Returns
the new transformation matrix of the root

◆ solve() [1/2]

void ChppGikSolver::solve ( std::vector< CjrlGikStateConstraint *> &  inTasks,
double  lambda,
const std::vector< double > &  inSRcoefs 
)

Compute a solution to the input vector of linear systems.

Parameters
inTasksVector of tasks in decreasing order of priority,
lambdaCoefficient applied to solution to update configuration,
inSRcoefsvector of damping coefficient. The linear systems(CjrlGikStateConstraint objects) should already be computed. The order in the vector of tasks follows decreasing priority.

◆ solve() [2/2]

void ChppGikSolver::solve ( std::vector< CjrlGikStateConstraint *> &  inTasks,
double  lambda 
)

Compute a solution to the input vector of linear systems.

Parameters
inTasksVector of tasks in decreasing order of priority,
lambdaCoefficient applied to solution to update configuration, The linear systems(CjrlGikStateConstraint objects) should already be computed. The order in the vector of tasks follows decreasing priority. Calls the other method ChppGikSolver::solve.

◆ weights()

bool ChppGikSolver::weights ( const vectorN inWeights)

Set weights on the degrees of freedom.

Returns
false if inWeights not of size robot.numberDof()