Public Member Functions | Private Member Functions | Private Attributes | List of all members
SolverTest Class Reference

#include <solvertest.hpp>

Inheritance diagram for SolverTest:
Inheritance graph
[legend]

Public Member Functions

void FdAndVereshchaginSolversConsistencyTest ()
 
void FdSolverConsistencyTest ()
 
void FdSolverDevelopmentTest ()
 
void FkPosAndIkPosTest ()
 
void FkPosAndJacTest ()
 
void FkPosVectTest ()
 
void FkVelAndIkVelTest ()
 
void FkVelAndJacTest ()
 
void FkVelVectTest ()
 
void IkSingularValueTest ()
 
void IkVelSolverWDLSTest ()
 
void LDLdecompTest ()
 
void setUp ()
 
void tearDown ()
 
void UpdateChainTest ()
 
void VereshchaginTest ()
 

Private Member Functions

 CPPUNIT_TEST (FkPosAndJacTest)
 
 CPPUNIT_TEST (FkVelAndJacTest)
 
 CPPUNIT_TEST (FkVelAndIkVelTest)
 
 CPPUNIT_TEST (FkPosAndIkPosTest)
 
 CPPUNIT_TEST (VereshchaginTest)
 
 CPPUNIT_TEST (IkSingularValueTest)
 
 CPPUNIT_TEST (IkVelSolverWDLSTest)
 
 CPPUNIT_TEST (FkPosVectTest)
 
 CPPUNIT_TEST (FkVelVectTest)
 
 CPPUNIT_TEST (FdSolverDevelopmentTest)
 
 CPPUNIT_TEST (FdSolverConsistencyTest)
 
 CPPUNIT_TEST (LDLdecompTest)
 
 CPPUNIT_TEST (FdAndVereshchaginSolversConsistencyTest)
 
 CPPUNIT_TEST (UpdateChainTest)
 
 CPPUNIT_TEST_SUITE (SolverTest)
 
 CPPUNIT_TEST_SUITE_END ()
 
void FkPosAndIkPosLocal (Chain &chain, ChainFkSolverPos &fksolverpos, ChainIkSolverPos &iksolverpos)
 
void FkPosAndJacLocal (Chain &chain, ChainFkSolverPos &fksolverpos, ChainJntToJacSolver &jacsolver)
 
void FkVelAndIkVelLocal (Chain &chain, ChainFkSolverVel &fksolvervel, ChainIkSolverVel &iksolvervel)
 
void FkVelAndJacLocal (Chain &chain, ChainFkSolverVel &fksolvervel, ChainJntToJacSolver &jacsolver)
 

Private Attributes

Chain chain1
 
Chain chain2
 
Chain chain3
 
Chain chain4
 
Chain chaindyn
 
Chain kukaLWR
 
Chain motomansia10
 
Chain motomansia10dyn
 

Detailed Description

Definition at line 28 of file solvertest.hpp.

Member Function Documentation

SolverTest::CPPUNIT_TEST ( FkPosAndJacTest  )
private
SolverTest::CPPUNIT_TEST ( FkVelAndJacTest  )
private
SolverTest::CPPUNIT_TEST ( FkVelAndIkVelTest  )
private
SolverTest::CPPUNIT_TEST ( FkPosAndIkPosTest  )
private
SolverTest::CPPUNIT_TEST ( VereshchaginTest  )
private
SolverTest::CPPUNIT_TEST ( IkSingularValueTest  )
private
SolverTest::CPPUNIT_TEST ( IkVelSolverWDLSTest  )
private
SolverTest::CPPUNIT_TEST ( FkPosVectTest  )
private
SolverTest::CPPUNIT_TEST ( FkVelVectTest  )
private
SolverTest::CPPUNIT_TEST ( FdSolverDevelopmentTest  )
private
SolverTest::CPPUNIT_TEST ( FdSolverConsistencyTest  )
private
SolverTest::CPPUNIT_TEST ( LDLdecompTest  )
private
SolverTest::CPPUNIT_TEST ( FdAndVereshchaginSolversConsistencyTest  )
private
SolverTest::CPPUNIT_TEST ( UpdateChainTest  )
private
SolverTest::CPPUNIT_TEST_SUITE ( SolverTest  )
private
SolverTest::CPPUNIT_TEST_SUITE_END ( )
private
void SolverTest::FdAndVereshchaginSolversConsistencyTest ( )

Compute the forward dynamics (joint accelearitions given actuator torques) using both solvers and test for consistency

Definition at line 1433 of file solvertest.cpp.

void SolverTest::FdSolverConsistencyTest ( )

Definition at line 1296 of file solvertest.cpp.

void SolverTest::FdSolverDevelopmentTest ( )

Definition at line 1128 of file solvertest.cpp.

void SolverTest::FkPosAndIkPosLocal ( Chain chain,
ChainFkSolverPos fksolverpos,
ChainIkSolverPos iksolverpos 
)
private

Definition at line 781 of file solvertest.cpp.

void SolverTest::FkPosAndIkPosTest ( )

Definition at line 458 of file solvertest.cpp.

void SolverTest::FkPosAndJacLocal ( Chain chain,
ChainFkSolverPos fksolverpos,
ChainJntToJacSolver jacsolver 
)
private

Definition at line 691 of file solvertest.cpp.

void SolverTest::FkPosAndJacTest ( )

Definition at line 383 of file solvertest.cpp.

void SolverTest::FkPosVectTest ( )

Definition at line 1087 of file solvertest.cpp.

void SolverTest::FkVelAndIkVelLocal ( Chain chain,
ChainFkSolverVel fksolvervel,
ChainIkSolverVel iksolvervel 
)
private

Definition at line 748 of file solvertest.cpp.

void SolverTest::FkVelAndIkVelTest ( )

Definition at line 415 of file solvertest.cpp.

void SolverTest::FkVelAndJacLocal ( Chain chain,
ChainFkSolverVel fksolvervel,
ChainJntToJacSolver jacsolver 
)
private

Definition at line 726 of file solvertest.cpp.

void SolverTest::FkVelAndJacTest ( )

Definition at line 399 of file solvertest.cpp.

void SolverTest::FkVelVectTest ( )

Definition at line 1107 of file solvertest.cpp.

void SolverTest::IkSingularValueTest ( )

Definition at line 509 of file solvertest.cpp.

void SolverTest::IkVelSolverWDLSTest ( )

Definition at line 630 of file solvertest.cpp.

void SolverTest::LDLdecompTest ( )

Definition at line 1377 of file solvertest.cpp.

void SolverTest::setUp ( )

KUKA LWR 4 Chain with Dynamics Parameters (for Forward Dynamics and Vereshchagin solver tests) Necessary test model for the Vereshchagin solver: KDL's implementation of the Vereshchagin solver can only work with the robot chains that have equal number of joints and segments. Note: Joint effective inertia values in this model are closely aligned with the joint inertia of the real robot. These parameters are published in: Jubien, A., Gautier, M. and Janot, A., "Dynamic identification of the Kuka LWR robot using motor torques and joint torque sensors data.", IFAC Proceedings Volumes, 2014., 47(3), pp.8391-8396.

Definition at line 12 of file solvertest.cpp.

void SolverTest::tearDown ( )

Definition at line 224 of file solvertest.cpp.

void SolverTest::UpdateChainTest ( )

Definition at line 233 of file solvertest.cpp.

void SolverTest::VereshchaginTest ( )

Compute Hybrid Dynamics for KUKA LWR 4.

Test setup:

  • Operational-space task imposes acceleration constraints on the end-effector
  • External forces and feedforward joint torques are acting on the robot's structure, as disturbances from the environment

Expected result:

  • The solver computes the required joint torque commands (joint constraint torques) that satisfy imposed acceleration constraints and at the same time, compensate for the above mentioned disturbances

Method to evaluate:

  • Compare the resultant Cartesian accelerations of the end-effector's segment with the task-specified acceleration constraints

Definition of the Cartesian Acceleration Constraints imposed on the end-effector. Note: the Vereshchagin solver expects that the input values in alpha parameters (unit constraint forces) are expressed w.r.t. robot's base frame. However, the acceleration energy setpoints, i.e. beta parameters, are expressed w.r.t. above defined unit constraint forces. More specifically, each DOF (element) in beta parameter corresponds to its respective DOF (column) of the unit constraint force matrix (alpha).

Definition at line 809 of file solvertest.cpp.

Member Data Documentation

Chain SolverTest::chain1
private

Definition at line 68 of file solvertest.hpp.

Chain SolverTest::chain2
private

Definition at line 68 of file solvertest.hpp.

Chain SolverTest::chain3
private

Definition at line 68 of file solvertest.hpp.

Chain SolverTest::chain4
private

Definition at line 68 of file solvertest.hpp.

Chain SolverTest::chaindyn
private

Definition at line 68 of file solvertest.hpp.

Chain SolverTest::kukaLWR
private

Definition at line 68 of file solvertest.hpp.

Chain SolverTest::motomansia10
private

Definition at line 68 of file solvertest.hpp.

Chain SolverTest::motomansia10dyn
private

Definition at line 68 of file solvertest.hpp.


The documentation for this class was generated from the following files:


orocos_kdl
Author(s):
autogenerated on Fri Mar 12 2021 03:05:44