#include <trac_ik.hpp>
|
| 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 () |
| |
Definition at line 47 of file trac_ik.hpp.
◆ TRAC_IK() [1/2]
◆ TRAC_IK() [2/2]
| 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 |
|
) |
| |
◆ ~TRAC_IK()
| TRAC_IK::TRAC_IK::~TRAC_IK |
( |
| ) |
|
◆ CartToJnt()
◆ fRand()
| static double TRAC_IK::TRAC_IK::fRand |
( |
double |
min, |
|
|
double |
max |
|
) |
| |
|
inlinestaticprivate |
◆ getKDLChain()
| bool TRAC_IK::TRAC_IK::getKDLChain |
( |
KDL::Chain & |
chain_ | ) |
|
|
inline |
◆ getKDLLimits()
◆ getSolutions() [1/2]
| bool TRAC_IK::TRAC_IK::getSolutions |
( |
std::vector< KDL::JntArray > & |
solutions_ | ) |
|
|
inline |
◆ getSolutions() [2/2]
| bool TRAC_IK::TRAC_IK::getSolutions |
( |
std::vector< KDL::JntArray > & |
solutions_, |
|
|
std::vector< std::pair< double, uint > > & |
errors_ |
|
) |
| |
|
inline |
◆ initialize()
| void TRAC_IK::TRAC_IK::initialize |
( |
| ) |
|
|
private |
◆ JointErr()
◆ manipPenalty()
| double TRAC_IK::TRAC_IK::manipPenalty |
( |
const KDL::JntArray & |
arr | ) |
|
|
private |
◆ ManipValue1()
| double TRAC_IK::TRAC_IK::ManipValue1 |
( |
const KDL::JntArray & |
arr | ) |
|
|
private |
◆ ManipValue2()
| double TRAC_IK::TRAC_IK::ManipValue2 |
( |
const KDL::JntArray & |
arr | ) |
|
|
private |
◆ myEqual()
◆ normalize_limits()
◆ normalize_seed()
◆ runKDL()
◆ runNLOPT()
◆ runSolver()
template<typename T1 , typename T2 >
| bool TRAC_IK::TRAC_IK::runSolver |
( |
T1 & |
solver, |
|
|
T2 & |
other_solver, |
|
|
const KDL::JntArray & |
q_init, |
|
|
const KDL::Frame & |
p_in |
|
) |
| |
|
private |
◆ setKDLLimits()
◆ SetSolveType()
| void TRAC_IK::TRAC_IK::SetSolveType |
( |
SolveType |
_type | ) |
|
|
inline |
◆ unique_solution()
| bool TRAC_IK::TRAC_IK::unique_solution |
( |
const KDL::JntArray & |
sol | ) |
|
|
private |
◆ bounds
◆ chain
◆ eps
| double TRAC_IK::TRAC_IK::eps |
|
private |
◆ errors
| std::vector<std::pair<double, uint> > TRAC_IK::TRAC_IK::errors |
|
private |
◆ iksolver
◆ initialized
| bool TRAC_IK::TRAC_IK::initialized |
|
private |
◆ jacsolver
◆ lb
◆ maxtime
| double TRAC_IK::TRAC_IK::maxtime |
|
private |
◆ mtx_
| std::mutex TRAC_IK::TRAC_IK::mtx_ |
|
private |
◆ nl_solver
◆ solutions
◆ solvetype
◆ start_time
| boost::posix_time::ptime TRAC_IK::TRAC_IK::start_time |
|
private |
◆ task1
| std::thread TRAC_IK::TRAC_IK::task1 |
|
private |
◆ task2
| std::thread TRAC_IK::TRAC_IK::task2 |
|
private |
◆ types
◆ ub
The documentation for this class was generated from the following files: