Tesseract
Motion Planning Environment
|
Universal Robot Inverse Kinematics Implementation. More...
#include <ur_inv_kin.h>
Public Types | |
using | Ptr = std::shared_ptr< URInvKin > |
using | ConstPtr = std::shared_ptr< const URInvKin > |
using | UPtr = std::unique_ptr< URInvKin > |
using | ConstUPtr = std::unique_ptr< const URInvKin > |
Public Types inherited from tesseract_kinematics::InverseKinematics | |
using | Ptr = std::shared_ptr< InverseKinematics > |
using | ConstPtr = std::shared_ptr< const InverseKinematics > |
using | UPtr = std::unique_ptr< InverseKinematics > |
using | ConstUPtr = std::unique_ptr< const InverseKinematics > |
Public Member Functions | |
~URInvKin () override=default | |
URInvKin (const URInvKin &other) | |
URInvKin & | operator= (const URInvKin &other) |
URInvKin (URInvKin &&)=default | |
URInvKin & | operator= (URInvKin &&)=default |
URInvKin (URParameters params, std::string base_link_name, std::string tip_link_name, std::vector< std::string > joint_names, std::string solver_name=UR_INV_KIN_CHAIN_SOLVER_NAME) | |
init Initialize UR Inverse Kinematics More... | |
tesseract_kinematics::IKSolutions | calcInvKin (const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const override final |
Calculates joint solutions given a pose for each tip link. More... | |
Eigen::Index | numJoints () const override final |
Number of joints in robot. More... | |
std::vector< std::string > | getJointNames () const override final |
Get list of joint names for kinematic object. More... | |
std::string | getBaseLinkName () const override final |
Get the robot base link name. More... | |
std::string | getWorkingFrame () const override final |
Get the inverse kinematics working frame. More... | |
std::vector< std::string > | getTipLinkNames () const override final |
Get the names of the tip links of the kinematics group. More... | |
std::string | getSolverName () const override final |
Get the name of the solver. Recommend using the name of the class. More... | |
InverseKinematics::UPtr | clone () const override final |
Clone the forward kinematics object. More... | |
Public Member Functions inherited from tesseract_kinematics::InverseKinematics | |
InverseKinematics ()=default | |
virtual | ~InverseKinematics ()=default |
InverseKinematics (const InverseKinematics &)=default | |
InverseKinematics & | operator= (const InverseKinematics &)=default |
InverseKinematics (InverseKinematics &&)=default | |
InverseKinematics & | operator= (InverseKinematics &&)=default |
virtual IKSolutions | calcInvKin (const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const =0 |
Calculates joint solutions given a pose for each tip link. More... | |
virtual std::vector< std::string > | getJointNames () const =0 |
Get list of joint names for kinematic object. More... | |
virtual Eigen::Index | numJoints () const =0 |
Number of joints in robot. More... | |
virtual std::string | getBaseLinkName () const =0 |
Get the robot base link name. More... | |
virtual std::string | getWorkingFrame () const =0 |
Get the inverse kinematics working frame. More... | |
virtual std::vector< std::string > | getTipLinkNames () const =0 |
Get the names of the tip links of the kinematics group. More... | |
virtual std::string | getSolverName () const =0 |
Get the name of the solver. Recommend using the name of the class. More... | |
virtual InverseKinematics::UPtr | clone () const =0 |
Clone the forward kinematics object. More... | |
Protected Attributes | |
URParameters | params_ |
The UR Inverse kinematics parameters. More... | |
std::string | base_link_name_ |
Link name of first link in the kinematic object. More... | |
std::string | tip_link_name_ |
Link name of last kink in the kinematic object. More... | |
std::vector< std::string > | joint_names_ |
Joint names for the kinematic object. More... | |
std::string | solver_name_ { UR_INV_KIN_CHAIN_SOLVER_NAME } |
Name of this solver. More... | |
Universal Robot Inverse Kinematics Implementation.
using tesseract_kinematics::URInvKin::ConstPtr = std::shared_ptr<const URInvKin> |
using tesseract_kinematics::URInvKin::ConstUPtr = std::unique_ptr<const URInvKin> |
using tesseract_kinematics::URInvKin::Ptr = std::shared_ptr<URInvKin> |
using tesseract_kinematics::URInvKin::UPtr = std::unique_ptr<URInvKin> |
|
overridedefault |
tesseract_kinematics::URInvKin::URInvKin | ( | const URInvKin & | other | ) |
|
default |
tesseract_kinematics::URInvKin::URInvKin | ( | URParameters | params, |
std::string | base_link_name, | ||
std::string | tip_link_name, | ||
std::vector< std::string > | joint_names, | ||
std::string | solver_name = UR_INV_KIN_CHAIN_SOLVER_NAME |
||
) |
init Initialize UR Inverse Kinematics
params | UR kinematics parameters |
base_link_name | The name of the base link for the kinematic chain |
tip_link_name | The name of the tip link for the kinematic chain |
joint_names | The joint names for the kinematic chain |
solver_name | The solver name of the kinematic chain |
|
finaloverridevirtual |
Calculates joint solutions given a pose for each tip link.
This interface supports IK for both kinematic chains that have a single tool tip link and kinematic chains that have multiple tip links. For example, consider a robot with external part positioner: a pose can be specified to be relative to the tip link of the robot or the tip link of the positioner is to support a pose relative to a active link. For example a robot with an external positioner where the pose is relative to the tip link of the positioner.
tip_link_poses | A map of poses corresponding to each tip link provided in getTipLinkNames and relative to the working frame of the kinematics group for which to solve inverse kinematics |
seed | Vector of seed joint angles (size must match number of joints in kinematic object) |
Implements tesseract_kinematics::InverseKinematics.
|
finaloverridevirtual |
Clone the forward kinematics object.
Implements tesseract_kinematics::InverseKinematics.
|
finaloverridevirtual |
Get the robot base link name.
Implements tesseract_kinematics::InverseKinematics.
|
finaloverridevirtual |
Get list of joint names for kinematic object.
Implements tesseract_kinematics::InverseKinematics.
|
finaloverridevirtual |
Get the name of the solver. Recommend using the name of the class.
Implements tesseract_kinematics::InverseKinematics.
|
finaloverridevirtual |
Get the names of the tip links of the kinematics group.
In the case of a kinematic chain, this returns one tip link; in the case of a kinematic tree this returns the tip link for each branch of the tree.
Implements tesseract_kinematics::InverseKinematics.
|
finaloverridevirtual |
Get the inverse kinematics working frame.
This is the frame of reference in which all poses given to the calcInvKin function should be defined
Implements tesseract_kinematics::InverseKinematics.
|
finaloverridevirtual |
Number of joints in robot.
Implements tesseract_kinematics::InverseKinematics.
|
protected |
Link name of first link in the kinematic object.
|
protected |
Joint names for the kinematic object.
|
protected |
The UR Inverse kinematics parameters.
|
protected |
Name of this solver.
|
protected |
Link name of last kink in the kinematic object.