26#ifndef TESSERACT_KINEMATICS_OPW_INV_KIN_H
27#define TESSERACT_KINEMATICS_OPW_INV_KIN_H
31#include <opw_kinematics/opw_parameters.h>
46 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
49 using Ptr = std::shared_ptr<OPWInvKin>;
50 using ConstPtr = std::shared_ptr<const OPWInvKin>;
51 using UPtr = std::unique_ptr<OPWInvKin>;
68 OPWInvKin(opw_kinematics::Parameters<double> params,
75 const Eigen::Ref<const Eigen::VectorXd>&
seed)
const override final;
77 Eigen::Index
numJoints() const override final;
86 opw_kinematics::Parameters<
double>
params_;
#define vector(a, b, c)
Definition: FloatMath.inl:3227
Inverse kinematics functions.
Definition: inverse_kinematics.h:47
OPW Inverse Kinematics Implementation.
Definition: opw_inv_kin.h:43
opw_kinematics::Parameters< double > params_
The opw kinematics parameters.
Definition: opw_inv_kin.h:86
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.
Definition: opw_inv_kin.cpp:103
std::shared_ptr< const OPWInvKin > ConstPtr
Definition: opw_inv_kin.h:50
~OPWInvKin() override=default
std::string getBaseLinkName() const override final
Get the robot base link name.
Definition: opw_inv_kin.cpp:102
std::unique_ptr< const OPWInvKin > ConstUPtr
Definition: opw_inv_kin.h:52
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
Definition: opw_inv_kin.cpp:101
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.
Definition: opw_inv_kin.cpp:70
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
Definition: opw_inv_kin.cpp:104
std::string solver_name_
Name of this solver.
Definition: opw_inv_kin.h:90
OPWInvKin & operator=(const OPWInvKin &other)
Definition: opw_inv_kin.cpp:60
std::shared_ptr< OPWInvKin > Ptr
Definition: opw_inv_kin.h:49
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
Definition: opw_inv_kin.cpp:105
std::string base_link_name_
Link name of first link in the kinematic object.
Definition: opw_inv_kin.h:87
OPWInvKin(OPWInvKin &&)=default
std::unique_ptr< OPWInvKin > UPtr
Definition: opw_inv_kin.h:51
std::vector< std::string > joint_names_
Joint names for the kinematic object.
Definition: opw_inv_kin.h:89
std::string tip_link_name_
Link name of last kink in the kinematic object.
Definition: opw_inv_kin.h:88
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
Definition: opw_inv_kin.cpp:56
Eigen::Index numJoints() const override final
Number of joints in robot.
Definition: opw_inv_kin.cpp:99
OPWInvKin & operator=(OPWInvKin &&)=default
Eigen::VectorXd seed
Definition: ikfast_kinematics_7dof_unit.cpp:48
std::string base_link_name
Definition: ikfast_kinematics_7dof_unit.cpp:52
std::string tip_link_name
Definition: ikfast_kinematics_7dof_unit.cpp:53
Inverse kinematics functions.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Definition: create_convex_hull.cpp:36
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
Definition: types.h:66
Definition: forward_kinematics.h:44
static const std::string OPW_INV_KIN_CHAIN_SOLVER_NAME
Definition: opw_inv_kin.h:39
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:41
joint_state joint_names
Definition: tesseract_common_serialization_unit.cpp:75