#include "ros/ros.h"
#include <kinematics_base/kinematics_base.h>
#include <geometry_msgs/PoseStamped.h>
#include <motion_planning_msgs/RobotState.h>
#include <kinematics_msgs/GetPositionIK.h>
#include <kinematics_msgs/GetPositionFK.h>
#include <kdl/tree.hpp>
#include <urdf/model.h>
#include <kdl_parser/kdl_parser.hpp>
#include "chainfksolver.hpp"
#include <iostream>
#include <iomanip>
#include <cmath>
#include <vector>
#include <sstream>
#include <map>
#include <stdexcept>
#include <list>
#include <boost/thread/mutex.hpp>
#include "tf/transform_datatypes.h"
#include "tf/exceptions.h"
#include "LinearMath/btTransform.h"
#include <boost/signals.hpp>
#include <string>
#include <ostream>
#include "ros/serialization.h"
#include "ros/builtin_message_traits.h"
#include "ros/message_operations.h"
#include "ros/message.h"
#include "ros/time.h"
#include "std_msgs/Header.h"
#include "geometry_msgs/Vector3.h"
#include <tf_conversions/tf_kdl.h>
#include <limits>
#include <algorithm>
#include <complex>
#include "Poco/Foundation.h"
#include "Poco/Exception.h"
#include <pthread.h>
#include <errno.h>
#include <set>
#include <typeinfo>
Go to the source code of this file.
Classes | |
class | cob3_arm_kinematics::ik_solver_base |
class | cob3_arm_kinematics::ikfast_solver< T > |
class | cob3_arm_kinematics::IKFastKinematicsPlugin |
class | cob3_arm_kinematics::cob3_2::IKSolution |
class | cob3_arm_kinematics::cob3_2::IKSolver |
struct | cob3_arm_kinematics::cob3_2::IKSolution::VARIABLE |
Namespaces | |
namespace | cob3_arm_kinematics |
namespace | cob3_arm_kinematics::cob3_2 |
Defines | |
#define | IK2PI ((IKReal)6.28318530717959) |
#define | IKFAST_ALIGNED16(x) x __attribute((aligned(16))) |
#define | IKFAST_API |
#define | IKFAST_ASSERT(b) { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } } |
#define | IKFAST_NO_MAIN |
#define | IKFAST_SINCOS_THRESH ((IKReal)0.000001) |
#define | IKPI ((IKReal)3.14159265358979) |
#define | IKPI_2 ((IKReal)1.57079632679490) |
Typedefs | |
typedef double | cob3_arm_kinematics::cob3_2::IKReal |
typedef double | IKReal |
Functions | |
void | cob3_arm_kinematics::cob3_2::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 | cob3_arm_kinematics::cob3_2::dgesv_ (const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info) |
void | cob3_arm_kinematics::cob3_2::dgetrf_ (const int *m, const int *n, double *a, const int *lda, int *ipiv, int *info) |
void | cob3_arm_kinematics::cob3_2::dgetri_ (const int *n, const double *a, const int *lda, int *ipiv, double *work, const int *lwork, int *info) |
void | cob3_arm_kinematics::cob3_2::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 void | cob3_arm_kinematics::cob3_2::fk (const IKReal *j, IKReal *eetrans, IKReal *eerot) |
IKFAST_API int * | cob3_arm_kinematics::cob3_2::getFreeParameters () |
IKFAST_API int | cob3_arm_kinematics::cob3_2::getIKRealSize () |
IKFAST_API int | cob3_arm_kinematics::cob3_2::getIKType () |
IKFAST_API const char * | cob3_arm_kinematics::cob3_2::getKinematicsHash () |
IKFAST_API int | cob3_arm_kinematics::cob3_2::getNumFreeParameters () |
IKFAST_API int | cob3_arm_kinematics::cob3_2::getNumJoints () |
IKFAST_API bool | cob3_arm_kinematics::cob3_2::ik (const IKReal *eetrans, const IKReal *eerot, const IKReal *pfree, std::vector< IKSolution > &vsolutions) |
double | cob3_arm_kinematics::cob3_2::IKabs (double f) |
float | cob3_arm_kinematics::cob3_2::IKabs (float f) |
double | cob3_arm_kinematics::cob3_2::IKacos (double f) |
float | cob3_arm_kinematics::cob3_2::IKacos (float f) |
double | cob3_arm_kinematics::cob3_2::IKasin (double f) |
float | cob3_arm_kinematics::cob3_2::IKasin (float f) |
double | cob3_arm_kinematics::cob3_2::IKatan2 (double fy, double fx) |
float | cob3_arm_kinematics::cob3_2::IKatan2 (float fy, float fx) |
double | cob3_arm_kinematics::cob3_2::IKcos (double f) |
float | cob3_arm_kinematics::cob3_2::IKcos (float f) |
float | cob3_arm_kinematics::cob3_2::IKfmod (double x, double y) |
float | cob3_arm_kinematics::cob3_2::IKfmod (float x, float y) |
double | cob3_arm_kinematics::cob3_2::IKlog (double f) |
float | cob3_arm_kinematics::cob3_2::IKlog (float f) |
double | cob3_arm_kinematics::cob3_2::IKsign (double f) |
float | cob3_arm_kinematics::cob3_2::IKsign (float f) |
double | cob3_arm_kinematics::cob3_2::IKsin (double f) |
float | cob3_arm_kinematics::cob3_2::IKsin (float f) |
double | cob3_arm_kinematics::cob3_2::IKsqrt (double f) |
float | cob3_arm_kinematics::cob3_2::IKsqrt (float f) |
double | cob3_arm_kinematics::cob3_2::IKtan (double f) |
float | cob3_arm_kinematics::cob3_2::IKtan (float f) |
void | cob3_arm_kinematics::cob3_2::zgetrf_ (const int *m, const int *n, std::complex< double > *a, const int *lda, int *ipiv, int *info) |
#define IK2PI ((IKReal)6.28318530717959) |
Definition at line 55 of file ikfast_kinematics_plugin.cpp.
#define IKFAST_ALIGNED16 | ( | x | ) | x __attribute((aligned(16))) |
Definition at line 52 of file ikfast_kinematics_plugin.cpp.
#define IKFAST_API |
Definition at line 73 of file ikfast_kinematics_plugin.cpp.
#define IKFAST_ASSERT | ( | b | ) | { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } } |
autogenerated analytical inverse kinematics code from ikfast program part of OpenRAVE
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 41 generated on 2011-06-20 18:42:47.666026 To compile with gcc: gcc -lstdc++ ik.cpp To compile without any main function as a shared object: gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -shared -Wl,-soname,ik.so -o ik.so ik.cpp
Definition at line 45 of file ikfast_kinematics_plugin.cpp.
#define IKFAST_NO_MAIN |
Definition at line 12 of file ikfast_kinematics_plugin.cpp.
#define IKFAST_SINCOS_THRESH ((IKReal)0.000001) |
Definition at line 143 of file ikfast_kinematics_plugin.cpp.
#define IKPI ((IKReal)3.14159265358979) |
Definition at line 56 of file ikfast_kinematics_plugin.cpp.
#define IKPI_2 ((IKReal)1.57079632679490) |
Definition at line 57 of file ikfast_kinematics_plugin.cpp.
typedef double IKReal |
Definition at line 16 of file ikfast_kinematics_plugin.cpp.