kinematics-dynamics
Loading...
Searching...
No Matches
Public Member Functions | Private Member Functions | Private Attributes | List of all members
KdlSolver Class Reference

The KdlSolver class implements ICartesianSolver.

#include <KdlSolver.hpp>

Inheritance diagram for KdlSolver:
roboticslab::ICartesianSolver KdlSolver_ParamsParser

Public Member Functions

int getNumJoints () override
 Get number of joints for which the solver has been configured.
 
int getNumTcps () override
 Get number of TCPs for which the solver has been configured.
 
bool appendLink (const std::vector< double > &x) override
 Append an additional link.
 
bool restoreOriginalChain () override
 Restore original kinematic chain.
 
bool changeOrigin (const std::vector< double > &x_old_obj, const std::vector< double > &x_new_old, std::vector< double > &x_new_obj) override
 Change origin in which a pose is expressed.
 
bool fwdKin (const std::vector< double > &q, std::vector< double > &x) override
 Perform forward kinematics.
 
bool poseDiff (const std::vector< double > &xLhs, const std::vector< double > &xRhs, std::vector< double > &xOut) override
 Obtain difference between supplied pose inputs.
 
bool invKin (const std::vector< double > &xd, const std::vector< double > &qGuess, std::vector< double > &q, reference_frame frame) override
 Perform inverse kinematics.
 
bool diffInvKin (const std::vector< double > &q, const std::vector< double > &xdot, std::vector< double > &qdot, reference_frame frame) override
 Perform differential inverse kinematics.
 
bool invDyn (const std::vector< double > &q, std::vector< double > &t) override
 Perform inverse dynamics.
 
bool invDyn (const std::vector< double > &q, const std::vector< double > &qdot, const std::vector< double > &qdotdot, const std::vector< double > &ftip, std::vector< double > &t, reference_frame frame) override
 Perform inverse dynamics.
 
bool open (yarp::os::Searchable &config) override
 
bool close () override
 
- Public Member Functions inherited from roboticslab::ICartesianSolver
virtual ~ICartesianSolver ()=default
 Destructor.
 
virtual bool invDyn (const std::vector< double > &q, const std::vector< double > &qdot, const std::vector< double > &qdotdot, const std::vector< std::vector< double > > &fexts, std::vector< double > &t)
 Perform inverse dynamics.
 
- Public Member Functions inherited from KdlSolver_ParamsParser
bool parseParams (const yarp::os::Searchable &config) override
 
std::string getDeviceClassName () const override
 
std::string getDeviceName () const override
 
std::string getDocumentationOfDeviceParams () const override
 
std::vector< std::string > getListOfParams () const override
 

Private Member Functions

const yarp::os::LogComponent & logc () const
 

Private Attributes

std::mutex mtx
 
KDL::Chain chain
 
KDL::Chain originalChain
 
KDL::ChainFkSolverPos * fkSolverPos {nullptr}
 
KDL::ChainIkSolverPos * ikSolverPos {nullptr}
 
KDL::ChainIkSolverVel * ikSolverVel {nullptr}
 
KDL::ChainIdSolver * idSolver {nullptr}
 

Additional Inherited Members

- Public Types inherited from roboticslab::ICartesianSolver
enum  reference_frame { BASE_FRAME = yarp::os::createVocab32('c','p','f','b') , TCP_FRAME = yarp::os::createVocab32('c','p','f','t') }
 Lists supported reference frames. More...
 
- Public Attributes inherited from KdlSolver_ParamsParser
const std::string m_device_classname = {"KdlSolver"}
 
const std::string m_device_name = {"KdlSolver"}
 
bool m_parser_is_strict = false
 
const parser_version_type m_parser_version = {}
 
const std::string m_quiet_defaultValue = {"false"}
 
const std::string m_kinematics_defaultValue = {""}
 
const std::string m_gravity_defaultValue = {"(0.0 0.0 9.81)"}
 
const std::string m_ikPos_defaultValue = {"st"}
 
const std::string m_ikVel_defaultValue = {"pinv"}
 
const std::string m_epsPos_defaultValue = {"1e-5"}
 
const std::string m_maxIterPos_defaultValue = {"1000"}
 
const std::string m_epsVel_defaultValue = {"1e-5"}
 
const std::string m_maxIterVel_defaultValue = {"150"}
 
const std::string m_lambda_defaultValue = {"0.01"}
 
const std::string m_weightsLMA_defaultValue = {"(1.0 1.0 1.0 0.1 0.1 0.1)"}
 
const std::string m_weightsJS_defaultValue = {""}
 
const std::string m_weightsTS_defaultValue = {""}
 
const std::string m_invKinStrategy_defaultValue = {"leastOverallAngularDisplacement"}
 
const std::string m_mins_defaultValue = {""}
 
const std::string m_maxs_defaultValue = {""}
 
bool m_quiet = {false}
 
std::string m_kinematics = {}
 
std::vector< double > m_gravity = { }
 
std::string m_ikPos = {"st"}
 
std::string m_ikVel = {"pinv"}
 
double m_epsPos = {1e-5}
 
int m_maxIterPos = {1000}
 
double m_epsVel = {1e-5}
 
int m_maxIterVel = {150}
 
double m_lambda = {0.01}
 
std::vector< double > m_weightsLMA = { }
 
std::vector< double > m_weightsJS = {}
 
std::vector< double > m_weightsTS = {}
 
std::string m_invKinStrategy = {"leastOverallAngularDisplacement"}
 
std::vector< double > m_mins = {}
 
std::vector< double > m_maxs = {}
 

Member Function Documentation

◆ appendLink()

bool KdlSolver::appendLink ( const std::vector< double > &  x)
overridevirtual
Parameters
x6-element vector describing end-effector frame in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
Returns
true on success, false otherwise

Implements roboticslab::ICartesianSolver.

◆ changeOrigin()

bool KdlSolver::changeOrigin ( const std::vector< double > &  x_old_obj,
const std::vector< double > &  x_new_old,
std::vector< double > &  x_new_obj 
)
overridevirtual
Parameters
x_old_obj_in6-element vector describing a pose in cartesian space, expressed in the old frame; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
x_new_old6-element vector describing a transformation from the new to the old frame; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
x_new_obj6-element vector describing a pose in cartesian space, expressed in the new frame; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
Returns
true on success, false otherwise

Implements roboticslab::ICartesianSolver.

◆ diffInvKin()

bool KdlSolver::diffInvKin ( const std::vector< double > &  q,
const std::vector< double > &  xdot,
std::vector< double > &  qdot,
reference_frame  frame 
)
overridevirtual
Parameters
qVector describing current position in joint space (meters or degrees).
xdot6-element vector describing desired velocity in cartesian space; first three elements denote translational velocity (meters/second), last three denote angular velocity (radians/second).
qdotVector describing target velocity in joint space (meters/second or degrees/second).
framePoints at the reference_frame the desired position is expressed in.
Returns
true on success, false otherwise

Implements roboticslab::ICartesianSolver.

◆ fwdKin()

bool KdlSolver::fwdKin ( const std::vector< double > &  q,
std::vector< double > &  x 
)
overridevirtual
Parameters
qVector describing a position in joint space (meters or degrees).
x6-element vector describing same position in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
Returns
true on success, false otherwise

Implements roboticslab::ICartesianSolver.

◆ getNumJoints()

int KdlSolver::getNumJoints ( )
overridevirtual
Returns
Number of joints.

Implements roboticslab::ICartesianSolver.

◆ getNumTcps()

int KdlSolver::getNumTcps ( )
overridevirtual
Returns
The number of TCPs.

Implements roboticslab::ICartesianSolver.

◆ invDyn() [1/2]

bool KdlSolver::invDyn ( const std::vector< double > &  q,
const std::vector< double > &  qdot,
const std::vector< double > &  qdotdot,
const std::vector< double > &  ftip,
std::vector< double > &  t,
reference_frame  frame 
)
overridevirtual
Parameters
qVector describing current position in joint space (meters or degrees).
qdotVector describing current velocity in joint space (meters/second or degrees/second).
qdotdotVector describing current acceleration in joint space (meters/second² or degrees/second²).
ftipVector describing an external force applied to the robot tip, expressed in cartesian space; first three elements denote translational acceleration (meters/second²), last three denote angular acceleration (radians/second²).
t6-element vector describing desired forces in cartesian space; first three elements denote translational acceleration (meters/second²), last three denote angular acceleration (radians/second²).
framePoints at the reference_frame ftip is expressed in.
Returns
true on success, false otherwise

Implements roboticslab::ICartesianSolver.

◆ invDyn() [2/2]

bool KdlSolver::invDyn ( const std::vector< double > &  q,
std::vector< double > &  t 
)
overridevirtual

Assumes null joint velocities and accelerations, and no external forces.

Parameters
qVector describing current position in joint space (meters or degrees).
t6-element vector describing desired forces in cartesian space; first three elements denote translational acceleration (meters/second²), last three denote angular acceleration (radians/second²).
Returns
true on success, false otherwise

Implements roboticslab::ICartesianSolver.

◆ invKin()

bool KdlSolver::invKin ( const std::vector< double > &  xd,
const std::vector< double > &  qGuess,
std::vector< double > &  q,
reference_frame  frame 
)
overridevirtual
Parameters
xd6-element vector describing desired position in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
qGuessVector describing current position in joint space (meters or degrees).
qVector describing target position in joint space (meters or degrees).
framePoints at the reference_frame the desired position is expressed in.
Returns
true on success, false otherwise

Implements roboticslab::ICartesianSolver.

◆ poseDiff()

bool KdlSolver::poseDiff ( const std::vector< double > &  xLhs,
const std::vector< double > &  xRhs,
std::vector< double > &  xOut 
)
overridevirtual

The result is an infinitesimal displacement twist, i.e. a vector, for which the operation of addition makes physical sense.

Parameters
xLhs6-element vector describing a pose in cartesian space (left hand side); first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
xRhs6-element vector describing a pose in cartesian space (right hand side); first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
xOut6-element vector describing a pose in cartesian space (result); first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians).
Returns
true on success, false otherwise

Implements roboticslab::ICartesianSolver.

◆ restoreOriginalChain()

bool KdlSolver::restoreOriginalChain ( )
overridevirtual
Returns
true on success, false otherwise

Implements roboticslab::ICartesianSolver.


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