kdl_kinematics_plugin.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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, David Lu!!, Ugo Cupcic */
36 
37 #pragma once
38 
39 // ROS
40 #include <ros/ros.h>
42 
43 // ROS msgs
44 #include <geometry_msgs/PoseStamped.h>
45 #include <moveit_msgs/GetPositionFK.h>
46 #include <moveit_msgs/GetPositionIK.h>
47 #include <moveit_msgs/KinematicSolverInfo.h>
48 #include <moveit_msgs/MoveItErrorCodes.h>
49 
50 // KDL
51 #include <kdl/config.h>
52 #include <kdl/chainfksolver.hpp>
53 #include <kdl/chainiksolver.hpp>
54 
55 // MoveIt
60 
61 namespace KDL
62 {
63 class ChainIkSolverVelMimicSVD;
64 }
65 
66 namespace kdl_kinematics_plugin
67 {
73 {
74 public:
79 
80  bool
81  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
82  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
84 
85  bool searchPositionIK(
86  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
87  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
89 
90  bool searchPositionIK(
91  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
92  const std::vector<double>& consistency_limits, std::vector<double>& solution,
93  moveit_msgs::MoveItErrorCodes& error_code,
95 
96  bool searchPositionIK(
97  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
98  std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
100 
101  bool searchPositionIK(
102  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
103  const std::vector<double>& consistency_limits, std::vector<double>& solution,
104  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
106 
107  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
108  std::vector<geometry_msgs::Pose>& poses) const override;
109 
110  bool initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
111  const std::string& base_frame, const std::vector<std::string>& tip_frames,
112  double search_discretization) override;
113 
117  const std::vector<std::string>& getJointNames() const override;
118 
122  const std::vector<std::string>& getLinkNames() const override;
123 
124 protected:
125  typedef Eigen::Matrix<double, 6, 1> Twist;
126 
128  // NOLINTNEXTLINE(readability-identifier-naming)
129  int CartToJnt(KDL::ChainIkSolverVelMimicSVD& ik_solver, const KDL::JntArray& q_init, const KDL::Frame& p_in,
130  KDL::JntArray& q_out, const unsigned int max_iter, const Eigen::VectorXd& joint_weights,
131  const Twist& cartesian_weights) const;
132 
133 private:
134  void getJointWeights();
135  bool timedOut(const ros::WallTime& start_time, double duration) const;
136 
143  bool checkConsistency(const Eigen::VectorXd& seed_state, const std::vector<double>& consistency_limits,
144  const Eigen::VectorXd& solution) const;
145 
146  void getRandomConfiguration(Eigen::VectorXd& jnt_array) const;
147 
153  void getRandomConfiguration(const Eigen::VectorXd& seed_state, const std::vector<double>& consistency_limits,
154  Eigen::VectorXd& jnt_array) const;
155 
157  void clipToJointLimits(const KDL::JntArray& q, KDL::JntArray& q_delta, Eigen::ArrayXd& weighting) const;
158 
160 
161  unsigned int dimension_;
162  moveit_msgs::KinematicSolverInfo solver_info_;
163 
165  moveit::core::RobotStatePtr state_;
166  KDL::Chain kdl_chain_;
167  std::unique_ptr<KDL::ChainFkSolverPos> fk_solver_;
168  std::vector<JointMimic> mimic_joints_;
169  std::vector<double> joint_weights_;
170  Eigen::VectorXd joint_min_, joint_max_;
171 
173  double epsilon_;
180 };
181 } // namespace kdl_kinematics_plugin
robot_model.h
random_numbers.h
kdl_kinematics_plugin::KDLKinematicsPlugin::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: kdl_kinematics_plugin.h:164
duration
std::chrono::system_clock::duration duration
kdl_kinematics_plugin::KDLKinematicsPlugin::initialize
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) override
Definition: kdl_kinematics_plugin.cpp:169
ros.h
moveit::core::RobotModel
kdl_kinematics_plugin::KDLKinematicsPlugin::max_solver_iterations_
int max_solver_iterations_
Definition: kdl_kinematics_plugin.h:172
kdl_kinematics_plugin::KDLKinematicsPlugin::state_
moveit::core::RobotStatePtr state_
Definition: kdl_kinematics_plugin.h:165
kdl_kinematics_plugin::KDLKinematicsPlugin::searchPositionIK
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 override
Definition: kdl_kinematics_plugin.cpp:317
kdl_kinematics_plugin::KDLKinematicsPlugin::clipToJointLimits
void clipToJointLimits(const KDL::JntArray &q, KDL::JntArray &q_delta, Eigen::ArrayXd &weighting) const
clip q_delta such that joint limits will not be violated
Definition: kdl_kinematics_plugin.cpp:535
robot_state.h
kdl_kinematics_plugin
Definition: joint_mimic.hpp:39
kinematics::KinematicsBase::IKCallbackFn
boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
kdl_kinematics_plugin::KDLKinematicsPlugin::timedOut
bool timedOut(const ros::WallTime &start_time, double duration) const
Definition: kdl_kinematics_plugin.cpp:301
KDL
Definition: chainiksolver_vel_mimic_svd.hpp:35
kdl_kinematics_plugin::KDLKinematicsPlugin::KDLKinematicsPlugin
KDLKinematicsPlugin()
Default constructor.
Definition: kdl_kinematics_plugin.cpp:86
kdl_kinematics_plugin::KDLKinematicsPlugin::getPositionFK
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
Definition: kdl_kinematics_plugin.cpp:554
kdl_kinematics_plugin::KDLKinematicsPlugin::joint_weights_
std::vector< double > joint_weights_
Definition: kdl_kinematics_plugin.h:169
kdl_kinematics_plugin::KDLKinematicsPlugin::joint_max_
Eigen::VectorXd joint_max_
joint limits
Definition: kdl_kinematics_plugin.h:170
kinematics::KinematicsBase
kdl_kinematics_plugin::KDLKinematicsPlugin::kdl_chain_
KDL::Chain kdl_chain_
Definition: kdl_kinematics_plugin.h:166
kdl_kinematics_plugin::KDLKinematicsPlugin::orientation_vs_position_weight_
double orientation_vs_position_weight_
Definition: kdl_kinematics_plugin.h:179
kdl_kinematics_plugin::KDLKinematicsPlugin::epsilon_
double epsilon_
Definition: kdl_kinematics_plugin.h:173
kdl_kinematics_plugin::KDLKinematicsPlugin::Twist
Eigen::Matrix< double, 6, 1 > Twist
Definition: kdl_kinematics_plugin.h:125
ros::WallTime
kdl_kinematics_plugin::KDLKinematicsPlugin::getLinkNames
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
Definition: kdl_kinematics_plugin.cpp:595
KDL::ChainIkSolverVelMimicSVD
Definition: chainiksolver_vel_mimic_svd.hpp:46
kdl_kinematics_plugin::KDLKinematicsPlugin
Specific implementation of kinematics using KDL. This version supports any kinematic chain,...
Definition: kdl_kinematics_plugin.h:72
kdl_kinematics_plugin::KDLKinematicsPlugin::mimic_joints_
std::vector< JointMimic > mimic_joints_
Definition: kdl_kinematics_plugin.h:168
kdl_kinematics_plugin::KDLKinematicsPlugin::checkConsistency
bool checkConsistency(const Eigen::VectorXd &seed_state, const std::vector< double > &consistency_limits, const Eigen::VectorXd &solution) const
Check whether the solution lies within the consistency limits of the seed state.
Definition: kdl_kinematics_plugin.cpp:104
kinematics::KinematicsQueryOptions
kdl_kinematics_plugin::KDLKinematicsPlugin::getPositionIK
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 override
Definition: kdl_kinematics_plugin.cpp:306
joint_mimic.hpp
kdl_kinematics_plugin::KDLKinematicsPlugin::CartToJnt
int CartToJnt(KDL::ChainIkSolverVelMimicSVD &ik_solver, const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const unsigned int max_iter, const Eigen::VectorXd &joint_weights, const Twist &cartesian_weights) const
Solve position IK given initial joint values.
Definition: kdl_kinematics_plugin.cpp:454
kdl_kinematics_plugin::KDLKinematicsPlugin::solver_info_
moveit_msgs::KinematicSolverInfo solver_info_
Stores information for the inverse kinematics solver.
Definition: kdl_kinematics_plugin.h:162
kinematics_base.h
moveit::core::JointModelGroup
kdl_kinematics_plugin::KDLKinematicsPlugin::getRandomConfiguration
void getRandomConfiguration(Eigen::VectorXd &jnt_array) const
Definition: kdl_kinematics_plugin.cpp:90
kdl_kinematics_plugin::KDLKinematicsPlugin::getJointNames
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
Definition: kdl_kinematics_plugin.cpp:590
kdl_kinematics_plugin::KDLKinematicsPlugin::fk_solver_
std::unique_ptr< KDL::ChainFkSolverPos > fk_solver_
Definition: kdl_kinematics_plugin.h:167
kdl_kinematics_plugin::KDLKinematicsPlugin::getJointWeights
void getJointWeights()
Definition: kdl_kinematics_plugin.cpp:114
kdl_kinematics_plugin::KDLKinematicsPlugin::joint_min_
Eigen::VectorXd joint_min_
Definition: kdl_kinematics_plugin.h:170
kdl_kinematics_plugin::KDLKinematicsPlugin::dimension_
unsigned int dimension_
Dimension of the group.
Definition: kdl_kinematics_plugin.h:161
kdl_kinematics_plugin::KDLKinematicsPlugin::initialized_
bool initialized_
Internal variable that indicates whether solver is configured and ready.
Definition: kdl_kinematics_plugin.h:159


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:15