Classes | Namespaces | Macros | Enumerations | Functions | Variables
prbt_manipulator_ikfast_moveit_plugin.cpp File Reference
#include <ros/ros.h>
#include <moveit/kinematics_base/kinematics_base.h>
#include <moveit/robot_state/robot_state.h>
#include <Eigen/Geometry>
#include <tf2_kdl/tf2_kdl.h>
#include <tf2_eigen/tf2_eigen.h>
#include <eigen_conversions/eigen_kdl.h>
#include "prbt_manipulator_ikfast_solver.cpp"
#include <pluginlib/class_list_macros.hpp>
Include dependency graph for prbt_manipulator_ikfast_moveit_plugin.cpp:

Go to the source code of this file.

Classes

struct  prbt_manipulator::CheckValue< T >
 
class  prbt_manipulator::IKFastKinematicsPlugin
 
class  prbt_manipulator::IKSolver
 
struct  prbt_manipulator::LimitObeyingSol
 

Namespaces

 prbt_manipulator
 

Macros

#define IKFAST_NO_MAIN
 

Enumerations

enum  prbt_manipulator::IkParameterizationType {
  prbt_manipulator::IKP_None = 0, prbt_manipulator::IKP_Transform6D = 0x67000001, prbt_manipulator::IKP_Rotation3D = 0x34000002, prbt_manipulator::IKP_Translation3D = 0x33000003,
  prbt_manipulator::IKP_Direction3D = 0x23000004, prbt_manipulator::IKP_Ray4D = 0x46000005, prbt_manipulator::IKP_Lookat3D = 0x23000006, prbt_manipulator::IKP_TranslationDirection5D = 0x56000007,
  prbt_manipulator::IKP_TranslationXY2D = 0x22000008, prbt_manipulator::IKP_TranslationXYOrientation3D = 0x33000009, prbt_manipulator::IKP_TranslationLocalGlobal6D = 0x3600000a, prbt_manipulator::IKP_TranslationXAxisAngle4D = 0x4400000b,
  prbt_manipulator::IKP_TranslationYAxisAngle4D = 0x4400000c, prbt_manipulator::IKP_TranslationZAxisAngle4D = 0x4400000d, prbt_manipulator::IKP_TranslationXAxisAngleZNorm4D = 0x4400000e, prbt_manipulator::IKP_TranslationYAxisAngleXNorm4D = 0x4400000f,
  prbt_manipulator::IKP_TranslationZAxisAngleYNorm4D = 0x44000010, prbt_manipulator::IKP_NumberOfParameterizations = 16, prbt_manipulator::IKP_VelocityDataBit, prbt_manipulator::IKP_Transform6DVelocity = IKP_Transform6D | IKP_VelocityDataBit,
  prbt_manipulator::IKP_Rotation3DVelocity = IKP_Rotation3D | IKP_VelocityDataBit, prbt_manipulator::IKP_Translation3DVelocity = IKP_Translation3D | IKP_VelocityDataBit, prbt_manipulator::IKP_Direction3DVelocity = IKP_Direction3D | IKP_VelocityDataBit, prbt_manipulator::IKP_Ray4DVelocity = IKP_Ray4D | IKP_VelocityDataBit,
  prbt_manipulator::IKP_Lookat3DVelocity = IKP_Lookat3D | IKP_VelocityDataBit, prbt_manipulator::IKP_TranslationDirection5DVelocity = IKP_TranslationDirection5D | IKP_VelocityDataBit, prbt_manipulator::IKP_TranslationXY2DVelocity = IKP_TranslationXY2D | IKP_VelocityDataBit, prbt_manipulator::IKP_TranslationXYOrientation3DVelocity = IKP_TranslationXYOrientation3D | IKP_VelocityDataBit,
  prbt_manipulator::IKP_TranslationLocalGlobal6DVelocity = IKP_TranslationLocalGlobal6D | IKP_VelocityDataBit, prbt_manipulator::IKP_TranslationXAxisAngle4DVelocity = IKP_TranslationXAxisAngle4D | IKP_VelocityDataBit, prbt_manipulator::IKP_TranslationYAxisAngle4DVelocity = IKP_TranslationYAxisAngle4D | IKP_VelocityDataBit, prbt_manipulator::IKP_TranslationZAxisAngle4DVelocity = IKP_TranslationZAxisAngle4D | IKP_VelocityDataBit,
  prbt_manipulator::IKP_TranslationXAxisAngleZNorm4DVelocity = IKP_TranslationXAxisAngleZNorm4D | IKP_VelocityDataBit, prbt_manipulator::IKP_TranslationYAxisAngleXNorm4DVelocity = IKP_TranslationYAxisAngleXNorm4D | IKP_VelocityDataBit, prbt_manipulator::IKP_TranslationZAxisAngleYNorm4DVelocity = IKP_TranslationZAxisAngleYNorm4D | IKP_VelocityDataBit, prbt_manipulator::IKP_UniqueIdMask = 0x0000ffff,
  prbt_manipulator::IKP_CustomDataBit = 0x00010000
}
 The types of inverse kinematics parameterizations supported. More...
 
enum  SEARCH_MODE { OPTIMIZE_FREE_JOINT = 1, OPTIMIZE_MAX_JOINT = 2 }
 Search modes for searchPositionIK(), see there. More...
 

Functions

IKFAST_API void prbt_manipulator::ComputeFk (const IkReal *j, IkReal *eetrans, IkReal *eerot)
 
IKFAST_API bool prbt_manipulator::ComputeIk (const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
 
IKFAST_API bool prbt_manipulator::ComputeIk2 (const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions, void *pOpenRAVEManip)
 
IKFAST_API int * prbt_manipulator::GetFreeParameters ()
 
IKFAST_API const char * prbt_manipulator::GetIkFastVersion ()
 
IKFAST_API int prbt_manipulator::GetIkRealSize ()
 
IKFAST_API int prbt_manipulator::GetIkType ()
 
IKFAST_API const char * prbt_manipulator::GetKinematicsHash ()
 
IKFAST_API int prbt_manipulator::GetNumFreeParameters ()
 
IKFAST_API int prbt_manipulator::GetNumJoints ()
 
float prbt_manipulator::IKabs (float f)
 
double prbt_manipulator::IKabs (double f)
 
float prbt_manipulator::IKacos (float f)
 
double prbt_manipulator::IKacos (double f)
 
float prbt_manipulator::IKasin (float f)
 
double prbt_manipulator::IKasin (double f)
 
float prbt_manipulator::IKatan2 (float fy, float fx)
 
double prbt_manipulator::IKatan2 (double fy, double fx)
 
float prbt_manipulator::IKatan2Simple (float fy, float fx)
 
double prbt_manipulator::IKatan2Simple (double fy, double fx)
 
template<typename T >
CheckValue< T > prbt_manipulator::IKatan2WithCheck (T fy, T fx, T epsilon)
 
float prbt_manipulator::IKcos (float f)
 
double prbt_manipulator::IKcos (double f)
 
 prbt_manipulator::IKFAST_COMPILE_ASSERT (IKFAST_VERSION==0x1000004a)
 
float prbt_manipulator::IKfmod (float x, float y)
 
double prbt_manipulator::IKfmod (double x, double y)
 
float prbt_manipulator::IKlog (float f)
 
double prbt_manipulator::IKlog (double f)
 
template<typename T >
CheckValue< T > prbt_manipulator::IKPowWithIntegerCheck (T f, int n)
 
float prbt_manipulator::IKsign (float f)
 
double prbt_manipulator::IKsign (double f)
 
float prbt_manipulator::IKsin (float f)
 
double prbt_manipulator::IKsin (double f)
 
float prbt_manipulator::IKsqr (float f)
 
double prbt_manipulator::IKsqr (double f)
 
float prbt_manipulator::IKsqrt (float f)
 
double prbt_manipulator::IKsqrt (double f)
 
float prbt_manipulator::IKtan (float f)
 
double prbt_manipulator::IKtan (double f)
 
 PLUGINLIB_EXPORT_CLASS (prbt_manipulator::IKFastKinematicsPlugin, kinematics::KinematicsBase)
 

Variables

const double LIMIT_TOLERANCE = .0000001
 

Macro Definition Documentation

#define IKFAST_NO_MAIN

Definition at line 65 of file prbt_manipulator_ikfast_moveit_plugin.cpp.

Enumeration Type Documentation

Search modes for searchPositionIK(), see there.

Enumerator
OPTIMIZE_FREE_JOINT 
OPTIMIZE_MAX_JOINT 

Definition at line 57 of file prbt_manipulator_ikfast_moveit_plugin.cpp.

Function Documentation

Variable Documentation

const double LIMIT_TOLERANCE = .0000001

Definition at line 55 of file prbt_manipulator_ikfast_moveit_plugin.cpp.



prbt_ikfast_manipulator_plugin
Author(s):
autogenerated on Mon May 3 2021 02:19:27