ur_moveit_plugin.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, Georgia Tech
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 Georgia Tech 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: Kelsey Hawkins */
36 
37 /* Based on orignal source from Willow Garage. License copied below */
38 
39 /*********************************************************************
40 * Software License Agreement (BSD License)
41 *
42 * Copyright (c) 2012, Willow Garage, Inc.
43 * All rights reserved.
44 *
45 * Redistribution and use in source and binary forms, with or without
46 * modification, are permitted provided that the following conditions
47 * are met:
48 *
49 * * Redistributions of source code must retain the above copyright
50 * notice, this list of conditions and the following disclaimer.
51 * * Redistributions in binary form must reproduce the above
52 * copyright notice, this list of conditions and the following
53 * disclaimer in the documentation and/or other materials provided
54 * with the distribution.
55 * * Neither the name of Willow Garage nor the names of its
56 * contributors may be used to endorse or promote products derived
57 * from this software without specific prior written permission.
58 *
59 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
60 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
61 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
62 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
63 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
64 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
65 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
66 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
67 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
68 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
69 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
70 * POSSIBILITY OF SUCH DAMAGE.
71 *********************************************************************/
72 
73 /* Author: Sachin Chitta, David Lu!!, Ugo Cupcic */
74 
75 #ifndef UR_KINEMATICS_PLUGIN_
76 #define UR_KINEMATICS_PLUGIN_
77 
78 // ROS
79 #include <ros/ros.h>
81 
82 // System
83 #include <boost/shared_ptr.hpp>
84 
85 // ROS msgs
86 #include <geometry_msgs/PoseStamped.h>
87 #include <moveit_msgs/GetPositionFK.h>
88 #include <moveit_msgs/GetPositionIK.h>
89 #include <moveit_msgs/KinematicSolverInfo.h>
90 #include <moveit_msgs/MoveItErrorCodes.h>
91 
92 // KDL
93 #include <kdl/jntarray.hpp>
94 #include <kdl/chainiksolvervel_pinv.hpp>
95 #include <kdl/chainiksolverpos_nr_jl.hpp>
96 #include <kdl/chainfksolverpos_recursive.hpp>
98 
99 // MoveIt!
103 
104 namespace ur_kinematics
105 {
110  {
111  public:
112 
117 
118  virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose,
119  const std::vector<double> &ik_seed_state,
120  std::vector<double> &solution,
121  moveit_msgs::MoveItErrorCodes &error_code,
123 
124  virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
125  const std::vector<double> &ik_seed_state,
126  double timeout,
127  std::vector<double> &solution,
128  moveit_msgs::MoveItErrorCodes &error_code,
130 
131  virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
132  const std::vector<double> &ik_seed_state,
133  double timeout,
134  const std::vector<double> &consistency_limits,
135  std::vector<double> &solution,
136  moveit_msgs::MoveItErrorCodes &error_code,
138 
139  virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
140  const std::vector<double> &ik_seed_state,
141  double timeout,
142  std::vector<double> &solution,
143  const IKCallbackFn &solution_callback,
144  moveit_msgs::MoveItErrorCodes &error_code,
146 
147  virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
148  const std::vector<double> &ik_seed_state,
149  double timeout,
150  const std::vector<double> &consistency_limits,
151  std::vector<double> &solution,
152  const IKCallbackFn &solution_callback,
153  moveit_msgs::MoveItErrorCodes &error_code,
155 
156  virtual bool getPositionFK(const std::vector<std::string> &link_names,
157  const std::vector<double> &joint_angles,
158  std::vector<geometry_msgs::Pose> &poses) const;
159 
160  virtual bool initialize(const std::string &robot_description,
161  const std::string &group_name,
162  const std::string &base_name,
163  const std::string &tip_name,
164  double search_discretization);
165 
169  const std::vector<std::string>& getJointNames() const;
170 
174  const std::vector<std::string>& getLinkNames() const;
175 
176  protected:
177 
193  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
194  const std::vector<double> &ik_seed_state,
195  double timeout,
196  std::vector<double> &solution,
197  const IKCallbackFn &solution_callback,
198  moveit_msgs::MoveItErrorCodes &error_code,
199  const std::vector<double> &consistency_limits,
201 
202  virtual bool setRedundantJoints(const std::vector<unsigned int> &redundant_joint_indices);
203 
204  private:
205 
206  bool timedOut(const ros::WallTime &start_time, double duration) const;
207 
208 
216  bool checkConsistency(const KDL::JntArray& seed_state,
217  const std::vector<double> &consistency_limit,
218  const KDL::JntArray& solution) const;
219 
220  int getJointIndex(const std::string &name) const;
221 
222  int getKDLSegmentIndex(const std::string &name) const;
223 
224  void getRandomConfiguration(KDL::JntArray &jnt_array, bool lock_redundancy) const;
225 
232  void getRandomConfiguration(const KDL::JntArray& seed_state,
233  const std::vector<double> &consistency_limits,
234  KDL::JntArray &jnt_array,
235  bool lock_redundancy) const;
236 
237  bool isRedundantJoint(unsigned int index) const;
238 
239  bool active_;
241  moveit_msgs::KinematicSolverInfo ik_chain_info_;
243  moveit_msgs::KinematicSolverInfo fk_chain_info_;
246 
247  unsigned int dimension_;
252 
253  robot_model::RobotModelPtr robot_model_;
254 
255  robot_state::RobotStatePtr state_, state_2_;
256 
258  std::vector<unsigned int> redundant_joints_map_index_;
259 
260  // Storage required for when the set of redundant joints is reset
261  bool position_ik_; //whether this solver is only being used for position ik
262  robot_model::JointModelGroup* joint_model_group_;
264  double epsilon_;
265  std::vector<kdl_kinematics_plugin::JointMimic> mimic_joints_;
266 
267  std::vector<double> ik_weights_;
268  std::vector<std::string> ur_joint_names_;
269  std::vector<std::string> ur_link_names_;
271  std::string arm_prefix_;
272 
273  // kinematic chains representing the chain from the group base link to the
274  // UR base link, and the UR tip link to the group tip link
277 
278  };
279 }
280 
281 #endif
bool isRedundantJoint(unsigned int index) const
robot_state::RobotStatePtr state_2_
int getKDLSegmentIndex(const std::string &name) const
const std::vector< std::string > & getJointNames() const
Return all the joint names in the order they are used internally.
std::vector< std::string > ur_joint_names_
virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
robot_model::RobotModelPtr robot_model_
robot_model::JointModelGroup * joint_model_group_
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices)
bool checkConsistency(const KDL::JntArray &seed_state, const std::vector< double > &consistency_limit, const KDL::JntArray &solution) const
Check whether the solution lies within the consistency limit of the seed state.
std::vector< unsigned int > redundant_joints_map_index_
bool timedOut(const ros::WallTime &start_time, double duration) const
Specific implementation of kinematics using KDL. This version can be used with any robot...
unsigned int index
random_numbers::RandomNumberGenerator random_number_generator_
const std::vector< std::string > & getLinkNames() const
Return all the link names in the order they are represented internally.
options
std::vector< kdl_kinematics_plugin::JointMimic > mimic_joints_
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
moveit_msgs::KinematicSolverInfo fk_chain_info_
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
URKinematicsPlugin()
Default constructor.
std::vector< std::string > ur_link_names_
void getRandomConfiguration(KDL::JntArray &jnt_array, bool lock_redundancy) const
robot_state::RobotStatePtr state_
virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
moveit_msgs::KinematicSolverInfo ik_chain_info_
int getJointIndex(const std::string &name) const
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization)


ur_kinematics
Author(s): Kelsey Hawkins
autogenerated on Sun Nov 24 2019 03:36:27