#include <nlopt_ik.hpp>
Public Member Functions | |
void | cartDQError (const std::vector< double > &x, double error[]) |
void | cartL2NormError (const std::vector< double > &x, double error[]) |
void | cartSumSquaredError (const std::vector< double > &x, double error[]) |
int | CartToJnt (const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist bounds=KDL::Twist::Zero(), const KDL::JntArray &q_desired=KDL::JntArray()) |
double | minJoints (const std::vector< double > &x, std::vector< double > &grad) |
NLOPT_IK (const KDL::Chain &chain, const KDL::JntArray &q_min, const KDL::JntArray &q_max, double maxtime=0.005, double eps=1e-3, OptType type=SumSq) | |
void | setMaxtime (double t) |
~NLOPT_IK () | |
Private Member Functions | |
void | abort () |
void | reset () |
Static Private Member Functions | |
static double | fRand (double min, double max) |
Private Attributes | |
bool | aborted |
std::vector< double > | best_x |
KDL::Twist | bounds |
const KDL::Chain | chain |
KDL::Frame | currentPose |
std::vector< double > | des |
double | eps |
KDL::ChainFkSolverPos_recursive | fksolver |
int | iter_counter |
std::vector< double > | lb |
double | maxtime |
nlopt::opt | opt |
int | progress |
KDL::Frame | targetPose |
OptType | TYPE |
std::vector< KDL::BasicJointType > | types |
std::vector< double > | ub |
KDL::Frame | x_out |
KDL::Frame | x_target |
KDL::Frame | y_out |
KDL::Frame | y_target |
KDL::Frame | z_target |
KDL::Frame | z_up |
Friends | |
class | TRAC_IK::TRAC_IK |
Definition at line 43 of file nlopt_ik.hpp.
NLOPT_IK::NLOPT_IK::NLOPT_IK | ( | const KDL::Chain & | chain, |
const KDL::JntArray & | q_min, | ||
const KDL::JntArray & | q_max, | ||
double | maxtime = 0.005 , |
||
double | eps = 1e-3 , |
||
OptType | type = SumSq |
||
) |
Definition at line 182 of file nlopt_ik.cpp.
NLOPT_IK::NLOPT_IK::~NLOPT_IK | ( | ) | [inline] |
Definition at line 49 of file nlopt_ik.hpp.
void NLOPT_IK::NLOPT_IK::abort | ( | ) | [inline, private] |
Definition at line 62 of file nlopt_ik.hpp.
void NLOPT_IK::NLOPT_IK::cartDQError | ( | const std::vector< double > & | x, |
double | error[] | ||
) |
Definition at line 358 of file nlopt_ik.cpp.
void NLOPT_IK::NLOPT_IK::cartL2NormError | ( | const std::vector< double > & | x, |
double | error[] | ||
) |
Definition at line 309 of file nlopt_ik.cpp.
void NLOPT_IK::NLOPT_IK::cartSumSquaredError | ( | const std::vector< double > & | x, |
double | error[] | ||
) |
Definition at line 261 of file nlopt_ik.cpp.
int NLOPT_IK::NLOPT_IK::CartToJnt | ( | const KDL::JntArray & | q_init, |
const KDL::Frame & | p_in, | ||
KDL::JntArray & | q_out, | ||
const KDL::Twist | bounds = KDL::Twist::Zero() , |
||
const KDL::JntArray & | q_desired = KDL::JntArray() |
||
) |
Definition at line 413 of file nlopt_ik.cpp.
static double NLOPT_IK::NLOPT_IK::fRand | ( | double | min, |
double | max | ||
) | [inline, static, private] |
Definition at line 105 of file nlopt_ik.hpp.
double NLOPT_IK::NLOPT_IK::minJoints | ( | const std::vector< double > & | x, |
std::vector< double > & | grad | ||
) |
Definition at line 241 of file nlopt_ik.cpp.
void NLOPT_IK::NLOPT_IK::reset | ( | ) | [inline, private] |
Definition at line 66 of file nlopt_ik.hpp.
void NLOPT_IK::NLOPT_IK::setMaxtime | ( | double | t | ) | [inline] |
Definition at line 58 of file nlopt_ik.hpp.
friend class TRAC_IK::TRAC_IK [friend] |
Definition at line 45 of file nlopt_ik.hpp.
bool NLOPT_IK::NLOPT_IK::aborted [private] |
Definition at line 101 of file nlopt_ik.hpp.
std::vector<double> NLOPT_IK::NLOPT_IK::best_x [private] |
Definition at line 99 of file nlopt_ik.hpp.
KDL::Twist NLOPT_IK::NLOPT_IK::bounds [private] |
Definition at line 103 of file nlopt_ik.hpp.
const KDL::Chain NLOPT_IK::NLOPT_IK::chain [private] |
Definition at line 74 of file nlopt_ik.hpp.
KDL::Frame NLOPT_IK::NLOPT_IK::currentPose [private] |
Definition at line 97 of file nlopt_ik.hpp.
std::vector<double> NLOPT_IK::NLOPT_IK::des [private] |
Definition at line 75 of file nlopt_ik.hpp.
double NLOPT_IK::NLOPT_IK::eps [private] |
Definition at line 81 of file nlopt_ik.hpp.
Definition at line 78 of file nlopt_ik.hpp.
int NLOPT_IK::NLOPT_IK::iter_counter [private] |
Definition at line 82 of file nlopt_ik.hpp.
std::vector<double> NLOPT_IK::NLOPT_IK::lb [private] |
Definition at line 71 of file nlopt_ik.hpp.
double NLOPT_IK::NLOPT_IK::maxtime [private] |
Definition at line 80 of file nlopt_ik.hpp.
nlopt::opt NLOPT_IK::NLOPT_IK::opt [private] |
Definition at line 95 of file nlopt_ik.hpp.
int NLOPT_IK::NLOPT_IK::progress [private] |
Definition at line 100 of file nlopt_ik.hpp.
KDL::Frame NLOPT_IK::NLOPT_IK::targetPose [private] |
Definition at line 85 of file nlopt_ik.hpp.
OptType NLOPT_IK::NLOPT_IK::TYPE [private] |
Definition at line 83 of file nlopt_ik.hpp.
std::vector<KDL::BasicJointType> NLOPT_IK::NLOPT_IK::types [private] |
Definition at line 93 of file nlopt_ik.hpp.
std::vector<double> NLOPT_IK::NLOPT_IK::ub [private] |
Definition at line 72 of file nlopt_ik.hpp.
KDL::Frame NLOPT_IK::NLOPT_IK::x_out [private] |
Definition at line 87 of file nlopt_ik.hpp.
KDL::Frame NLOPT_IK::NLOPT_IK::x_target [private] |
Definition at line 90 of file nlopt_ik.hpp.
KDL::Frame NLOPT_IK::NLOPT_IK::y_out [private] |
Definition at line 88 of file nlopt_ik.hpp.
KDL::Frame NLOPT_IK::NLOPT_IK::y_target [private] |
Definition at line 91 of file nlopt_ik.hpp.
KDL::Frame NLOPT_IK::NLOPT_IK::z_target [private] |
Definition at line 89 of file nlopt_ik.hpp.
KDL::Frame NLOPT_IK::NLOPT_IK::z_up [private] |
Definition at line 86 of file nlopt_ik.hpp.