Classes | |
class | CDh |
Denavit Hartenberg Link information. More... | |
class | CFrame |
Robot types with implemented inverse kinematics. More... | |
class | CFrameCombination |
Frame in cartesian space. More... | |
class | CFrameContainer |
class | CFrameInterface |
class | CFrameReference |
Frame in cartesian space. More... | |
class | CKinematicChain |
Kinematic chain. More... | |
class | CKinematicChainContainer |
Kinematic Robot Model. More... | |
class | CMathLib |
Mathematical functions. More... | |
class | CMatrix |
Homogenous matrix. More... | |
class | COptimizer |
class | COptimizerGnuplot |
class | COptimizerIv |
class | COptimizerResult |
class | COptimizerRos |
class | CVec |
Homogenous vector. More... | |
class | OptimizerContainer |
class | OptimizerGoal |
class | OptimizerGoalGlobal |
class | OptimizerGoalGlobalOrientation |
class | OptimizerGoalGlobalPosition |
class | OptimizerGoalOrientation |
class | OptimizerGoalPosition |
class | ValueSetter |
Functions | |
void | arrayToMatrix (CMatrix &matrix, std::vector< double > &values) |
template<typename T > | |
std::string | arrayToString (std::vector< T > &array) |
std::string | boolToString (bool value) |
void | calculateTransformationFromPlane (CVec &plane, CMatrix &transformation) |
std::string | combineStrings (std::vector< std::string > &input, std::string delimiter=" ") |
template<typename T , typename S > | |
bool | comparePairs (const std::pair< T, S > &first, const std::pair< T, S > &second) |
template<typename T , typename S > | |
bool | comparePairsVector (const std::pair< T, S > &first, const std::pair< T, S > &second) |
void | convertMatrix (CMatrix &from, double(*R)[3], double *T) |
void | convertMatrix (double(*R)[3], double *T, CMatrix &to) |
unsigned long | fac (unsigned int value) |
void | getConvexHullXY (std::vector< CVec > &points, std::vector< CVec > &hull) |
int | getDirectoryFiles (std::string dir, std::vector< std::string > &files, bool appendDir=false) |
double | getGaussian (double value, double mean, double std) |
double | getGaussianProb (double mean, double std) |
double | getGaussianWithoutNormalization (double value, double mean, double std) |
double | getLogisticProb (double alpha, double beta) |
void | getMeanFromVectors (std::vector< std::vector< double > > &values, std::vector< double > &mean) |
double | getSigmoid (double value, double offset, double factor) |
unsigned long | getTickCount () |
double | getUniform () |
int | getUniform (int min, int max) |
template<typename T > | |
bool | inRange (std::vector< T > &array, T min, T max) |
template<typename T > | |
bool | isIncluded (std::vector< T > &array, T &value) |
void | matrixToArray (const CMatrix &matrix, std::vector< double > &values) |
void | matrixToVector (const CMatrix &matrix, std::vector< double > &values) |
void | matrixToVector6 (const CMatrix &matrix, double *values) |
void | orientation2scaledAxis (CMatrix &matrix, CVec &axis) |
void | orientation2scaledAxis (CMatrix &matrix, std::vector< double > &axis) |
std::string | printToString (const char *format,...) |
boost::variate_generator< boost::mt19937 &, boost::uniform_01< double > > | pRngUniform01 (pRngMt19937, pRngDist) |
int | rnd (PRECISION value) |
Rounds a value. More... | |
void | rosenbrock (int n, double *x, double *bl, double *bu, double bigbnd, int maxiter, double eps, int verbose, void obj(int, double *, double *, void *), void *extraparams) |
int | roundToInt (double value) |
void | scaledAxis2Orientation (CVec &axis, CMatrix &matrix) |
void | scaledAxis2Orientation (std::vector< double > &axis, CMatrix &matrix) |
void | setUniformSeed (unsigned int seed) |
double | sign (double value) |
void | simulatedannealing (int n, double *x, double *bl, double *bu, double bigbnd, int maxiter, double eps, int verbose, void obj(int, double *, double *, void *), void *extraparams) |
bool | stringEndsWith (std::string text, std::string end, std::string sep="_") |
bool | stringStartsWith (std::string text, std::string end, std::string sep="_") |
std::string | strreplace (const std::string &stringSearchString, const std::string &stringReplaceString, std::string stringStringToReplace) |
void | strreplace (char *text, char what= '.', char with= ',') |
void | strreplaceWithCondition (const std::string &stringSearchString, const std::string &stringReplaceString, std::string &stringStringToReplace, std::string condition="") |
void | strToArray (std::string text, std::vector< double > &result, std::string delimiter=" ") |
double | strToDouble (const char *text, double value=0.0) |
void | strtokenize (const std::string &str, std::vector< std::string > &tokens, const std::string &delimiters) |
std::string | strtrim (std::string &s, const std::string &drop=" ") |
double | vectorlength (std::vector< double > &v) |
void | vectorToMatrix (CMatrix &matrix, const std::vector< double > &values) |
void | vectorToMatrix6 (CMatrix &matrix, const double *values) |
std::string | waitForReturn (std::string msg="Press any key.\n") |
Variables | |
boost::uniform_01< double > | pRngDist |
boost::mt19937 | pRngMt19937 |
boost::variate_generator< boost::mt19937 &, boost::uniform_01< double > > | pRngUniform01 |
char | rosenbrock_version [] = "rosenbrock 0.99" |
Copyright (c) 2016, Aumann Florian, Heller Florian, Jäkel Rainer, Wittenbeck Valerij All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
void robotLibPbD::arrayToMatrix | ( | CMatrix & | matrix, |
std::vector< double > & | values | ||
) |
std::string robotLibPbD::arrayToString | ( | std::vector< T > & | array | ) |
Definition at line 1011 of file vecmath.cpp.
std::string robotLibPbD::combineStrings | ( | std::vector< std::string > & | input, |
std::string | delimiter = " " |
||
) |
bool robotLibPbD::comparePairs | ( | const std::pair< T, S > & | first, |
const std::pair< T, S > & | second | ||
) |
bool robotLibPbD::comparePairsVector | ( | const std::pair< T, S > & | first, |
const std::pair< T, S > & | second | ||
) |
void robotLibPbD::convertMatrix | ( | CMatrix & | from, |
double(*) | R[3], | ||
double * | T | ||
) |
Definition at line 1119 of file vecmath.cpp.
void robotLibPbD::convertMatrix | ( | double(*) | R[3], |
double * | T, | ||
CMatrix & | to | ||
) |
Definition at line 1100 of file vecmath.cpp.
unsigned long robotLibPbD::fac | ( | unsigned int | value | ) |
int robotLibPbD::getDirectoryFiles | ( | std::string | dir, |
std::vector< std::string > & | files, | ||
bool | appendDir = false |
||
) |
double robotLibPbD::getGaussian | ( | double | value, |
double | mean, | ||
double | std | ||
) |
Definition at line 1071 of file vecmath.cpp.
|
inline |
double robotLibPbD::getGaussianWithoutNormalization | ( | double | value, |
double | mean, | ||
double | std | ||
) |
Definition at line 1078 of file vecmath.cpp.
double robotLibPbD::getLogisticProb | ( | double | alpha, |
double | beta | ||
) |
Definition at line 1085 of file vecmath.cpp.
void robotLibPbD::getMeanFromVectors | ( | std::vector< std::vector< double > > & | values, |
std::vector< double > & | mean | ||
) |
Definition at line 1139 of file vecmath.cpp.
double robotLibPbD::getSigmoid | ( | double | value, |
double | offset, | ||
double | factor | ||
) |
Definition at line 1066 of file vecmath.cpp.
bool robotLibPbD::inRange | ( | std::vector< T > & | array, |
T | min, | ||
T | max | ||
) |
bool robotLibPbD::isIncluded | ( | std::vector< T > & | array, |
T & | value | ||
) |
void robotLibPbD::matrixToArray | ( | const CMatrix & | matrix, |
std::vector< double > & | values | ||
) |
void robotLibPbD::matrixToVector | ( | const CMatrix & | matrix, |
std::vector< double > & | values | ||
) |
void robotLibPbD::matrixToVector6 | ( | const CMatrix & | matrix, |
double * | values | ||
) |
Definition at line 1162 of file vecmath.cpp.
void robotLibPbD::orientation2scaledAxis | ( | CMatrix & | matrix, |
std::vector< double > & | axis | ||
) |
Definition at line 1169 of file vecmath.cpp.
std::string robotLibPbD::printToString | ( | const char * | format, |
... | |||
) |
boost::variate_generator<boost::mt19937&, boost::uniform_01<double> > robotLibPbD::pRngUniform01 | ( | pRngMt19937 | , |
pRngDist | |||
) |
int robotLibPbD::rnd | ( | PRECISION | value | ) |
Rounds a value.
Definition at line 308 of file vecmath.cpp.
void robotLibPbD::rosenbrock | ( | int | n, |
double * | x, | ||
double * | bl, | ||
double * | bu, | ||
double | bigbnd, | ||
int | maxiter, | ||
double | eps, | ||
int | verbose, | ||
void | objint, double *, double *, void *, | ||
void * | extraparams | ||
) |
Definition at line 871 of file vecmath.cpp.
int robotLibPbD::roundToInt | ( | double | value | ) |
Definition at line 1180 of file vecmath.cpp.
void robotLibPbD::scaledAxis2Orientation | ( | std::vector< double > & | axis, |
CMatrix & | matrix | ||
) |
Definition at line 1192 of file vecmath.cpp.
void robotLibPbD::setUniformSeed | ( | unsigned int | seed | ) |
Definition at line 1059 of file vecmath.cpp.
double robotLibPbD::sign | ( | double | value | ) |
void robotLibPbD::simulatedannealing | ( | int | n, |
double * | x, | ||
double * | bl, | ||
double * | bu, | ||
double | bigbnd, | ||
int | maxiter, | ||
double | eps, | ||
int | verbose, | ||
void | objint, double *, double *, void *, | ||
void * | extraparams | ||
) |
Definition at line 804 of file vecmath.cpp.
bool robotLibPbD::stringEndsWith | ( | std::string | text, |
std::string | end, | ||
std::string | sep = "_" |
||
) |
bool robotLibPbD::stringStartsWith | ( | std::string | text, |
std::string | end, | ||
std::string | sep = "_" |
||
) |
std::string robotLibPbD::strreplace | ( | const std::string & | stringSearchString, |
const std::string & | stringReplaceString, | ||
std::string | stringStringToReplace | ||
) |
void robotLibPbD::strreplace | ( | char * | text, |
char | what = '.' , |
||
char | with = ',' |
||
) |
void robotLibPbD::strreplaceWithCondition | ( | const std::string & | stringSearchString, |
const std::string & | stringReplaceString, | ||
std::string & | stringStringToReplace, | ||
std::string | condition = "" |
||
) |
void robotLibPbD::strToArray | ( | std::string | text, |
std::vector< double > & | result, | ||
std::string | delimiter = " " |
||
) |
double robotLibPbD::strToDouble | ( | const char * | text, |
double | value = 0.0 |
||
) |
void robotLibPbD::strtokenize | ( | const std::string & | str, |
std::vector< std::string > & | tokens, | ||
const std::string & | delimiters | ||
) |
std::string robotLibPbD::strtrim | ( | std::string & | s, |
const std::string & | drop = " " |
||
) |
double robotLibPbD::vectorlength | ( | std::vector< double > & | v | ) |
Definition at line 791 of file vecmath.cpp.
void robotLibPbD::vectorToMatrix | ( | CMatrix & | matrix, |
const std::vector< double > & | values | ||
) |
void robotLibPbD::vectorToMatrix6 | ( | CMatrix & | matrix, |
const double * | values | ||
) |
std::string robotLibPbD::waitForReturn | ( | std::string | msg = "Press any key.\n" | ) |
boost::uniform_01< double > robotLibPbD::pRngDist |
Definition at line 45 of file vecmath.cpp.
boost::mt19937 robotLibPbD::pRngMt19937 |
Definition at line 44 of file vecmath.cpp.
boost::variate_generator<boost::mt19937&, boost::uniform_01<double> > robotLibPbD::pRngUniform01 |
char robotLibPbD::rosenbrock_version[] = "rosenbrock 0.99" |
Definition at line 799 of file vecmath.cpp.