Classes | Macros | Functions
abb_irb2400_ikfast_solver.hpp File Reference
#include <tesseract_common/macros.h>
#include <tesseract_kinematics/ikfast/external/ikfast.h>
#include <cmath>
#include <vector>
#include <limits>
#include <complex>
#include <stdexcept>
#include <iostream>
#include <cstddef>
#include <memory>
Include dependency graph for abb_irb2400_ikfast_solver.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  IKSolver
 

Macros

#define __PRETTY_FUNCTION__   __func__
 
#define IK2PI   ((IkReal)6.28318530717959)
 
#define IKFAST_ALIGNED16(x)   x __attribute((aligned(16)))
 
#define IKFAST_ASSERT(b)
 
#define IKFAST_ATAN2_MAGTHRESH   ((IkReal)2e-6)
 
#define IKFAST_COMPILE_ASSERT(x)   extern int __dummy[(int)(x)]
 
#define IKFAST_NO_MAIN
 
#define IKFAST_SINCOS_THRESH   ((IkReal)0.000001)
 
#define IKFAST_SOLUTION_THRESH   ((IkReal)1e-6)
 
#define IKFAST_STRINGIZE(s)   IKFAST_STRINGIZE2(s)
 
#define IKFAST_STRINGIZE2(s)   #s
 
#define IKPI   ((IkReal)3.14159265358979)
 
#define IKPI_2   ((IkReal)1.57079632679490)
 

Functions

IKFAST_API void ComputeFk (const IkReal *j, IkReal *eetrans, IkReal *eerot)
 
IKFAST_API bool ComputeIk (const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
 
void dgeev_ (const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi, double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info)
 
void dgesv_ (const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info)
 
void dgetrf_ (const int *m, const int *n, double *a, const int *lda, int *ipiv, int *info)
 
void dgetri_ (const int *n, const double *a, const int *lda, int *ipiv, double *work, const int *lwork, int *info)
 
void dgetrs_ (const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info)
 
IKFAST_API int * GetFreeParameters ()
 
const IKFAST_API char * GetIkFastVersion ()
 
IKFAST_API int GetIkRealSize ()
 
IKFAST_API int GetIkType ()
 
const IKFAST_API char * GetKinematicsHash ()
 
IKFAST_API int GetNumFreeParameters ()
 
IKFAST_API int GetNumJoints ()
 
double IKabs (double f)
 
float IKabs (float f)
 
double IKacos (double f)
 
float IKacos (float f)
 
double IKasin (double f)
 
float IKasin (float f)
 
double IKatan2 (double fy, double fx)
 
float IKatan2 (float fy, float fx)
 
double IKcos (double f)
 
float IKcos (float f)
 
 IKFAST_COMPILE_ASSERT (IKFAST_VERSION==61)
 
double IKfmod (double x, double y)
 
float IKfmod (float x, float y)
 
double IKlog (double f)
 
float IKlog (float f)
 
double IKsign (double f)
 
float IKsign (float f)
 
double IKsin (double f)
 
float IKsin (float f)
 
double IKsqr (double f)
 
float IKsqr (float f)
 
double IKsqrt (double f)
 
float IKsqrt (float f)
 
double IKtan (double f)
 
float IKtan (float f)
 
void zgetrf_ (const int *m, const int *n, std::complex< double > *a, const int *lda, int *ipiv, int *info)
 

Macro Definition Documentation

◆ __PRETTY_FUNCTION__

#define __PRETTY_FUNCTION__   __func__

Definition at line 55 of file abb_irb2400_ikfast_solver.hpp.

◆ IK2PI

#define IK2PI   ((IkReal)6.28318530717959)

Definition at line 77 of file abb_irb2400_ikfast_solver.hpp.

◆ IKFAST_ALIGNED16

#define IKFAST_ALIGNED16 (   x)    x __attribute((aligned(16)))

Definition at line 74 of file abb_irb2400_ikfast_solver.hpp.

◆ IKFAST_ASSERT

#define IKFAST_ASSERT (   b)
Value:
{ \
if (!(b)) \
{ \
std::stringstream ss; \
ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " << __PRETTY_FUNCTION__ << ": Assertion '" \
<< #b << "' failed"; \
throw std::runtime_error(ss.str()); \
} \
}

Definition at line 58 of file abb_irb2400_ikfast_solver.hpp.

◆ IKFAST_ATAN2_MAGTHRESH

#define IKFAST_ATAN2_MAGTHRESH   ((IkReal)2e-6)

Definition at line 141 of file abb_irb2400_ikfast_solver.hpp.

◆ IKFAST_COMPILE_ASSERT

#define IKFAST_COMPILE_ASSERT (   x)    extern int __dummy[(int)(x)]

Definition at line 31 of file abb_irb2400_ikfast_solver.hpp.

◆ IKFAST_NO_MAIN

#define IKFAST_NO_MAIN

autogenerated analytical inverse kinematics code from ikfast program part of OpenRAVE

Author
Rosen Diankov

Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

ikfast version 61 generated on 2015-05-22 14:09:58.982511 To compile with gcc: gcc -lstdc++ ik.cpp To compile without any main function as a shared object (might need -llapack): gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp

Definition at line 25 of file abb_irb2400_ikfast_solver.hpp.

◆ IKFAST_SINCOS_THRESH

#define IKFAST_SINCOS_THRESH   ((IkReal)0.000001)

Definition at line 136 of file abb_irb2400_ikfast_solver.hpp.

◆ IKFAST_SOLUTION_THRESH

#define IKFAST_SOLUTION_THRESH   ((IkReal)1e-6)

Definition at line 146 of file abb_irb2400_ikfast_solver.hpp.

◆ IKFAST_STRINGIZE

#define IKFAST_STRINGIZE (   s)    IKFAST_STRINGIZE2(s)

Definition at line 40 of file abb_irb2400_ikfast_solver.hpp.

◆ IKFAST_STRINGIZE2

#define IKFAST_STRINGIZE2 (   s)    #s

Definition at line 39 of file abb_irb2400_ikfast_solver.hpp.

◆ IKPI

#define IKPI   ((IkReal)3.14159265358979)

Definition at line 78 of file abb_irb2400_ikfast_solver.hpp.

◆ IKPI_2

#define IKPI_2   ((IkReal)1.57079632679490)

Definition at line 79 of file abb_irb2400_ikfast_solver.hpp.

Function Documentation

◆ ComputeFk()

IKFAST_API void ComputeFk ( const IkReal *  j,
IkReal *  eetrans,
IkReal *  eerot 
)

solves the forward kinematics equations.

Parameters
pfreeis an array specifying the free joints of the chain.

Definition at line 283 of file abb_irb2400_ikfast_solver.hpp.

◆ ComputeIk()

IKFAST_API bool ComputeIk ( const IkReal *  eetrans,
const IkReal *  eerot,
const IkReal *  pfree,
IkSolutionListBase< IkReal > &  solutions 
)

solves the inverse kinematics equations.

Parameters
pfreeis an array specifying the free joints of the chain.

Definition at line 3209 of file abb_irb2400_ikfast_solver.hpp.

◆ dgeev_()

void dgeev_ ( const char *  jobvl,
const char *  jobvr,
const int *  n,
double *  a,
const int *  lda,
double *  wr,
double *  wi,
double *  vl,
const int *  ldvl,
double *  vr,
const int *  ldvr,
double *  work,
const int *  lwork,
int *  info 
)

◆ dgesv_()

void dgesv_ ( const int *  n,
const int *  nrhs,
double *  a,
const int *  lda,
int *  ipiv,
double *  b,
const int *  ldb,
int *  info 
)

◆ dgetrf_()

void dgetrf_ ( const int *  m,
const int *  n,
double *  a,
const int *  lda,
int *  ipiv,
int *  info 
)

◆ dgetri_()

void dgetri_ ( const int *  n,
const double *  a,
const int *  lda,
int *  ipiv,
double *  work,
const int *  lwork,
int *  info 
)

◆ dgetrs_()

void dgetrs_ ( const char *  trans,
const int *  n,
const int *  nrhs,
double *  a,
const int *  lda,
int *  ipiv,
double *  b,
const int *  ldb,
int *  info 
)

◆ GetFreeParameters()

IKFAST_API int* GetFreeParameters ( )

Definition at line 379 of file abb_irb2400_ikfast_solver.hpp.

◆ GetIkFastVersion()

const IKFAST_API char* GetIkFastVersion ( )

Definition at line 3220 of file abb_irb2400_ikfast_solver.hpp.

◆ GetIkRealSize()

IKFAST_API int GetIkRealSize ( )

Definition at line 382 of file abb_irb2400_ikfast_solver.hpp.

◆ GetIkType()

IKFAST_API int GetIkType ( )

Definition at line 384 of file abb_irb2400_ikfast_solver.hpp.

◆ GetKinematicsHash()

const IKFAST_API char* GetKinematicsHash ( )

Definition at line 3215 of file abb_irb2400_ikfast_solver.hpp.

◆ GetNumFreeParameters()

IKFAST_API int GetNumFreeParameters ( )

Definition at line 378 of file abb_irb2400_ikfast_solver.hpp.

◆ GetNumJoints()

IKFAST_API int GetNumJoints ( )

Definition at line 380 of file abb_irb2400_ikfast_solver.hpp.

◆ IKabs() [1/2]

double IKabs ( double  f)
inline

Definition at line 126 of file abb_irb2400_ikfast_solver.hpp.

◆ IKabs() [2/2]

float IKabs ( float  f)
inline

Definition at line 125 of file abb_irb2400_ikfast_solver.hpp.

◆ IKacos() [1/2]

double IKacos ( double  f)
inline

Definition at line 200 of file abb_irb2400_ikfast_solver.hpp.

◆ IKacos() [2/2]

float IKacos ( float  f)
inline

Definition at line 190 of file abb_irb2400_ikfast_solver.hpp.

◆ IKasin() [1/2]

double IKasin ( double  f)
inline

Definition at line 159 of file abb_irb2400_ikfast_solver.hpp.

◆ IKasin() [2/2]

float IKasin ( float  f)
inline

Definition at line 149 of file abb_irb2400_ikfast_solver.hpp.

◆ IKatan2() [1/2]

double IKatan2 ( double  fy,
double  fx 
)
inline

Definition at line 241 of file abb_irb2400_ikfast_solver.hpp.

◆ IKatan2() [2/2]

float IKatan2 ( float  fy,
float  fx 
)
inline

Definition at line 228 of file abb_irb2400_ikfast_solver.hpp.

◆ IKcos() [1/2]

double IKcos ( double  f)
inline

Definition at line 213 of file abb_irb2400_ikfast_solver.hpp.

◆ IKcos() [2/2]

float IKcos ( float  f)
inline

Definition at line 212 of file abb_irb2400_ikfast_solver.hpp.

◆ IKFAST_COMPILE_ASSERT()

IKFAST_COMPILE_ASSERT ( IKFAST_VERSION  = =61)

◆ IKfmod() [1/2]

double IKfmod ( double  x,
double  y 
)
inline

Definition at line 181 of file abb_irb2400_ikfast_solver.hpp.

◆ IKfmod() [2/2]

float IKfmod ( float  x,
float  y 
)
inline

Definition at line 171 of file abb_irb2400_ikfast_solver.hpp.

◆ IKlog() [1/2]

double IKlog ( double  f)
inline

Definition at line 132 of file abb_irb2400_ikfast_solver.hpp.

◆ IKlog() [2/2]

float IKlog ( float  f)
inline

Definition at line 131 of file abb_irb2400_ikfast_solver.hpp.

◆ IKsign() [1/2]

double IKsign ( double  f)
inline

Definition at line 268 of file abb_irb2400_ikfast_solver.hpp.

◆ IKsign() [2/2]

float IKsign ( float  f)
inline

Definition at line 255 of file abb_irb2400_ikfast_solver.hpp.

◆ IKsin() [1/2]

double IKsin ( double  f)
inline

Definition at line 211 of file abb_irb2400_ikfast_solver.hpp.

◆ IKsin() [2/2]

float IKsin ( float  f)
inline

Definition at line 210 of file abb_irb2400_ikfast_solver.hpp.

◆ IKsqr() [1/2]

double IKsqr ( double  f)
inline

Definition at line 129 of file abb_irb2400_ikfast_solver.hpp.

◆ IKsqr() [2/2]

float IKsqr ( float  f)
inline

Definition at line 128 of file abb_irb2400_ikfast_solver.hpp.

◆ IKsqrt() [1/2]

double IKsqrt ( double  f)
inline

Definition at line 222 of file abb_irb2400_ikfast_solver.hpp.

◆ IKsqrt() [2/2]

float IKsqrt ( float  f)
inline

Definition at line 216 of file abb_irb2400_ikfast_solver.hpp.

◆ IKtan() [1/2]

double IKtan ( double  f)
inline

Definition at line 215 of file abb_irb2400_ikfast_solver.hpp.

◆ IKtan() [2/2]

float IKtan ( float  f)
inline

Definition at line 214 of file abb_irb2400_ikfast_solver.hpp.

◆ zgetrf_()

void zgetrf_ ( const int *  m,
const int *  n,
std::complex< double > *  a,
const int *  lda,
int *  ipiv,
int *  info 
)
__PRETTY_FUNCTION__
#define __PRETTY_FUNCTION__
Definition: abb_irb2400_ikfast_solver.hpp:55


tesseract_kinematics
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:14