ur_inv_kin.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Provides forward and inverse kinematics for Univeral robot designs
4  * Author: Kelsey Hawkins (kphawkins@gatech.edu)
5  *
6  * Software License Agreement (BSD License)
7  *
8  * Copyright (c) 2013, Georgia Institute of Technology
9  * All rights reserved.
10  *
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions
13  * are met:
14  *
15  * * Redistributions of source code must retain the above copyright
16  * notice, this list of conditions and the following disclaimer.
17  * * Redistributions in binary form must reproduce the above
18  * copyright notice, this list of conditions and the following
19  * disclaimer in the documentation and/or other materials provided
20  * with the distribution.
21  * * Neither the name of the Georgia Institute of Technology nor the names of
22  * its contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
26  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
27  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
28  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
29  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
30  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
31  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
32  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
33  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  *********************************************************************/
38 #ifndef TESSERACT_KINEMATICS_UR_INV_KIN_H
39 #define TESSERACT_KINEMATICS_UR_INV_KIN_H
40 
43 
44 namespace tesseract_kinematics
45 {
46 static const std::string UR_INV_KIN_CHAIN_SOLVER_NAME = "URInvKin";
47 
49 class URInvKin : public tesseract_kinematics::InverseKinematics
50 {
51 public:
52  // LCOV_EXCL_START
53  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54  // LCOV_EXCL_STOP
55 
56  using Ptr = std::shared_ptr<URInvKin>;
57  using ConstPtr = std::shared_ptr<const URInvKin>;
58  using UPtr = std::unique_ptr<URInvKin>;
59  using ConstUPtr = std::unique_ptr<const URInvKin>;
60 
61  ~URInvKin() override = default;
62  URInvKin(const URInvKin& other);
63  URInvKin& operator=(const URInvKin& other);
64  URInvKin(URInvKin&&) = default;
65  URInvKin& operator=(URInvKin&&) = default;
66 
75  URInvKin(URParameters params,
76  std::string base_link_name,
77  std::string tip_link_name,
78  std::vector<std::string> joint_names,
79  std::string solver_name = UR_INV_KIN_CHAIN_SOLVER_NAME);
80 
82  const Eigen::Ref<const Eigen::VectorXd>& seed) const override final;
83 
84  Eigen::Index numJoints() const override final;
85  std::vector<std::string> getJointNames() const override final;
86  std::string getBaseLinkName() const override final;
87  std::string getWorkingFrame() const override final;
88  std::vector<std::string> getTipLinkNames() const override final;
89  std::string getSolverName() const override final;
90  InverseKinematics::UPtr clone() const override final;
91 
92 protected:
94  std::string base_link_name_;
95  std::string tip_link_name_;
96  std::vector<std::string> joint_names_;
98 };
99 } // namespace tesseract_kinematics
100 
101 #endif // TESSERACT_KINEMATICS_UR_INV_KIN_H
tesseract_kinematics::UR_INV_KIN_CHAIN_SOLVER_NAME
static const std::string UR_INV_KIN_CHAIN_SOLVER_NAME
Definition: ur_inv_kin.h:82
tesseract_kinematics::URInvKin::getJointNames
std::vector< std::string > getJointNames() const override final
Get list of joint names for kinematic object.
Definition: ur_inv_kin.cpp:288
types.h
Kinematics types.
tesseract_kinematics::URInvKin::URInvKin
URInvKin(const URInvKin &other)
Definition: ur_inv_kin.cpp:242
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_kinematics::URInvKin::getSolverName
std::string getSolverName() const override final
Get the name of the solver. Recommend using the name of the class.
Definition: ur_inv_kin.cpp:292
inverse_kinematics.h
Inverse kinematics functions.
tesseract_kinematics::URInvKin::operator=
URInvKin & operator=(const URInvKin &other)
Definition: ur_inv_kin.cpp:244
tesseract_kinematics::URInvKin::getBaseLinkName
std::string getBaseLinkName() const override final
Get the robot base link name.
Definition: ur_inv_kin.cpp:289
tesseract_kinematics::URInvKin::joint_names_
std::vector< std::string > joint_names_
Joint names for the kinematic object.
Definition: ur_inv_kin.h:132
tesseract_kinematics::InverseKinematics::UPtr
std::unique_ptr< InverseKinematics > UPtr
Definition: inverse_kinematics.h:52
tesseract_kinematics::URParameters
The Universal Robot kinematic parameters.
Definition: types.h:41
tesseract_kinematics::URInvKin::solver_name_
std::string solver_name_
Name of this solver.
Definition: ur_inv_kin.h:133
tesseract_kinematics::URInvKin::getWorkingFrame
std::string getWorkingFrame() const override final
Get the inverse kinematics working frame.
Definition: ur_inv_kin.cpp:290
tesseract_kinematics::URInvKin::clone
InverseKinematics::UPtr clone() const override final
Clone the forward kinematics object.
Definition: ur_inv_kin.cpp:240
tesseract_kinematics::URInvKin::numJoints
Eigen::Index numJoints() const override final
Number of joints in robot.
Definition: ur_inv_kin.cpp:287
tesseract_kinematics::URInvKin::getTipLinkNames
std::vector< std::string > getTipLinkNames() const override final
Get the names of the tip links of the kinematics group.
Definition: ur_inv_kin.cpp:291
tesseract_kinematics::URInvKin::ConstUPtr
std::unique_ptr< const URInvKin > ConstUPtr
Definition: ur_inv_kin.h:95
tesseract_kinematics::InverseKinematics
Inverse kinematics functions.
Definition: inverse_kinematics.h:43
tesseract_kinematics::URInvKin::ConstPtr
std::shared_ptr< const URInvKin > ConstPtr
Definition: ur_inv_kin.h:93
tesseract_kinematics::URInvKin::~URInvKin
~URInvKin() override=default
tesseract_kinematics::URInvKin::base_link_name_
std::string base_link_name_
Link name of first link in the kinematic object.
Definition: ur_inv_kin.h:130
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::URInvKin::tip_link_name_
std::string tip_link_name_
Link name of last kink in the kinematic object.
Definition: ur_inv_kin.h:131
tesseract_kinematics::URInvKin::calcInvKin
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.
Definition: ur_inv_kin.cpp:255
tesseract_kinematics::IKSolutions
std::vector< Eigen::VectorXd > IKSolutions
The inverse kinematics solutions container.
Definition: types.h:38
tesseract_kinematics::URInvKin::UPtr
std::unique_ptr< URInvKin > UPtr
Definition: ur_inv_kin.h:94
tesseract_kinematics::URInvKin::Ptr
std::shared_ptr< URInvKin > Ptr
Definition: ur_inv_kin.h:92
tesseract_kinematics::URInvKin::params_
URParameters params_
The UR Inverse kinematics parameters.
Definition: ur_inv_kin.h:129


tesseract_kinematics
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:14