moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
kinematics_base.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Sachin Chitta, Dave Coleman */
36
39#include <rclcpp/logger.hpp>
41
42namespace kinematics
43{
44namespace
45{
46rclcpp::Logger getLogger()
47{
48 return moveit::getLogger("moveit.core.kinematics_base");
49}
50} // namespace
51
53const double KinematicsBase::DEFAULT_TIMEOUT = 1.0;
54
55static void noDeleter(const moveit::core::RobotModel* /*unused*/)
56{
57}
58
59void KinematicsBase::storeValues(const moveit::core::RobotModel& robot_model, const std::string& group_name,
60 const std::string& base_frame, const std::vector<std::string>& tip_frames,
61 double search_discretization)
62{
63 // The RobotModel is passed in as a borrowed reference from the JointModelGroup belonging to this RobotModel.
64 // Hence, it is ensured that the RobotModel will not be destroyed before the JMG and its associated
65 // kinematics solvers. To keep RobotModelPtr API (instead of storing the reference here only), but break
66 // the circular reference (RM => JMG => KS -> RM), here we create a new shared_ptr that doesn't delete the RM.
67 robot_model_ = moveit::core::RobotModelConstPtr(&robot_model, &noDeleter);
69 group_name_ = group_name;
70 base_frame_ = removeSlash(base_frame);
71 tip_frames_.clear();
72 for (const std::string& name : tip_frames)
73 tip_frames_.push_back(removeSlash(name));
74 setSearchDiscretization(search_discretization);
75}
76
77void KinematicsBase::setValues(const std::string& robot_description, const std::string& group_name,
78 const std::string& base_frame, const std::vector<std::string>& tip_frames,
79 double search_discretization)
80{
81 robot_model_.reset();
82 robot_description_ = robot_description;
83 group_name_ = group_name;
84 base_frame_ = removeSlash(base_frame);
85 tip_frames_.clear();
86 for (const std::string& name : tip_frames)
87 tip_frames_.push_back(removeSlash(name));
88 setSearchDiscretization(search_discretization);
89}
90
91bool KinematicsBase::initialize(const rclcpp::Node::SharedPtr& /*node*/,
92 const moveit::core::RobotModel& /*robot_model*/, const std::string& group_name,
93 const std::string& /*base_frame*/, const std::vector<std::string>& /*tip_frames*/,
94 double /*search_discretization*/)
95{
96 RCLCPP_ERROR(getLogger(),
97 "IK plugin for group '%s' relies on deprecated API. "
98 "Please implement initialize(rclcpp::Node::SharedPtr, RobotModel, ...).",
99 group_name.c_str());
100 return false;
101}
102
103bool KinematicsBase::setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices)
104{
105 for (unsigned int redundant_joint_index : redundant_joint_indices)
106 {
107 if (redundant_joint_index >= getJointNames().size())
108 {
109 return false;
110 }
111 }
112 redundant_joint_indices_ = redundant_joint_indices;
114
115 return true;
116}
117
118bool KinematicsBase::setRedundantJoints(const std::vector<std::string>& redundant_joint_names)
119{
120 const std::vector<std::string>& jnames = getJointNames();
121 std::vector<unsigned int> redundant_joint_indices;
122 for (const std::string& redundant_joint_name : redundant_joint_names)
123 {
124 for (std::size_t j = 0; j < jnames.size(); ++j)
125 {
126 if (jnames[j] == redundant_joint_name)
127 {
128 redundant_joint_indices.push_back(j);
129 break;
130 }
131 }
132 }
133 return redundant_joint_indices.size() == redundant_joint_names.size() ? setRedundantJoints(redundant_joint_indices) :
134 false;
135}
136
137std::string KinematicsBase::removeSlash(const std::string& str) const
138{
139 return (!str.empty() && str[0] == '/') ? removeSlash(str.substr(1)) : str;
140}
141
142bool KinematicsBase::supportsGroup(const moveit::core::JointModelGroup* jmg, std::string* error_text_out) const
143{
144 // Default implementation for legacy solvers:
145 if (!jmg->isChain())
146 {
147 if (error_text_out)
148 {
149 *error_text_out = "This plugin only supports joint groups which are chains";
150 }
151 return false;
152 }
153
154 return true;
155}
156
157KinematicsBase::KinematicsBase() : default_timeout_(DEFAULT_TIMEOUT)
158{
160}
161
163
164bool KinematicsBase::getPositionIK(const std::vector<geometry_msgs::msg::Pose>& ik_poses,
165 const std::vector<double>& ik_seed_state,
166 std::vector<std::vector<double> >& solutions, KinematicsResult& result,
167 const KinematicsQueryOptions& options) const
168{
169 std::vector<double> solution;
170 result.solution_percentage = 0.0;
171
172 if (std::find(supported_methods_.begin(), supported_methods_.end(), options.discretization_method) ==
173 supported_methods_.end())
174 {
176 return false;
177 }
178
179 if (ik_poses.size() != 1)
180 {
181 RCLCPP_ERROR(getLogger(), "This kinematic solver does not support getPositionIK for multiple tips");
183 return false;
184 }
185
186 if (ik_poses.empty())
187 {
188 RCLCPP_ERROR(getLogger(), "Input ik_poses array is empty");
190 return false;
191 }
192
193 moveit_msgs::msg::MoveItErrorCodes error_code;
194 if (getPositionIK(ik_poses[0], ik_seed_state, solution, error_code, options))
195 {
196 solutions.resize(1);
197 solutions[0] = solution;
199 result.solution_percentage = 1.0f;
200 }
201 else
202 {
204 return false;
205 }
206
207 return true;
208}
209} // end of namespace kinematics
void setSearchDiscretization(double sd)
Set the search discretization value for all the redundant joints.
void storeValues(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
virtual void setValues(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
Set the parameters for the solver, for use with non-chain IK solvers.
std::vector< unsigned int > redundant_joint_indices_
std::vector< DiscretizationMethod > supported_methods_
virtual bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
Initialization function for the kinematics, for use with kinematic chain IK solvers.
virtual bool getPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const =0
Given a desired pose of the end-effector, compute the joint angles to reach it.
virtual ~KinematicsBase()
Virtual destructor for the interface.
std::vector< std::string > tip_frames_
virtual bool supportsGroup(const moveit::core::JointModelGroup *jmg, std::string *error_text_out=nullptr) const
Check if this solver supports a given JointModelGroup.
static const double DEFAULT_TIMEOUT
moveit::core::RobotModelConstPtr robot_model_
static const double DEFAULT_SEARCH_DISCRETIZATION
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices)
Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK so...
virtual const std::vector< std::string > & getJointNames() const =0
Return all the joint names in the order they are used internally.
bool isChain() const
Check if this group is a linear chain.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition robot_model.h:76
API for forward and inverse kinematics.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
A set of options for the kinematics solver.