#include <trac_ik.hpp>
| Public Member Functions | |
| int | CartToJnt (const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist &bounds=KDL::Twist::Zero()) | 
| bool | getKDLChain (KDL::Chain &chain_) | 
| bool | getKDLLimits (KDL::JntArray &lb_, KDL::JntArray &ub_) | 
| bool | getSolutions (std::vector< KDL::JntArray > &solutions_) | 
| bool | getSolutions (std::vector< KDL::JntArray > &solutions_, std::vector< std::pair< double, uint > > &errors_) | 
| bool | setKDLLimits (KDL::JntArray &lb_, KDL::JntArray &ub_) | 
| void | SetSolveType (SolveType _type) | 
| 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) | |
| 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) | |
| ~TRAC_IK () | |
| Static Public Member Functions | |
| static double | JointErr (const KDL::JntArray &arr1, const KDL::JntArray &arr2) | 
| Private Member Functions | |
| void | initialize () | 
| double | manipPenalty (const KDL::JntArray &) | 
| double | ManipValue1 (const KDL::JntArray &) | 
| double | ManipValue2 (const KDL::JntArray &) | 
| bool | myEqual (const KDL::JntArray &a, const KDL::JntArray &b) | 
| void | normalize_limits (const KDL::JntArray &seed, KDL::JntArray &solution) | 
| void | normalize_seed (const KDL::JntArray &seed, KDL::JntArray &solution) | 
| bool | runKDL (const KDL::JntArray &q_init, const KDL::Frame &p_in) | 
| bool | runNLOPT (const KDL::JntArray &q_init, const KDL::Frame &p_in) | 
| template<typename T1 , typename T2 > | |
| bool | runSolver (T1 &solver, T2 &other_solver, const KDL::JntArray &q_init, const KDL::Frame &p_in) | 
| bool | unique_solution (const KDL::JntArray &sol) | 
| Static Private Member Functions | |
| static double | fRand (double min, double max) | 
| Private Attributes | |
| KDL::Twist | bounds | 
| KDL::Chain | chain | 
| double | eps | 
| std::vector< std::pair< double, uint > > | errors | 
| std::unique_ptr< KDL::ChainIkSolverPos_TL > | iksolver | 
| bool | initialized | 
| std::unique_ptr< KDL::ChainJntToJacSolver > | jacsolver | 
| KDL::JntArray | lb | 
| double | maxtime | 
| std::mutex | mtx_ | 
| std::unique_ptr< NLOPT_IK::NLOPT_IK > | nl_solver | 
| std::vector< KDL::JntArray > | solutions | 
| SolveType | solvetype | 
| boost::posix_time::ptime | start_time | 
| std::thread | task1 | 
| std::thread | task2 | 
| std::vector< KDL::BasicJointType > | types | 
| KDL::JntArray | ub | 
Definition at line 47 of file trac_ik.hpp.
| TRAC_IK::TRAC_IK::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 | ||
| ) | 
Definition at line 133 of file trac_ik.cpp.
| TRAC_IK::TRAC_IK::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 | ||
| ) | 
Definition at line 43 of file trac_ik.cpp.
| TRAC_IK::TRAC_IK::~TRAC_IK | ( | ) | 
Definition at line 464 of file trac_ik.cpp.
| int TRAC_IK::TRAC_IK::CartToJnt | ( | const KDL::JntArray & | q_init, | 
| const KDL::Frame & | p_in, | ||
| KDL::JntArray & | q_out, | ||
| const KDL::Twist & | bounds = KDL::Twist::Zero() | ||
| ) | 
Definition at line 415 of file trac_ik.cpp.
| 
 | inlinestaticprivate | 
Definition at line 145 of file trac_ik.hpp.
| 
 | inline | 
Definition at line 56 of file trac_ik.hpp.
| 
 | inline | 
Definition at line 62 of file trac_ik.hpp.
| 
 | inline | 
Definition at line 70 of file trac_ik.hpp.
| 
 | inline | 
Definition at line 76 of file trac_ik.hpp.
| 
 | private | 
Definition at line 145 of file trac_ik.cpp.
| 
 | inlinestatic | 
Definition at line 91 of file trac_ik.hpp.
| 
 | private | 
Definition at line 373 of file trac_ik.cpp.
| 
 | private | 
Definition at line 387 of file trac_ik.cpp.
| 
 | private | 
Definition at line 402 of file trac_ik.cpp.
| 
 | inlineprivate | 
Definition at line 160 of file trac_ik.hpp.
| 
 | private | 
Definition at line 337 of file trac_ik.cpp.
| 
 | private | 
Definition at line 307 of file trac_ik.cpp.
| 
 | inlineprivate | 
Definition at line 169 of file trac_ik.hpp.
| 
 | inlineprivate | 
Definition at line 174 of file trac_ik.hpp.
| 
 | private | 
Definition at line 227 of file trac_ik.cpp.
| 
 | inline | 
Definition at line 82 of file trac_ik.hpp.
| 
 | inline | 
Definition at line 104 of file trac_ik.hpp.
| 
 | private | 
Definition at line 175 of file trac_ik.cpp.
| 
 | private | 
Definition at line 141 of file trac_ik.hpp.
| 
 | private | 
Definition at line 111 of file trac_ik.hpp.
| 
 | private | 
Definition at line 114 of file trac_ik.hpp.
| 
 | private | 
Definition at line 138 of file trac_ik.hpp.
| 
 | private | 
Definition at line 119 of file trac_ik.hpp.
| 
 | private | 
Definition at line 110 of file trac_ik.hpp.
| 
 | private | 
Definition at line 113 of file trac_ik.hpp.
| 
 | private | 
Definition at line 112 of file trac_ik.hpp.
| 
 | private | 
Definition at line 115 of file trac_ik.hpp.
| 
 | private | 
Definition at line 136 of file trac_ik.hpp.
| 
 | private | 
Definition at line 118 of file trac_ik.hpp.
| 
 | private | 
Definition at line 137 of file trac_ik.hpp.
| 
 | private | 
Definition at line 116 of file trac_ik.hpp.
| 
 | private | 
Definition at line 121 of file trac_ik.hpp.
| 
 | private | 
Definition at line 140 of file trac_ik.hpp.
| 
 | private | 
Definition at line 140 of file trac_ik.hpp.
| 
 | private | 
Definition at line 134 of file trac_ik.hpp.
| 
 | private | 
Definition at line 112 of file trac_ik.hpp.