trac_ik.hpp
Go to the documentation of this file.
1 /********************************************************************************
2 Copyright (c) 2015, TRACLabs, Inc.
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without modification,
6  are permitted provided that the following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice,
9  this list of conditions and the following disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice,
12  this list of conditions and the following disclaimer in the documentation
13  and/or other materials provided with the distribution.
14 
15  3. Neither the name of the copyright holder nor the names of its contributors
16  may be used to endorse or promote products derived from this software
17  without specific prior written permission.
18 
19 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
20 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
21 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
22 IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
23 INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24 BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
25 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
26 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
27 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
28 OF THE POSSIBILITY OF SUCH DAMAGE.
29 ********************************************************************************/
30 
31 
32 #ifndef TRAC_IK_HPP
33 #define TRAC_IK_HPP
34 
35 #include <trac_ik/nlopt_ik.hpp>
36 #include <kdl/chainjnttojacsolver.hpp>
37 #include <thread>
38 #include <mutex>
39 #include <memory>
40 #include <boost/date_time.hpp>
41 
42 namespace TRAC_IK
43 {
44 
46 
47 class TRAC_IK
48 {
49 public:
50  TRAC_IK(const KDL::Chain& _chain, const KDL::JntArray& _q_min, const KDL::JntArray& _q_max, double _maxtime = 0.005, double _eps = 1e-5, SolveType _type = Speed);
51 
52  TRAC_IK(const std::string& base_link, const std::string& tip_link, const std::string& URDF_param = "/robot_description", double _maxtime = 0.005, double _eps = 1e-5, SolveType _type = Speed);
53 
54  ~TRAC_IK();
55 
56  bool getKDLChain(KDL::Chain& chain_)
57  {
58  chain_ = chain;
59  return initialized;
60  }
61 
63  {
64  lb_ = lb;
65  ub_ = ub;
66  return initialized;
67  }
68 
69  // Requires a previous call to CartToJnt()
70  bool getSolutions(std::vector<KDL::JntArray>& solutions_)
71  {
72  solutions_ = solutions;
73  return initialized && !solutions.empty();
74  }
75 
76  bool getSolutions(std::vector<KDL::JntArray>& solutions_, std::vector<std::pair<double, uint> >& errors_)
77  {
78  errors_ = errors;
79  return getSolutions(solutions_);
80  }
81 
83  {
84  lb = lb_;
85  ub = ub_;
86  nl_solver.reset(new NLOPT_IK::NLOPT_IK(chain, lb, ub, maxtime, eps, NLOPT_IK::SumSq));
87  iksolver.reset(new KDL::ChainIkSolverPos_TL(chain, lb, ub, maxtime, eps, true, true));
88  return true;
89  }
90 
91  static double JointErr(const KDL::JntArray& arr1, const KDL::JntArray& arr2)
92  {
93  double err = 0;
94  for (uint i = 0; i < arr1.data.size(); i++)
95  {
96  err += pow(arr1(i) - arr2(i), 2);
97  }
98 
99  return err;
100  }
101 
102  int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist& bounds = KDL::Twist::Zero());
103 
104  inline void SetSolveType(SolveType _type)
105  {
106  solvetype = _type;
107  }
108 
109 private:
113  std::unique_ptr<KDL::ChainJntToJacSolver> jacsolver;
114  double eps;
115  double maxtime;
117 
118  std::unique_ptr<NLOPT_IK::NLOPT_IK> nl_solver;
119  std::unique_ptr<KDL::ChainIkSolverPos_TL> iksolver;
120 
121  boost::posix_time::ptime start_time;
122 
123  template<typename T1, typename T2>
124  bool runSolver(T1& solver, T2& other_solver,
125  const KDL::JntArray &q_init,
126  const KDL::Frame &p_in);
127 
128  bool runKDL(const KDL::JntArray &q_init, const KDL::Frame &p_in);
129  bool runNLOPT(const KDL::JntArray &q_init, const KDL::Frame &p_in);
130 
131  void normalize_seed(const KDL::JntArray& seed, KDL::JntArray& solution);
132  void normalize_limits(const KDL::JntArray& seed, KDL::JntArray& solution);
133 
134  std::vector<KDL::BasicJointType> types;
135 
136  std::mutex mtx_;
137  std::vector<KDL::JntArray> solutions;
138  std::vector<std::pair<double, uint> > errors;
139 
140  std::thread task1, task2;
142 
143  bool unique_solution(const KDL::JntArray& sol);
144 
145  inline static double fRand(double min, double max)
146  {
147  double f = (double)rand() / RAND_MAX;
148  return min + f * (max - min);
149  }
150 
151  /* @brief Manipulation metrics and penalties taken from "Workspace
152  Geometric Characterization and Manipulability of Industrial Robots",
153  Ming-June, Tsia, PhD Thesis, Ohio State University, 1986.
154  https://etd.ohiolink.edu/!etd.send_file?accession=osu1260297835
155  */
156  double manipPenalty(const KDL::JntArray&);
157  double ManipValue1(const KDL::JntArray&);
158  double ManipValue2(const KDL::JntArray&);
159 
160  inline bool myEqual(const KDL::JntArray& a, const KDL::JntArray& b)
161  {
162  return (a.data - b.data).isZero(1e-4);
163  }
164 
165  void initialize();
166 
167 };
168 
169 inline bool TRAC_IK::runKDL(const KDL::JntArray &q_init, const KDL::Frame &p_in)
170 {
171  return runSolver(*iksolver.get(), *nl_solver.get(), q_init, p_in);
172 }
173 
174 inline bool TRAC_IK::runNLOPT(const KDL::JntArray &q_init, const KDL::Frame &p_in)
175 {
176  return runSolver(*nl_solver.get(), *iksolver.get(), q_init, p_in);
177 }
178 
179 }
180 
181 #endif
bool myEqual(const KDL::JntArray &a, const KDL::JntArray &b)
Definition: trac_ik.hpp:160
SolveType solvetype
Definition: trac_ik.hpp:116
static Twist Zero()
bool getKDLLimits(KDL::JntArray &lb_, KDL::JntArray &ub_)
Definition: trac_ik.hpp:62
KDL::Twist bounds
Definition: trac_ik.hpp:141
f
ROSCONSOLE_DECL void initialize()
KDL::Chain chain
Definition: trac_ik.hpp:111
std::vector< KDL::JntArray > solutions
Definition: trac_ik.hpp:137
std::unique_ptr< KDL::ChainIkSolverPos_TL > iksolver
Definition: trac_ik.hpp:119
std::mutex mtx_
Definition: trac_ik.hpp:136
bool setKDLLimits(KDL::JntArray &lb_, KDL::JntArray &ub_)
Definition: trac_ik.hpp:82
std::unique_ptr< NLOPT_IK::NLOPT_IK > nl_solver
Definition: trac_ik.hpp:118
std::vector< std::pair< double, uint > > errors
Definition: trac_ik.hpp:138
std::vector< KDL::BasicJointType > types
Definition: trac_ik.hpp:134
std::unique_ptr< KDL::ChainJntToJacSolver > jacsolver
Definition: trac_ik.hpp:113
static double JointErr(const KDL::JntArray &arr1, const KDL::JntArray &arr2)
Definition: trac_ik.hpp:91
Eigen::VectorXd data
static double fRand(double min, double max)
Definition: trac_ik.hpp:145
void SetSolveType(SolveType _type)
Definition: trac_ik.hpp:104
boost::posix_time::ptime start_time
Definition: trac_ik.hpp:121
std::thread task2
Definition: trac_ik.hpp:140
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
bool getSolutions(std::vector< KDL::JntArray > &solutions_, std::vector< std::pair< double, uint > > &errors_)
Definition: trac_ik.hpp:76
bool getKDLChain(KDL::Chain &chain_)
Definition: trac_ik.hpp:56
bool getSolutions(std::vector< KDL::JntArray > &solutions_)
Definition: trac_ik.hpp:70
KDL::JntArray ub
Definition: trac_ik.hpp:112


trac_ik_lib
Author(s): Patrick Beeson, Barrett Ames
autogenerated on Tue Jun 1 2021 02:38:35