kinematics-dynamics
Public Types | Public Member Functions | List of all members
roboticslab::ICartesianSolver Class Referenceabstract

Abstract base class for a cartesian solver.

#include <ICartesianSolver.h>

Inheritance diagram for roboticslab::ICartesianSolver:
roboticslab::AsibotSolver roboticslab::KdlSolver roboticslab::KdlTreeSolver

Public Types

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 Member Functions

virtual ~ICartesianSolver ()=default
 Destructor.
 
virtual int getNumJoints ()=0
 Get number of joints for which the solver has been configured. More...
 
virtual int getNumTcps ()=0
 Get number of TCPs for which the solver has been configured. More...
 
virtual bool appendLink (const std::vector< double > &x)=0
 Append an additional link. More...
 
virtual bool restoreOriginalChain ()=0
 Restore original kinematic chain. More...
 
virtual bool changeOrigin (const std::vector< double > &x_old_obj, const std::vector< double > &x_new_old, std::vector< double > &x_new_obj)=0
 Change origin in which a pose is expressed. More...
 
virtual bool fwdKin (const std::vector< double > &q, std::vector< double > &x)=0
 Perform forward kinematics. More...
 
virtual bool poseDiff (const std::vector< double > &xLhs, const std::vector< double > &xRhs, std::vector< double > &xOut)=0
 Obtain difference between supplied pose inputs. More...
 
virtual bool invKin (const std::vector< double > &xd, const std::vector< double > &qGuess, std::vector< double > &q, reference_frame frame=BASE_FRAME)=0
 Perform inverse kinematics. More...
 
virtual bool diffInvKin (const std::vector< double > &q, const std::vector< double > &xdot, std::vector< double > &qdot, reference_frame frame=BASE_FRAME)=0
 Perform differential inverse kinematics. More...
 
virtual bool invDyn (const std::vector< double > &q, std::vector< double > &t)=0
 Perform inverse dynamics. More...
 
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. More...
 
virtual 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=BASE_FRAME)=0
 Perform inverse dynamics. More...
 

Member Enumeration Documentation

◆ reference_frame

Enumerator
BASE_FRAME 

Base frame.

TCP_FRAME 

End-effector frame (TCP)

Member Function Documentation

◆ appendLink()

virtual bool roboticslab::ICartesianSolver::appendLink ( const std::vector< double > &  x)
pure virtual
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

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.

◆ changeOrigin()

virtual bool roboticslab::ICartesianSolver::changeOrigin ( const std::vector< double > &  x_old_obj,
const std::vector< double > &  x_new_old,
std::vector< double > &  x_new_obj 
)
pure virtual
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

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.

◆ diffInvKin()

virtual bool roboticslab::ICartesianSolver::diffInvKin ( const std::vector< double > &  q,
const std::vector< double > &  xdot,
std::vector< double > &  qdot,
reference_frame  frame = BASE_FRAME 
)
pure virtual
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

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.

◆ fwdKin()

virtual bool roboticslab::ICartesianSolver::fwdKin ( const std::vector< double > &  q,
std::vector< double > &  x 
)
pure virtual
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

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.

◆ getNumJoints()

virtual int roboticslab::ICartesianSolver::getNumJoints ( )
pure virtual
Returns
Number of joints.

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.

◆ getNumTcps()

virtual int roboticslab::ICartesianSolver::getNumTcps ( )
pure virtual
Returns
The number of TCPs.

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.

◆ invDyn() [1/3]

virtual bool roboticslab::ICartesianSolver::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 = BASE_FRAME 
)
pure virtual
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

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.

◆ invDyn() [2/3]

virtual bool roboticslab::ICartesianSolver::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 
)
inlinevirtual
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²).
fextsvector of external forces applied to each robot segment, 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²).
Returns
true on success, false otherwise

◆ invDyn() [3/3]

virtual bool roboticslab::ICartesianSolver::invDyn ( const std::vector< double > &  q,
std::vector< double > &  t 
)
pure virtual

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

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.

◆ invKin()

virtual bool roboticslab::ICartesianSolver::invKin ( const std::vector< double > &  xd,
const std::vector< double > &  qGuess,
std::vector< double > &  q,
reference_frame  frame = BASE_FRAME 
)
pure virtual
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

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.

◆ poseDiff()

virtual bool roboticslab::ICartesianSolver::poseDiff ( const std::vector< double > &  xLhs,
const std::vector< double > &  xRhs,
std::vector< double > &  xOut 
)
pure virtual

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

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.

◆ restoreOriginalChain()

virtual bool roboticslab::ICartesianSolver::restoreOriginalChain ( )
pure virtual
Returns
true on success, false otherwise

Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.


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