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 {
109  class URKinematicsPlugin : public kinematics::KinematicsBase
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 moveit::core::RobotModel& robot_model,
161  const std::string& group_name,
162  const std::string& base_frame,
163  const std::vector<std::string>& tip_frames,
164  double search_discretization);
165 
166 
170  const std::vector<std::string>& getJointNames() const;
171 
175  const std::vector<std::string>& getLinkNames() const;
176 
177  protected:
178 
194  bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
195  const std::vector<double> &ik_seed_state,
196  double timeout,
197  std::vector<double> &solution,
198  const IKCallbackFn &solution_callback,
199  moveit_msgs::MoveItErrorCodes &error_code,
200  const std::vector<double> &consistency_limits,
202 
203  virtual bool setRedundantJoints(const std::vector<unsigned int> &redundant_joint_indices);
204 
205  private:
206 
207  bool timedOut(const ros::WallTime &start_time, double duration) const;
208 
209 
217  bool checkConsistency(const KDL::JntArray& seed_state,
218  const std::vector<double> &consistency_limit,
219  const KDL::JntArray& solution) const;
220 
221  int getJointIndex(const std::string &name) const;
222 
223  int getKDLSegmentIndex(const std::string &name) const;
224 
225  void getRandomConfiguration(KDL::JntArray &jnt_array, bool lock_redundancy) const;
226 
233  void getRandomConfiguration(const KDL::JntArray& seed_state,
234  const std::vector<double> &consistency_limits,
235  KDL::JntArray &jnt_array,
236  bool lock_redundancy) const;
237 
238  bool isRedundantJoint(unsigned int index) const;
239 
240  bool active_;
242  moveit_msgs::KinematicSolverInfo ik_chain_info_;
244  moveit_msgs::KinematicSolverInfo fk_chain_info_;
246  KDL::Chain kdl_chain_;
247 
248  unsigned int dimension_;
250  KDL::JntArray joint_min_, joint_max_;
253 
254  robot_state::RobotStatePtr state_, state_2_;
255 
257  std::vector<unsigned int> redundant_joints_map_index_;
258 
259  // Storage required for when the set of redundant joints is reset
260  bool position_ik_; //whether this solver is only being used for position ik
261  const robot_model::JointModelGroup* joint_model_group_;
262  double max_solver_iterations_;
263  double epsilon_;
264  std::vector<kdl_kinematics_plugin::JointMimic> mimic_joints_;
265 
266  std::vector<double> ik_weights_;
267  std::vector<std::string> ur_joint_names_;
268  std::vector<std::string> ur_link_names_;
270  std::string arm_prefix_;
271 
272  // kinematic chains representing the chain from the group base link to the
273  // UR base link, and the UR tip link to the group tip link
274  KDL::Chain kdl_base_chain_;
275  KDL::Chain kdl_tip_chain_;
276 
277  };
278 }
279 
280 #endif
robot_model.h
random_numbers.h
ur_kinematics::URKinematicsPlugin::getPositionIK
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
Definition: ur_moveit_plugin.cpp:502
ur_kinematics::URKinematicsPlugin::num_possible_redundant_joints_
int num_possible_redundant_joints_
Definition: ur_moveit_plugin.h:384
duration
std::chrono::system_clock::duration duration
ur_kinematics::URKinematicsPlugin::getLinkNames
const std::vector< std::string > & getLinkNames() const
Return all the link names in the order they are represented internally.
Definition: ur_moveit_plugin.cpp:874
ur_kinematics::URKinematicsPlugin::epsilon_
double epsilon_
Definition: ur_moveit_plugin.h:391
ur_kinematics::URKinematicsPlugin::setRedundantJoints
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices)
Definition: ur_moveit_plugin.cpp:432
ros.h
ur_kinematics::URKinematicsPlugin::getKDLSegmentIndex
int getKDLSegmentIndex(const std::string &name) const
Definition: ur_moveit_plugin.cpp:485
ur_kinematics::URKinematicsPlugin::ur_joint_inds_start_
int ur_joint_inds_start_
Definition: ur_moveit_plugin.h:397
ur_kinematics::URKinematicsPlugin::kdl_chain_
KDL::Chain kdl_chain_
Definition: ur_moveit_plugin.h:374
moveit::core::RobotModel
ur_kinematics::URKinematicsPlugin::isRedundantJoint
bool isRedundantJoint(unsigned int index) const
Definition: ur_moveit_plugin.cpp:175
ur_kinematics::URKinematicsPlugin::state_2_
robot_state::RobotStatePtr state_2_
Definition: ur_moveit_plugin.h:382
ur_kinematics::URKinematicsPlugin::timedOut
bool timedOut(const ros::WallTime &start_time, double duration) const
Definition: ur_moveit_plugin.cpp:497
ur_kinematics::URKinematicsPlugin::position_ik_
bool position_ik_
Definition: ur_moveit_plugin.h:388
robot_state.h
ur_kinematics::URKinematicsPlugin::joint_model_group_
const robot_model::JointModelGroup * joint_model_group_
Definition: ur_moveit_plugin.h:389
kinematics::KinematicsBase::IKCallbackFn
boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
ur_kinematics::URKinematicsPlugin::checkConsistency
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.
Definition: ur_moveit_plugin.cpp:220
ur_kinematics::URKinematicsPlugin::redundant_joints_map_index_
std::vector< unsigned int > redundant_joints_map_index_
Definition: ur_moveit_plugin.h:385
kinematics::KinematicsBase
ur_kinematics::URKinematicsPlugin::searchPositionIK
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
Definition: ur_moveit_plugin.cpp:521
ur_kinematics::URKinematicsPlugin::kdl_tip_chain_
KDL::Chain kdl_tip_chain_
Definition: ur_moveit_plugin.h:403
ur_kinematics::URKinematicsPlugin::random_number_generator_
random_numbers::RandomNumberGenerator random_number_generator_
Definition: ur_moveit_plugin.h:380
ur_kinematics::URKinematicsPlugin::ur_joint_names_
std::vector< std::string > ur_joint_names_
Definition: ur_moveit_plugin.h:395
ur_kinematics::URKinematicsPlugin::max_solver_iterations_
double max_solver_iterations_
Definition: ur_moveit_plugin.h:390
ros::WallTime
ur_kinematics
Definition: ur_kin.h:58
ur_kinematics::URKinematicsPlugin::fk_chain_info_
moveit_msgs::KinematicSolverInfo fk_chain_info_
Definition: ur_moveit_plugin.h:372
ur_kinematics::URKinematicsPlugin::getJointNames
const std::vector< std::string > & getJointNames() const
Return all the joint names in the order they are used internally.
Definition: ur_moveit_plugin.cpp:869
random_numbers::RandomNumberGenerator
ur_kinematics::URKinematicsPlugin::active_
bool active_
Definition: ur_moveit_plugin.h:368
ur_kinematics::URKinematicsPlugin::URKinematicsPlugin
URKinematicsPlugin()
Default constructor.
Definition: ur_moveit_plugin.cpp:159
ur_kinematics::URKinematicsPlugin::ik_chain_info_
moveit_msgs::KinematicSolverInfo ik_chain_info_
Definition: ur_moveit_plugin.h:370
joint_mimic.hpp
ur_kinematics::URKinematicsPlugin::getPositionFK
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
Definition: ur_moveit_plugin.cpp:823
ur_kinematics::URKinematicsPlugin::getRandomConfiguration
void getRandomConfiguration(KDL::JntArray &jnt_array, bool lock_redundancy) const
Definition: ur_moveit_plugin.cpp:161
kinematics::KinematicsQueryOptions
ur_kinematics::URKinematicsPlugin::joint_max_
KDL::JntArray joint_max_
Definition: ur_moveit_plugin.h:378
ur_kinematics::URKinematicsPlugin::state_
robot_state::RobotStatePtr state_
Definition: ur_moveit_plugin.h:382
kinematics_base.h
ur_kinematics::URKinematicsPlugin::ik_weights_
std::vector< double > ik_weights_
Definition: ur_moveit_plugin.h:394
ur_kinematics::URKinematicsPlugin::getJointIndex
int getJointIndex(const std::string &name) const
Definition: ur_moveit_plugin.cpp:476
ur_kinematics::URKinematicsPlugin::joint_min_
KDL::JntArray joint_min_
Definition: ur_moveit_plugin.h:378
ur_kinematics::URKinematicsPlugin::kdl_base_chain_
KDL::Chain kdl_base_chain_
Definition: ur_moveit_plugin.h:402
ur_kinematics::URKinematicsPlugin::mimic_joints_
std::vector< kdl_kinematics_plugin::JointMimic > mimic_joints_
Definition: ur_moveit_plugin.h:392
ur_kinematics::URKinematicsPlugin::initialize
virtual bool initialize(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)
Definition: ur_moveit_plugin.cpp:230
ur_kinematics::URKinematicsPlugin::dimension_
unsigned int dimension_
Definition: ur_moveit_plugin.h:376
ur_kinematics::URKinematicsPlugin::arm_prefix_
std::string arm_prefix_
Definition: ur_moveit_plugin.h:398
ur_kinematics::URKinematicsPlugin::ur_link_names_
std::vector< std::string > ur_link_names_
Definition: ur_moveit_plugin.h:396


ur_kinematics
Author(s): Kelsey Hawkins
autogenerated on Tue May 13 2025 02:43:05