Macros | Functions | Variables
test_kinematics_as_service.cpp File Reference
#include <map>
#include <string>
#include <vector>
#include <math.h>
#include <pluginlib/class_loader.h>
#include <hand_kinematics/hand_kinematics_plugin.h>
#include <gtest/gtest.h>
#include <sr_utilities/sr_math_utils.hpp>
Include dependency graph for test_kinematics_as_service.cpp:

Go to the source code of this file.

Macros

#define DEG2RAD   (M_PI / 180.0)
 
#define IK_NEAR   0.001
 
#define MAX_DELTA   0.01
 
#define RAD2DEG   (180.0 / M_PI)
 

Functions

int main (int argc, char **argv)
 
double rand_range (double min_n, double max_n)
 
void random_test_finger_fkik (std::string PREFIX, std::string prefix, int n_tests, bool verbose=false)
 
 TEST (FKIK, first_finger)
 
 TEST (FKIK, middle_finger)
 
 TEST (FKIK, ring_finger)
 
 TEST (FKIK, little_finger)
 
 TEST (FKIK, thumb)
 

Variables

ros::NodeHandlenh
 
bool verbose
 

Macro Definition Documentation

#define DEG2RAD   (M_PI / 180.0)

Definition at line 62 of file test_kinematics_as_service.cpp.

#define IK_NEAR   0.001

Definition at line 67 of file test_kinematics_as_service.cpp.

#define MAX_DELTA   0.01

Definition at line 66 of file test_kinematics_as_service.cpp.

#define RAD2DEG   (180.0 / M_PI)

Definition at line 63 of file test_kinematics_as_service.cpp.

Function Documentation

int main ( int  argc,
char **  argv 
)

interface and selftest (fk==ik) of the forward/inverse kinematics solver for the Shadow hand with J1/J2 finger-couplings, for the Shadow hand thumb, and support for little-finger palm-arch (LFJ5). The solvers start at the "palm" frame and work towards idealized "fftip" "mftip" "rftip" "lftip" and "thtip" frames, which are approximations to the core of the fingertips (assuming spherical fingertip shape). Actual contact points on the fingertips are therefore about one-half finger radius outside of the positions specified by the *tip frames.

Definition at line 346 of file test_kinematics_as_service.cpp.

double rand_range ( double  min_n,
double  max_n 
)

Definition at line 72 of file test_kinematics_as_service.cpp.

void random_test_finger_fkik ( std::string  PREFIX,
std::string  prefix,
int  n_tests,
bool  verbose = false 
)

Definition at line 77 of file test_kinematics_as_service.cpp.

TEST ( FKIK  ,
first_finger   
)

Definition at line 309 of file test_kinematics_as_service.cpp.

TEST ( FKIK  ,
middle_finger   
)

Definition at line 314 of file test_kinematics_as_service.cpp.

TEST ( FKIK  ,
ring_finger   
)

Definition at line 319 of file test_kinematics_as_service.cpp.

TEST ( FKIK  ,
little_finger   
)

Definition at line 324 of file test_kinematics_as_service.cpp.

TEST ( FKIK  ,
thumb   
)

Definition at line 329 of file test_kinematics_as_service.cpp.

Variable Documentation

Definition at line 69 of file test_kinematics_as_service.cpp.

bool verbose

Definition at line 70 of file test_kinematics_as_service.cpp.



hand_kinematics
Author(s): Juan Antonio Corrales Ramon (UPMC),, Guillaume Walck (CITEC)
autogenerated on Wed Oct 14 2020 04:05:07