Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes
TRAC_IK::TRAC_IK Class Reference

#include <trac_ik.hpp>

List of all members.

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_)
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)
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
boost::scoped_ptr
< KDL::ChainIkSolverPos_TL
iksolver
bool initialized
boost::asio::io_service io_service
boost::scoped_ptr
< KDL::ChainJntToJacSolver
jacsolver
KDL::JntArray lb
double maxtime
boost::mutex mtx_
boost::scoped_ptr
< NLOPT_IK::NLOPT_IK
nl_solver
std::vector< KDL::JntArraysolutions
SolveType solvetype
boost::posix_time::ptime start_time
boost::thread_group threads
std::vector< KDL::BasicJointType > types
KDL::JntArray ub
boost::asio::io_service::work work

Detailed Description

Definition at line 46 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 125 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.

Definition at line 522 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 459 of file trac_ik.cpp.

static double TRAC_IK::TRAC_IK::fRand ( double  min,
double  max 
) [inline, static, private]

Definition at line 119 of file trac_ik.hpp.

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

Definition at line 55 of file trac_ik.hpp.

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

Definition at line 60 of file trac_ik.hpp.

void TRAC_IK::TRAC_IK::initialize ( ) [private]

Definition at line 139 of file trac_ik.cpp.

static double TRAC_IK::TRAC_IK::JointErr ( const KDL::JntArray arr1,
const KDL::JntArray arr2 
) [inline, static]

Definition at line 67 of file trac_ik.hpp.

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

Definition at line 421 of file trac_ik.cpp.

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

Definition at line 433 of file trac_ik.cpp.

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

Definition at line 447 of file trac_ik.cpp.

bool TRAC_IK::TRAC_IK::myEqual ( const KDL::JntArray a,
const KDL::JntArray b 
) [inline, private]

Definition at line 134 of file trac_ik.hpp.

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

Definition at line 388 of file trac_ik.cpp.

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

Definition at line 361 of file trac_ik.cpp.

bool TRAC_IK::TRAC_IK::runKDL ( const KDL::JntArray q_init,
const KDL::Frame p_in 
) [private]

Definition at line 216 of file trac_ik.cpp.

bool TRAC_IK::TRAC_IK::runNLOPT ( const KDL::JntArray q_init,
const KDL::Frame p_in 
) [private]

Definition at line 288 of file trac_ik.cpp.

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

Definition at line 78 of file trac_ik.hpp.

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

Definition at line 172 of file trac_ik.cpp.


Member Data Documentation

Definition at line 115 of file trac_ik.hpp.

Definition at line 84 of file trac_ik.hpp.

double TRAC_IK::TRAC_IK::eps [private]

Definition at line 87 of file trac_ik.hpp.

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

Definition at line 109 of file trac_ik.hpp.

Definition at line 92 of file trac_ik.hpp.

Definition at line 83 of file trac_ik.hpp.

boost::asio::io_service TRAC_IK::TRAC_IK::io_service [private]

Definition at line 112 of file trac_ik.hpp.

Definition at line 86 of file trac_ik.hpp.

Definition at line 85 of file trac_ik.hpp.

double TRAC_IK::TRAC_IK::maxtime [private]

Definition at line 88 of file trac_ik.hpp.

boost::mutex TRAC_IK::TRAC_IK::mtx_ [private]

Definition at line 107 of file trac_ik.hpp.

boost::scoped_ptr<NLOPT_IK::NLOPT_IK> TRAC_IK::TRAC_IK::nl_solver [private]

Definition at line 91 of file trac_ik.hpp.

Definition at line 108 of file trac_ik.hpp.

Definition at line 89 of file trac_ik.hpp.

boost::posix_time::ptime TRAC_IK::TRAC_IK::start_time [private]

Definition at line 94 of file trac_ik.hpp.

boost::thread_group TRAC_IK::TRAC_IK::threads [private]

Definition at line 113 of file trac_ik.hpp.

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

Definition at line 105 of file trac_ik.hpp.

Definition at line 85 of file trac_ik.hpp.

boost::asio::io_service::work TRAC_IK::TRAC_IK::work [private]

Definition at line 114 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 Thu Sep 21 2017 02:53:02