Tesseract
Motion Planning Environment
|
Robot With External Positioner Inverse kinematic implementation. More...
#include <rep_inv_kin.h>
Public Types | |
using | Ptr = std::shared_ptr< REPInvKin > |
using | ConstPtr = std::shared_ptr< const REPInvKin > |
using | UPtr = std::unique_ptr< REPInvKin > |
using | ConstUPtr = std::unique_ptr< const REPInvKin > |
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 | |
~REPInvKin () override=default | |
REPInvKin (const REPInvKin &other) | |
REPInvKin & | operator= (const REPInvKin &other) |
REPInvKin (REPInvKin &&)=default | |
REPInvKin & | operator= (REPInvKin &&)=default |
REPInvKin (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, ForwardKinematics::UPtr 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 (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, ForwardKinematics::UPtr 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... | |
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... | |
std::vector< std::string > | getJointNames () const override final |
Get list of joint names for kinematic object. More... | |
Eigen::Index | numJoints () const override final |
Number of joints in robot. 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... | |
Private Member Functions | |
void | init (const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, InverseKinematics::UPtr manipulator, double manipulator_reach, ForwardKinematics::UPtr positioner, const Eigen::MatrixX2d &poitioner_sample_range, const Eigen::VectorXd &positioner_sample_resolution, std::string solver_name=DEFAULT_REP_INV_KIN_SOLVER_NAME) |
IKSolutions | calcInvKinHelper (const tesseract_common::TransformMap &tip_link_poses, const Eigen::Ref< const Eigen::VectorXd > &seed) const |
calcFwdKin helper function More... | |
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 |
void | ikAt (IKSolutions &solutions, const tesseract_common::TransformMap &tip_link_poses, Eigen::VectorXd &positioner_pose, const Eigen::Ref< const Eigen::VectorXd > &seed) const |
Private Attributes | |
std::vector< std::string > | joint_names_ |
InverseKinematics::UPtr | manip_inv_kin_ |
ForwardKinematics::UPtr | positioner_fwd_kin_ |
std::string | working_frame_ |
std::string | manip_tip_link_ |
double | manip_reach_ { 0 } |
Eigen::Isometry3d | manip_base_to_positioner_base_ |
Eigen::Index | dof_ { -1 } |
std::vector< Eigen::VectorXd > | dof_range_ |
std::string | solver_name_ { DEFAULT_REP_INV_KIN_SOLVER_NAME } |
Name of this solver. More... | |
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.
using tesseract_kinematics::REPInvKin::ConstPtr = std::shared_ptr<const REPInvKin> |
using tesseract_kinematics::REPInvKin::ConstUPtr = std::unique_ptr<const REPInvKin> |
using tesseract_kinematics::REPInvKin::Ptr = std::shared_ptr<REPInvKin> |
using tesseract_kinematics::REPInvKin::UPtr = std::unique_ptr<REPInvKin> |
|
overridedefault |
tesseract_kinematics::REPInvKin::REPInvKin | ( | const REPInvKin & | other | ) |
|
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, | ||
ForwardKinematics::UPtr | 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 |
tesseract_kinematics::REPInvKin::REPInvKin | ( | const tesseract_scene_graph::SceneGraph & | scene_graph, |
const tesseract_scene_graph::SceneState & | scene_state, | ||
InverseKinematics::UPtr | manipulator, | ||
double | manipulator_reach, | ||
ForwardKinematics::UPtr | 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 |
|
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.
|
private |
calcFwdKin helper function
|
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.
|
private |
|
private |
|
private |
|
finaloverridevirtual |
Number of joints in robot.
Implements tesseract_kinematics::InverseKinematics.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
Name of this solver.
|
private |