Tesseract
Motion Planning Environment
|
IKFast Inverse Kinematics Implmentation. More...
#include <ikfast_inv_kin.h>
Public Types | |
using | Ptr = std::shared_ptr< IKFastInvKin > |
using | ConstPtr = std::shared_ptr< const IKFastInvKin > |
using | UPtr = std::unique_ptr< IKFastInvKin > |
using | ConstUPtr = std::unique_ptr< const IKFastInvKin > |
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 | |
~IKFastInvKin () override=default | |
IKFastInvKin (const IKFastInvKin &other) | |
IKFastInvKin & | operator= (const IKFastInvKin &other) |
IKFastInvKin (IKFastInvKin &&)=default | |
IKFastInvKin & | operator= (IKFastInvKin &&)=default |
IKFastInvKin (std::string base_link_name, std::string tip_link_name, std::vector< std::string > joint_names, std::vector< Eigen::Index > redundancy_capable_joints, std::string solver_name=IKFAST_INV_KIN_CHAIN_SOLVER_NAME, std::vector< std::vector< double > > free_joint_states={}) | |
Construct IKFast Inverse Kinematics. More... | |
IKSolutions | calcInvKin (const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const override |
Calculates joint solutions given a pose for each tip link. More... | |
Eigen::Index | numJoints () const override |
Number of joints in robot. More... | |
std::vector< std::string > | getJointNames () const override |
Get list of joint names for kinematic object. More... | |
std::string | getBaseLinkName () const override |
Get the robot base link name. More... | |
std::string | getWorkingFrame () const override |
Get the inverse kinematics working frame. More... | |
std::vector< std::string > | getTipLinkNames () const override |
Get the names of the tip links of the kinematics group. More... | |
std::string | getSolverName () const override |
Get the name of the solver. Recommend using the name of the class. More... | |
InverseKinematics::UPtr | clone () const override |
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... | |
Static Public Member Functions | |
static std::vector< std::vector< double > > | generateAllFreeJointStateCombinations (const std::vector< std::vector< double > > &free_joint_samples) |
Generates all possible combinations of joint states and stores it to the free_joint_states_ class member Example: Given 2 free joints, wanting to sample the first joint at 0, 1, and 2 and the second joint at 3 and 4 the input would be [[0, 1, 2][3,4]] and it would generate [[0,3][0,4][1,3][1,4][2,3][2,4]]. More... | |
Protected Attributes | |
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::vector< Eigen::Index > | redundancy_capable_joints_ |
std::string | solver_name_ { IKFAST_INV_KIN_CHAIN_SOLVER_NAME } |
Redundancy capable joints. More... | |
std::vector< std::vector< double > > | free_joint_states_ |
IKFast Inverse Kinematics Implmentation.
This along with the ikfast_inv_kin.hpp is to be used with a generated ikfast to create a tesseract implementation. Once you have created your ikfast solver of your robot all you need is to create header similar to what is shown below:
Header File: fanuc_p50ib_15_inv_kinematics.h
#include <Eigen/Geometry> #include <vector> #include <tesseract_kinematics/ikfast/ikfast_inv_kin.h>
namespace fanuc_p50ib_15_ikfast_wrapper { class FanucP50iBInvKinematics : public tesseract_kinematics::IKFastInvKin { public: FanucP50iBInvKinematics(const std::string base_link_name, const std::string tip_link_name, const std::vector<std::string> joint_names, const std::string name) };
Cpp File:
#include <tesseract_kinematics/ikfast/impl/ikfast_inv_kin.hpp> #include <fanuc_p50ib_15_ikfast_wrapper/impl/fanuc_p50ib_15_ikfast.hpp> #include <fanuc_p50ib_15_ikfast_wrapper/tesseract_fanuc_p50ib_kinematics.h>
namespace fanuc_p50ib_15_ikfast_wrapper { FanucP50iBInvKinematics::FanucP50iBInvKinematics(const std::string base_link_name, const std::string tip_link_name, const std::vector<std::string> joint_names const std::string name) : FanucP50iBInvKinematics(base_link_name, tip_link_name, joint_names, name, joint_limits) {} }
using tesseract_kinematics::IKFastInvKin::ConstPtr = std::shared_ptr<const IKFastInvKin> |
using tesseract_kinematics::IKFastInvKin::ConstUPtr = std::unique_ptr<const IKFastInvKin> |
using tesseract_kinematics::IKFastInvKin::Ptr = std::shared_ptr<IKFastInvKin> |
using tesseract_kinematics::IKFastInvKin::UPtr = std::unique_ptr<IKFastInvKin> |
|
overridedefault |
|
inline |
|
default |
|
inline |
Construct IKFast Inverse Kinematics.
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 |
|
inlineoverridevirtual |
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.
|
inlineoverridevirtual |
Clone the forward kinematics object.
Implements tesseract_kinematics::InverseKinematics.
|
inlinestatic |
Generates all possible combinations of joint states and stores it to the free_joint_states_ class member Example: Given 2 free joints, wanting to sample the first joint at 0, 1, and 2 and the second joint at 3 and 4 the input would be [[0, 1, 2][3,4]] and it would generate [[0,3][0,4][1,3][1,4][2,3][2,4]].
free_joint_samples | A vector of vectors in which the lower level vectors each represent all of a single joint's possible positions to be sampled |
|
inlineoverridevirtual |
Get the robot base link name.
Implements tesseract_kinematics::InverseKinematics.
|
inlineoverridevirtual |
Get list of joint names for kinematic object.
Implements tesseract_kinematics::InverseKinematics.
|
inlineoverridevirtual |
Get the name of the solver. Recommend using the name of the class.
Implements tesseract_kinematics::InverseKinematics.
|
inlineoverridevirtual |
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.
|
inlineoverridevirtual |
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.
|
inlineoverridevirtual |
Number of joints in robot.
Implements tesseract_kinematics::InverseKinematics.
|
inline |
|
default |
|
protected |
Link name of first link in the kinematic object.
|
protected |
|
protected |
Joint names for the kinematic object.
|
protected |
|
protected |
Redundancy capable joints.
Name of this solver
combinations of free joints to sample when computing IK Example: Given 3 free joints, a valid input would be [[0,0,0][0,0,1][-1,0,1][0,2,0]]
|
protected |
Link name of last kink in the kinematic object.