Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
TRAC_IK::TRAC_IK Class Reference

#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_TLiksolver
 
bool initialized
 
std::unique_ptr< KDL::ChainJntToJacSolverjacsolver
 
KDL::JntArray lb
 
double maxtime
 
std::mutex mtx_
 
std::unique_ptr< NLOPT_IK::NLOPT_IKnl_solver
 
std::vector< KDL::JntArraysolutions
 
SolveType solvetype
 
boost::posix_time::ptime start_time
 
std::thread task1
 
std::thread task2
 
std::vector< KDL::BasicJointTypetypes
 
KDL::JntArray ub
 

Detailed Description

Definition at line 47 of file trac_ik.hpp.

Constructor & Destructor Documentation

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.

Member Function Documentation

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.

static double TRAC_IK::TRAC_IK::fRand ( double  min,
double  max 
)
inlinestaticprivate

Definition at line 145 of file trac_ik.hpp.

bool TRAC_IK::TRAC_IK::getKDLChain ( KDL::Chain chain_)
inline

Definition at line 56 of file trac_ik.hpp.

bool TRAC_IK::TRAC_IK::getKDLLimits ( KDL::JntArray lb_,
KDL::JntArray ub_ 
)
inline

Definition at line 62 of file trac_ik.hpp.

bool TRAC_IK::TRAC_IK::getSolutions ( std::vector< KDL::JntArray > &  solutions_)
inline

Definition at line 70 of file trac_ik.hpp.

bool TRAC_IK::TRAC_IK::getSolutions ( std::vector< KDL::JntArray > &  solutions_,
std::vector< std::pair< double, uint > > &  errors_ 
)
inline

Definition at line 76 of file trac_ik.hpp.

void TRAC_IK::TRAC_IK::initialize ( )
private

Definition at line 145 of file trac_ik.cpp.

static double TRAC_IK::TRAC_IK::JointErr ( const KDL::JntArray arr1,
const KDL::JntArray arr2 
)
inlinestatic

Definition at line 91 of file trac_ik.hpp.

double TRAC_IK::TRAC_IK::manipPenalty ( const KDL::JntArray arr)
private

Definition at line 373 of file trac_ik.cpp.

double TRAC_IK::TRAC_IK::ManipValue1 ( const KDL::JntArray arr)
private

Definition at line 387 of file trac_ik.cpp.

double TRAC_IK::TRAC_IK::ManipValue2 ( const KDL::JntArray arr)
private

Definition at line 402 of file trac_ik.cpp.

bool TRAC_IK::TRAC_IK::myEqual ( const KDL::JntArray a,
const KDL::JntArray b 
)
inlineprivate

Definition at line 160 of file trac_ik.hpp.

void TRAC_IK::TRAC_IK::normalize_limits ( const KDL::JntArray seed,
KDL::JntArray solution 
)
private

Definition at line 337 of file trac_ik.cpp.

void TRAC_IK::TRAC_IK::normalize_seed ( const KDL::JntArray seed,
KDL::JntArray solution 
)
private

Definition at line 307 of file trac_ik.cpp.

bool TRAC_IK::TRAC_IK::runKDL ( const KDL::JntArray q_init,
const KDL::Frame p_in 
)
inlineprivate

Definition at line 169 of file trac_ik.hpp.

bool TRAC_IK::TRAC_IK::runNLOPT ( const KDL::JntArray q_init,
const KDL::Frame p_in 
)
inlineprivate

Definition at line 174 of file trac_ik.hpp.

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

Definition at line 227 of file trac_ik.cpp.

bool TRAC_IK::TRAC_IK::setKDLLimits ( KDL::JntArray lb_,
KDL::JntArray ub_ 
)
inline

Definition at line 82 of file trac_ik.hpp.

void TRAC_IK::TRAC_IK::SetSolveType ( SolveType  _type)
inline

Definition at line 104 of file trac_ik.hpp.

bool TRAC_IK::TRAC_IK::unique_solution ( const KDL::JntArray sol)
private

Definition at line 175 of file trac_ik.cpp.

Member Data Documentation

KDL::Twist TRAC_IK::TRAC_IK::bounds
private

Definition at line 141 of file trac_ik.hpp.

KDL::Chain TRAC_IK::TRAC_IK::chain
private

Definition at line 111 of file trac_ik.hpp.

double TRAC_IK::TRAC_IK::eps
private

Definition at line 114 of file trac_ik.hpp.

std::vector<std::pair<double, uint> > TRAC_IK::TRAC_IK::errors
private

Definition at line 138 of file trac_ik.hpp.

std::unique_ptr<KDL::ChainIkSolverPos_TL> TRAC_IK::TRAC_IK::iksolver
private

Definition at line 119 of file trac_ik.hpp.

bool TRAC_IK::TRAC_IK::initialized
private

Definition at line 110 of file trac_ik.hpp.

std::unique_ptr<KDL::ChainJntToJacSolver> TRAC_IK::TRAC_IK::jacsolver
private

Definition at line 113 of file trac_ik.hpp.

KDL::JntArray TRAC_IK::TRAC_IK::lb
private

Definition at line 112 of file trac_ik.hpp.

double TRAC_IK::TRAC_IK::maxtime
private

Definition at line 115 of file trac_ik.hpp.

std::mutex TRAC_IK::TRAC_IK::mtx_
private

Definition at line 136 of file trac_ik.hpp.

std::unique_ptr<NLOPT_IK::NLOPT_IK> TRAC_IK::TRAC_IK::nl_solver
private

Definition at line 118 of file trac_ik.hpp.

std::vector<KDL::JntArray> TRAC_IK::TRAC_IK::solutions
private

Definition at line 137 of file trac_ik.hpp.

SolveType TRAC_IK::TRAC_IK::solvetype
private

Definition at line 116 of file trac_ik.hpp.

boost::posix_time::ptime TRAC_IK::TRAC_IK::start_time
private

Definition at line 121 of file trac_ik.hpp.

std::thread TRAC_IK::TRAC_IK::task1
private

Definition at line 140 of file trac_ik.hpp.

std::thread TRAC_IK::TRAC_IK::task2
private

Definition at line 140 of file trac_ik.hpp.

std::vector<KDL::BasicJointType> TRAC_IK::TRAC_IK::types
private

Definition at line 134 of file trac_ik.hpp.

KDL::JntArray TRAC_IK::TRAC_IK::ub
private

Definition at line 112 of file trac_ik.hpp.


The documentation for this class was generated from the following files:


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