kinematics-dynamics
|
Abstract base class for a cartesian solver.
#include <ICartesianSolver.h>
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... | |
|
pure virtual |
x | 6-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). |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.
|
pure virtual |
x_old_obj_in | 6-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_old | 6-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_obj | 6-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). |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.
|
pure virtual |
q | Vector describing current position in joint space (meters or degrees). |
xdot | 6-element vector describing desired velocity in cartesian space; first three elements denote translational velocity (meters/second), last three denote angular velocity (radians/second). |
qdot | Vector describing target velocity in joint space (meters/second or degrees/second). |
frame | Points at the reference_frame the desired position is expressed in. |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.
|
pure virtual |
q | Vector describing a position in joint space (meters or degrees). |
x | 6-element vector describing same position in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians). |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.
|
pure virtual |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.
|
pure virtual |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.
|
pure virtual |
q | Vector describing current position in joint space (meters or degrees). |
qdot | Vector describing current velocity in joint space (meters/second or degrees/second). |
qdotdot | Vector describing current acceleration in joint space (meters/second² or degrees/second²). |
ftip | Vector 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²). |
t | 6-element vector describing desired forces in cartesian space; first three elements denote translational acceleration (meters/second²), last three denote angular acceleration (radians/second²). |
frame | Points at the reference_frame ftip is expressed in. |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.
|
inlinevirtual |
q | Vector describing current position in joint space (meters or degrees). |
qdot | Vector describing current velocity in joint space (meters/second or degrees/second). |
qdotdot | Vector describing current acceleration in joint space (meters/second² or degrees/second²). |
fexts | vector 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²). |
t | 6-element vector describing desired forces in cartesian space; first three elements denote translational acceleration (meters/second²), last three denote angular acceleration (radians/second²). |
|
pure virtual |
Assumes null joint velocities and accelerations, and no external forces.
q | Vector describing current position in joint space (meters or degrees). |
t | 6-element vector describing desired forces in cartesian space; first three elements denote translational acceleration (meters/second²), last three denote angular acceleration (radians/second²). |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.
|
pure virtual |
xd | 6-element vector describing desired position in cartesian space; first three elements denote translation (meters), last three denote rotation in scaled axis-angle representation (radians). |
qGuess | Vector describing current position in joint space (meters or degrees). |
q | Vector describing target position in joint space (meters or degrees). |
frame | Points at the reference_frame the desired position is expressed in. |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.
|
pure virtual |
The result is an infinitesimal displacement twist, i.e. a vector, for which the operation of addition makes physical sense.
xLhs | 6-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). |
xRhs | 6-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). |
xOut | 6-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). |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.
|
pure virtual |
Implemented in roboticslab::KdlTreeSolver, roboticslab::KdlSolver, and roboticslab::AsibotSolver.