lma_kinematics_plugin.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2016, CRI group, NTU, Singapore
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 CRI group 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: Francisco Suarez-Ruiz */
36 
37 #pragma once
38 
39 // ROS
40 #include <ros/ros.h>
42 
43 // ROS msgs
44 #include <geometry_msgs/Pose.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
59 
61 {
67 {
68 public:
73 
74  bool
75  getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
76  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
78 
79  bool searchPositionIK(
80  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
81  std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
83 
84  bool searchPositionIK(
85  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
86  const std::vector<double>& consistency_limits, std::vector<double>& solution,
87  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  std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
94 
95  bool searchPositionIK(
96  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
97  const std::vector<double>& consistency_limits, std::vector<double>& solution,
98  const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
100 
101  bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
102  std::vector<geometry_msgs::Pose>& poses) const override;
103 
104  bool initialize(const moveit::core::RobotModel& robot_model, const std::string& group_name,
105  const std::string& base_frame, const std::vector<std::string>& tip_frames,
106  double search_discretization) override;
107 
111  const std::vector<std::string>& getJointNames() const override;
112 
116  const std::vector<std::string>& getLinkNames() const override;
117 
118 private:
119  bool timedOut(const ros::WallTime& start_time, double duration) const;
120 
127  bool checkConsistency(const Eigen::VectorXd& seed_state, const std::vector<double>& consistency_limits,
128  const Eigen::VectorXd& solution) const;
130  bool obeysLimits(const Eigen::VectorXd& values) const;
132  void harmonize(Eigen::VectorXd& values) const;
133 
134  void getRandomConfiguration(Eigen::VectorXd& jnt_array) const;
135 
141  void getRandomConfiguration(const Eigen::VectorXd& seed_state, const std::vector<double>& consistency_limits,
142  Eigen::VectorXd& jnt_array) const;
143 
144  bool initialized_;
145 
146  unsigned int dimension_;
147  moveit_msgs::KinematicSolverInfo solver_info_;
148 
150  moveit::core::RobotStatePtr state_;
151  KDL::Chain kdl_chain_;
152  std::unique_ptr<KDL::ChainFkSolverPos> fk_solver_;
153  std::vector<const moveit::core::JointModel*> joints_;
154  std::vector<std::string> joint_names_;
155 
157  double epsilon_;
164 };
165 } // namespace lma_kinematics_plugin
robot_model.h
random_numbers.h
lma_kinematics_plugin::LMAKinematicsPlugin::fk_solver_
std::unique_ptr< KDL::ChainFkSolverPos > fk_solver_
Definition: lma_kinematics_plugin.h:216
duration
std::chrono::system_clock::duration duration
lma_kinematics_plugin::LMAKinematicsPlugin::solver_info_
moveit_msgs::KinematicSolverInfo solver_info_
Stores information for the inverse kinematics solver.
Definition: lma_kinematics_plugin.h:211
lma_kinematics_plugin::LMAKinematicsPlugin::orientation_vs_position_weight_
double orientation_vs_position_weight_
Definition: lma_kinematics_plugin.h:227
lma_kinematics_plugin::LMAKinematicsPlugin::kdl_chain_
KDL::Chain kdl_chain_
Definition: lma_kinematics_plugin.h:215
lma_kinematics_plugin::LMAKinematicsPlugin::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: lma_kinematics_plugin.cpp:338
ros.h
lma_kinematics_plugin::LMAKinematicsPlugin::joint_names_
std::vector< std::string > joint_names_
Definition: lma_kinematics_plugin.h:218
moveit::core::RobotModel
lma_kinematics_plugin::LMAKinematicsPlugin::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: lma_kinematics_plugin.cpp:102
lma_kinematics_plugin::LMAKinematicsPlugin::harmonize
void harmonize(Eigen::VectorXd &values) const
Definition: lma_kinematics_plugin.cpp:224
robot_state.h
kinematics::KinematicsBase::IKCallbackFn
boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
lma_kinematics_plugin::LMAKinematicsPlugin::getLinkNames
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
Definition: lma_kinematics_plugin.cpp:379
lma_kinematics_plugin::LMAKinematicsPlugin::max_solver_iterations_
int max_solver_iterations_
Definition: lma_kinematics_plugin.h:220
lma_kinematics_plugin::LMAKinematicsPlugin::dimension_
unsigned int dimension_
Dimension of the group.
Definition: lma_kinematics_plugin.h:210
lma_kinematics_plugin::LMAKinematicsPlugin::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: lma_kinematics_plugin.h:213
lma_kinematics_plugin::LMAKinematicsPlugin::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: lma_kinematics_plugin.cpp:182
lma_kinematics_plugin::LMAKinematicsPlugin::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: lma_kinematics_plugin.cpp:112
lma_kinematics_plugin::LMAKinematicsPlugin::epsilon_
double epsilon_
Definition: lma_kinematics_plugin.h:221
lma_kinematics_plugin::LMAKinematicsPlugin::state_
moveit::core::RobotStatePtr state_
Definition: lma_kinematics_plugin.h:214
lma_kinematics_plugin::LMAKinematicsPlugin
Implementation of kinematics using Levenberg-Marquardt (LMA) solver from KDL. This version supports a...
Definition: lma_kinematics_plugin.h:98
kinematics::KinematicsBase
lma_kinematics_plugin::LMAKinematicsPlugin::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: lma_kinematics_plugin.cpp:193
lma_kinematics_plugin::LMAKinematicsPlugin::initialized_
bool initialized_
Internal variable that indicates whether solver is configured and ready.
Definition: lma_kinematics_plugin.h:208
lma_kinematics_plugin::LMAKinematicsPlugin::joints_
std::vector< const moveit::core::JointModel * > joints_
Definition: lma_kinematics_plugin.h:217
ros::WallTime
lma_kinematics_plugin::LMAKinematicsPlugin::getRandomConfiguration
void getRandomConfiguration(Eigen::VectorXd &jnt_array) const
Definition: lma_kinematics_plugin.cpp:88
lma_kinematics_plugin::LMAKinematicsPlugin::getJointNames
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
Definition: lma_kinematics_plugin.cpp:374
kinematics::KinematicsQueryOptions
kinematics_base.h
moveit::core::JointModelGroup
lma_kinematics_plugin::LMAKinematicsPlugin::LMAKinematicsPlugin
LMAKinematicsPlugin()
Default constructor.
Definition: lma_kinematics_plugin.cpp:84
lma_kinematics_plugin
Definition: lma_kinematics_plugin.h:60
lma_kinematics_plugin::LMAKinematicsPlugin::obeysLimits
bool obeysLimits(const Eigen::VectorXd &values) const
Definition: lma_kinematics_plugin.cpp:231
lma_kinematics_plugin::LMAKinematicsPlugin::timedOut
bool timedOut(const ros::WallTime &start_time, double duration) const
Definition: lma_kinematics_plugin.cpp:177


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