solvertest.hpp
Go to the documentation of this file.
1 #ifndef KDL_SOLVER_TEST_HPP
2 #define KDL_SOLVER_TEST_HPP
3 
4 #include <cppunit/extensions/HelperMacros.h>
5 
6 #include <chain.hpp>
13 #include <chainiksolverpos_nr.hpp>
14 #include <chainiksolverpos_lma.hpp>
16 #include <chainjnttojacsolver.hpp>
20 #include <chaindynparam.hpp>
24 
25 
26 using namespace KDL;
27 
28 class SolverTest : public CppUnit::TestFixture
29 {
30  CPPUNIT_TEST_SUITE( SolverTest);
31  CPPUNIT_TEST(FkPosAndJacTest );
32  CPPUNIT_TEST(FkVelAndJacTest );
33  CPPUNIT_TEST(FkVelAndIkVelTest );
34  CPPUNIT_TEST(FkPosAndIkPosTest );
35  CPPUNIT_TEST(VereshchaginTest );
36  CPPUNIT_TEST(IkSingularValueTest );
37  CPPUNIT_TEST(IkVelSolverWDLSTest );
38  CPPUNIT_TEST(FkPosVectTest );
39  CPPUNIT_TEST(FkVelVectTest );
40  CPPUNIT_TEST(FdSolverDevelopmentTest );
41  CPPUNIT_TEST(FdSolverConsistencyTest );
42  CPPUNIT_TEST(LDLdecompTest);
43  CPPUNIT_TEST(UpdateChainTest );
44  CPPUNIT_TEST_SUITE_END();
45 
46 public:
47  void setUp();
48  void tearDown();
49 
50  void FkPosAndJacTest();
51  void FkVelAndJacTest();
52  void FkVelAndIkVelTest();
53  void FkPosAndIkPosTest();
54  void VereshchaginTest();
55  void IkSingularValueTest() ;
56  void IkVelSolverWDLSTest();
57  void FkPosVectTest();
58  void FkVelVectTest();
59  void FdSolverDevelopmentTest();
60  void FdSolverConsistencyTest();
61  void LDLdecompTest();
62  void UpdateChainTest();
63 
64 private:
65 
66  Chain chain1, chain2, chain3, chain4, chaindyn, motomansia10, motomansia10dyn;
67 
68  void FkPosAndJacLocal(Chain& chain,ChainFkSolverPos& fksolverpos,ChainJntToJacSolver& jacsolver);
69  void FkVelAndJacLocal(Chain& chain, ChainFkSolverVel& fksolvervel, ChainJntToJacSolver& jacsolver);
70  void FkVelAndIkVelLocal(Chain& chain, ChainFkSolverVel& fksolvervel, ChainIkSolverVel& iksolvervel);
71  void FkPosAndIkPosLocal(Chain& chain,ChainFkSolverPos& fksolverpos, ChainIkSolverPos& iksolverpos);
72 
73 };
74 #endif
75 
This abstract class encapsulates the inverse position solver for a KDL::Chain.
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
Definition: chain.hpp:35
computing inverse position kinematics using Levenberg-Marquardt.
Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers. It should not be used outside of KDL.
Chain motomansia10dyn
Definition: solvertest.hpp:66
This abstract class encapsulates a solver for the forward velocity kinematics for a KDL::Chain...
This abstract class encapsulates the inverse velocity solver for a KDL::Chain.
This abstract class encapsulates a solver for the forward position kinematics for a KDL::Chain...


orocos_kdl
Author(s):
autogenerated on Sat Jun 15 2019 19:07:36