forked from moveit/moveit2
/
pr2_arm_kinematics_plugin.h
254 lines (214 loc) · 10.9 KB
/
pr2_arm_kinematics_plugin.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Sachin Chitta */
#pragma once
#include <kdl/config.h>
#include <kdl/frames.hpp>
#include <kdl/jntarray.hpp>
#include <kdl/tree.hpp>
#include <kdl_parser/kdl_parser.hpp>
#include <moveit/macros/class_forward.h>
#include <moveit_msgs/srv/get_position_fk.hpp>
#include <moveit_msgs/srv/get_position_ik.hpp>
#include <moveit_msgs/msg/kinematic_solver_info.hpp>
#include <moveit_msgs/msg/move_it_error_codes.hpp>
#include <kdl/chainfksolverpos_recursive.hpp>
#include <urdf/model.h>
#include <moveit/kinematics_base/kinematics_base.h>
#include <memory>
#include "pr2_arm_ik.h"
namespace pr2_arm_kinematics
{
static const int NO_IK_SOLUTION = -1;
static const int TIMED_OUT = -2;
MOVEIT_CLASS_FORWARD(PR2ArmIKSolver);
// minimal stuff necessary
class PR2ArmIKSolver : public KDL::ChainIkSolverPos
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
/** @class
* @brief ROS/KDL based interface for the inverse kinematics of the PR2 arm
* @author Sachin Chitta <sachinc@willowgarage.com>
*
* This class provides a KDL based interface to the inverse kinematics of the PR2 arm.
* It inherits from the KDL::ChainIkSolverPos class but also exposes additional functionality
* to return multiple solutions from an inverse kinematics computation.
*/
PR2ArmIKSolver(const urdf::ModelInterface& robot_model, const std::string& root_frame_name,
const std::string& tip_frame_name, double search_discretization_angle, int free_angle);
~PR2ArmIKSolver() override{};
void updateInternalDataStructures() override;
/**
* @brief The PR2 inverse kinematics solver
*/
PR2ArmIK pr2_arm_ik_;
/**
* @brief Indicates whether the solver has been successfully initialized
*/
bool active_;
int CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out) override;
int cartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out, double timeout);
void getSolverInfo(moveit_msgs::msg::KinematicSolverInfo& response)
{
pr2_arm_ik_.getSolverInfo(response);
}
private:
bool getCount(int& count, int max_count, int min_count);
double search_discretization_angle_;
int free_angle_;
std::string root_frame_name_;
};
Eigen::Isometry3f kdlToEigenMatrix(const KDL::Frame& p);
double computeEuclideanDistance(const std::vector<double>& array_1, const KDL::JntArray& array_2);
void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::msg::KinematicSolverInfo& chain_info);
MOVEIT_CLASS_FORWARD(PR2ArmKinematicsPlugin);
class PR2ArmKinematicsPlugin : public kinematics::KinematicsBase
{
public:
/** @class
* @brief Plugin-able interface to the PR2 arm kinematics
*/
PR2ArmKinematicsPlugin();
/**
* @brief Specifies if the node is active or not
* @return True if the node is active, false otherwise.
*/
bool isActive();
/**
* @brief Given a desired pose of the end-effector, compute the joint angles to reach it
* @param ik_link_name - the name of the link for which IK is being computed
* @param ik_pose the desired pose of the link
* @param ik_seed_state an initial guess solution for the inverse kinematics
* @return True if a valid solution was found, false otherwise
*/
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 override;
/**
* @brief Given a desired pose of the end-effector, search for the joint angles required to reach it.
* This particular method is intended for "searching" for a solutions by stepping through the redundancy
* (or other numerical routines).
* @param ik_pose the desired pose of the link
* @param ik_seed_state an initial guess solution for the inverse kinematics
* @return True if a valid solution was found, false otherwise
*/
bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const override;
/**
* @brief Given a desired pose of the end-effector, search for the joint angles required to reach it.
* This particular method is intended for "searching" for a solutions by stepping through the redundancy
* (or other numerical routines).
* @param ik_pose the desired pose of the link
* @param ik_seed_state an initial guess solution for the inverse kinematics
* @param consistency_limit the distance that the redundancy can be from the current position
* @return True if a valid solution was found, false otherwise
*/
bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
moveit_msgs::msg::MoveItErrorCodes& error_code,
const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const override;
/**
* @brief Given a desired pose of the end-effector, search for the joint angles required to reach it.
* This particular method is intended for "searching" for a solutions by stepping through the redundancy
* (or other numerical routines).
* @param ik_pose the desired pose of the link
* @param ik_seed_state an initial guess solution for the inverse kinematics
* @return True if a valid solution was found, false otherwise
*/
bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
std::vector<double>& solution, const IKCallbackFn& solution_callback,
moveit_msgs::msg::MoveItErrorCodes& error_code,
const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const override;
/**
* @brief Given a desired pose of the end-effector, search for the joint angles required to reach it.
* This particular method is intended for "searching" for a solutions by stepping through the redundancy
* (or other numerical routines). The consistency_limit specifies that only certain redundancy positions
* around those specified in the seed state are admissible and need to be searched.
* @param ik_pose the desired pose of the link
* @param ik_seed_state an initial guess solution for the inverse kinematics
* @param consistency_limit the distance that the redundancy can be from the current position
* @return True if a valid solution was found, false otherwise
*/
bool searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const override;
/**
* @brief Given a set of joint angles and a set of links, compute their pose
* @param request - the request contains the joint angles, set of links for which poses are to be computed and a
* timeout
* @param response - the response contains stamped pose information for all the requested links
* @return True if a valid solution was found, false otherwise
*/
bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
std::vector<geometry_msgs::msg::Pose>& poses) const override;
/**
* @brief Initialization function for the kinematics
* @return True if initialization was successful, false otherwise
*/
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) override;
/**
* @brief Return all the joint names in the order they are used internally
*/
const std::vector<std::string>& getJointNames() const override;
/**
* @brief Return all the link names in the order they are represented internally
*/
const std::vector<std::string>& getLinkNames() const override;
protected:
bool active_;
int free_angle_;
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_;
std::string root_name_;
int dimension_;
std::shared_ptr<KDL::ChainFkSolverPos_recursive> jnt_to_pose_solver_;
KDL::Chain kdl_chain_;
moveit_msgs::msg::KinematicSolverInfo ik_solver_info_, fk_solver_info_;
mutable IKCallbackFn desiredPoseCallback_;
mutable IKCallbackFn solutionCallback_;
void desiredPoseCallback(const KDL::JntArray& jnt_array, const KDL::Frame& ik_pose,
moveit_msgs::msg::MoveItErrorCodes& error_code) const;
void jointSolutionCallback(const KDL::JntArray& jnt_array, const KDL::Frame& ik_pose,
moveit_msgs::msg::MoveItErrorCodes& error_code) const;
};
} // namespace pr2_arm_kinematics