Robot With External Positioner Inverse kinematic implementation. More...
#include <rep_inv_kin.h>
Public Types | |
using | ConstPtr = std::shared_ptr< const REPInvKin > |
using | ConstUPtr = std::unique_ptr< const REPInvKin > |
using | Ptr = std::shared_ptr< REPInvKin > |
using | UPtr = std::unique_ptr< REPInvKin > |
![]() | |
using | ConstPtr = std::shared_ptr< const InverseKinematics > |
using | ConstUPtr = std::unique_ptr< const InverseKinematics > |
using | Ptr = std::shared_ptr< InverseKinematics > |
using | UPtr = std::unique_ptr< InverseKinematics > |
Public Member Functions | |
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... | |
InverseKinematics::UPtr | clone () const override final |
Clone the forward kinematics object. More... | |
std::string | getBaseLinkName () const override final |
Get the robot base link name. More... | |
std::vector< std::string > | getJointNames () const override final |
Get list of joint names for kinematic object. More... | |
std::string | getSolverName () const override final |
Get the name of the solver. Recommend using the name of the class. More... | |
std::vector< std::string > | getTipLinkNames () const override final |
Get the names of the tip links of the kinematics group. More... | |
std::string | getWorkingFrame () const override final |
Get the inverse kinematics working frame. More... | |
Eigen::Index | numJoints () const override final |
Number of joints in robot. More... | |
REPInvKin & | operator= (const REPInvKin &other) |
REPInvKin & | operator= (REPInvKin &&)=default |
REPInvKin (const REPInvKin &other) | |
REPInvKin (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, std::unique_ptr< ForwardKinematics > positioner, const Eigen::MatrixX2d &positioner_sample_range, const Eigen::VectorXd &positioner_sample_resolution, std::string solver_name=DEFAULT_REP_INV_KIN_SOLVER_NAME) | |
Construct Inverse Kinematics for a robot on a positioner. More... | |
REPInvKin (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, std::unique_ptr< ForwardKinematics > positioner, const Eigen::VectorXd &positioner_sample_resolution, std::string solver_name=DEFAULT_REP_INV_KIN_SOLVER_NAME) | |
Construct Inverse Kinematics for a robot on a positioner. More... | |
REPInvKin (REPInvKin &&)=default | |
~REPInvKin () override=default | |
![]() | |
InverseKinematics ()=default | |
InverseKinematics (const InverseKinematics &)=default | |
InverseKinematics (InverseKinematics &&)=default | |
InverseKinematics & | operator= (const InverseKinematics &)=default |
InverseKinematics & | operator= (InverseKinematics &&)=default |
virtual | ~InverseKinematics () |
Private Member Functions | |
IKSolutions | calcInvKinHelper (const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const |
calcFwdKin helper function More... | |
void | ikAt (IKSolutions &solutions, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const |
void | init (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, std::unique_ptr< ForwardKinematics > positioner, const Eigen::MatrixX2d &poitioner_sample_range, const Eigen::VectorXd &positioner_sample_resolution, std::string solver_name=DEFAULT_REP_INV_KIN_SOLVER_NAME) |
void | nested_ik (IKSolutions &solutions, int loop_level, const std::vector< Eigen::VectorXd > &dof_range, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const |
Private Attributes | |
Eigen::Index | dof_ { -1 } |
std::vector< Eigen::VectorXd > | dof_range_ |
std::vector< std::string > | joint_names_ |
Eigen::Isometry3d | manip_base_to_positioner_base_ |
InverseKinematics::UPtr | manip_inv_kin_ |
double | manip_reach_ { 0 } |
std::string | manip_tip_link_ |
std::unique_ptr< ForwardKinematics > | positioner_fwd_kin_ |
std::string | solver_name_ { DEFAULT_REP_INV_KIN_SOLVER_NAME } |
Name of this solver. More... | |
std::string | working_frame_ |
Robot With External Positioner Inverse kinematic implementation.
In this kinematic arrangement the base link is the tip link of the external positioner and the tip link is the tip link of the manipulator. Therefore all provided target poses are expected to the tip link of the positioner.
Definition at line 49 of file rep_inv_kin.h.
using tesseract_kinematics::REPInvKin::ConstPtr = std::shared_ptr<const REPInvKin> |
Definition at line 57 of file rep_inv_kin.h.
using tesseract_kinematics::REPInvKin::ConstUPtr = std::unique_ptr<const REPInvKin> |
Definition at line 59 of file rep_inv_kin.h.
using tesseract_kinematics::REPInvKin::Ptr = std::shared_ptr<REPInvKin> |
Definition at line 56 of file rep_inv_kin.h.
using tesseract_kinematics::REPInvKin::UPtr = std::unique_ptr<REPInvKin> |
Definition at line 58 of file rep_inv_kin.h.
|
overridedefault |
tesseract_kinematics::REPInvKin::REPInvKin | ( | const REPInvKin & | other | ) |
Definition at line 158 of file rep_inv_kin.cpp.
|
default |
tesseract_kinematics::REPInvKin::REPInvKin | ( | const tesseract_scene_graph::SceneGraph & | scene_graph, |
const tesseract_scene_graph::SceneState & | scene_state, | ||
InverseKinematics::UPtr | manipulator, | ||
double | manipulator_reach, | ||
std::unique_ptr< ForwardKinematics > | positioner, | ||
const Eigen::VectorXd & | positioner_sample_resolution, | ||
std::string | solver_name = DEFAULT_REP_INV_KIN_SOLVER_NAME |
||
) |
Construct Inverse Kinematics for a robot on a positioner.
scene_graph | The Tesseract Scene Graph |
scene_state | The Tesseract Scene State |
manipulator | |
manipulator_reach | |
positioner | |
positioner_sample_resolution | |
solver_name | The name given to the solver. This is exposed so you may have same solver with different |
Definition at line 38 of file rep_inv_kin.cpp.
tesseract_kinematics::REPInvKin::REPInvKin | ( | const tesseract_scene_graph::SceneGraph & | scene_graph, |
const tesseract_scene_graph::SceneState & | scene_state, | ||
InverseKinematics::UPtr | manipulator, | ||
double | manipulator_reach, | ||
std::unique_ptr< ForwardKinematics > | positioner, | ||
const Eigen::MatrixX2d & | positioner_sample_range, | ||
const Eigen::VectorXd & | positioner_sample_resolution, | ||
std::string | solver_name = DEFAULT_REP_INV_KIN_SOLVER_NAME |
||
) |
Construct Inverse Kinematics for a robot on a positioner.
scene_graph | The Tesseract Scene Graph |
manipulator | |
manipulator_reach | |
positioner | |
positioner_sample_range | |
positioner_sample_resolution | |
solver_name | The name given to the solver. This is exposed so you may have same solver with different sampling resolutions |
Definition at line 73 of file rep_inv_kin.cpp.
|
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.
Definition at line 235 of file rep_inv_kin.cpp.
|
private |
calcFwdKin helper function
Definition at line 175 of file rep_inv_kin.cpp.
|
finaloverridevirtual |
Clone the forward kinematics object.
Implements tesseract_kinematics::InverseKinematics.
Definition at line 156 of file rep_inv_kin.cpp.
|
finaloverridevirtual |
Get the robot base link name.
Implements tesseract_kinematics::InverseKinematics.
Definition at line 249 of file rep_inv_kin.cpp.
|
finaloverridevirtual |
Get list of joint names for kinematic object.
Implements tesseract_kinematics::InverseKinematics.
Definition at line 245 of file rep_inv_kin.cpp.
|
finaloverridevirtual |
Get the name of the solver. Recommend using the name of the class.
Implements tesseract_kinematics::InverseKinematics.
Definition at line 255 of file rep_inv_kin.cpp.
|
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.
Definition at line 253 of file rep_inv_kin.cpp.
|
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.
Definition at line 251 of file rep_inv_kin.cpp.
|
private |
Definition at line 204 of file rep_inv_kin.cpp.
|
private |
Definition at line 92 of file rep_inv_kin.cpp.
|
private |
Definition at line 184 of file rep_inv_kin.cpp.
|
finaloverridevirtual |
Number of joints in robot.
Implements tesseract_kinematics::InverseKinematics.
Definition at line 247 of file rep_inv_kin.cpp.
Definition at line 160 of file rep_inv_kin.cpp.
|
private |
Definition at line 124 of file rep_inv_kin.h.
|
private |
Definition at line 125 of file rep_inv_kin.h.
|
private |
Definition at line 117 of file rep_inv_kin.h.
|
private |
Definition at line 123 of file rep_inv_kin.h.
|
private |
Definition at line 118 of file rep_inv_kin.h.
|
private |
Definition at line 122 of file rep_inv_kin.h.
|
private |
Definition at line 121 of file rep_inv_kin.h.
|
private |
Definition at line 119 of file rep_inv_kin.h.
|
private |
Name of this solver.
Definition at line 126 of file rep_inv_kin.h.
|
private |
Definition at line 120 of file rep_inv_kin.h.