AUV-Coop-Assembly
Master Thesis for Robotics Engineering. Cooperative peg-in-hole assembly with two underwater vehicles guided by vision
Public Member Functions | List of all members
KDLHelper Class Reference

Public Member Functions

 KDLHelper (std::string filename, std::string link0_name, std::string endEffector_name, std::string vehicle_name, std::string toolName="")
 KDLHelper::KDLHelper. More...
 
int setEESolvers ()
 KDLHelper::setEESolvers Initialize the kinematic solvers (jacob and pose) for the arm End Effector. More...
 
int setToolSolvers (Eigen::Matrix4d eeTtool_eigen)
 KDLHelper::setToolSolvers. More...
 
int setToolSolvers ()
 KDLHelper::setToolSolvers version for when the peg is a link of the robot. More...
 
int getFixedFrame (std::string frameOrigin, std::string frameTarget, Eigen::Matrix4d *xTx_eigen)
 KDLHelper::getFixedFrame get relative position of things inside the urdf file of the robot that NOT change their relative position (e.g. vehicle and a sensor fixed on the vehicle ) More...
 
int getEEpose (std::vector< double > jointPos, Eigen::Matrix4d *eePose_eigen)
 
int getJacobianEE (std::vector< double > jointPos, Eigen::Matrix< double, 6, ARM_DOF > *jacobianEE_eigen)
 KDLHelper::getJacobianEE respect base frame of arm (link0) More...
 
int getJacobianTool (std::vector< double > jointPos, Eigen::Matrix< double, 6, ARM_DOF > *jacobianTool_eigen)
 KDLHelper::getJacobianTool respect base frame of arm (link0) More...
 
int getNJoints ()
 
int getToolpose (std::vector< double > jointPos, Eigen::Matrix4d eeTtool_eigen, Eigen::Matrix4d *toolPose_eigen)
 debug More...
 
int setToolSolvers_old (Eigen::Matrix4d eeTtool_eigen)
 old More...
 

Detailed Description

Definition at line 15 of file kdlHelper.h.

Constructor & Destructor Documentation

KDLHelper::KDLHelper ( std::string  filename,
std::string  link0_name,
std::string  endEffector_name,
std::string  vehicle_name,
std::string  tool_name = "" 
)

KDLHelper::KDLHelper.

Parameters
filenamepath and name of the urdf file of the robot (arm + vehicle is ok)
link0_namename in the urdf file of the frame of the joint 0 (actually, name of <link></link>)
endEffector_namename in the urdf file of the frame of the end effector (actually, name of <link></link>)

Definition at line 8 of file kdlHelper.cpp.

Member Function Documentation

int KDLHelper::getFixedFrame ( std::string  frameOrigin,
std::string  frameTarget,
Eigen::Matrix4d *  xTx_eigen 
)

KDLHelper::getFixedFrame get relative position of things inside the urdf file of the robot that NOT change their relative position (e.g. vehicle and a sensor fixed on the vehicle )

Parameters
frameOrigin
frameTarget
*xTx_eigenFIXED transformation between origin and target, passed by reference
Returns
0 correct execution
Warning
DO NOT USE for trasformations that change during the mission.
Todo:
Maybe exist an easier method to parse fixed frame from urdf without needed of kdl solver: The other method is to use the tf listener (in world interface) but it is a ros inteface so specifically only if simulator used publish frame positions on ros

Definition at line 220 of file kdlHelper.cpp.

int KDLHelper::getJacobianEE ( std::vector< double >  jointPos,
Eigen::Matrix< double, 6, ARM_DOF > *  jacobianEE_eigen 
)

KDLHelper::getJacobianEE respect base frame of arm (link0)

Parameters
jointPos
jacobianEE_eigen
Returns

Definition at line 165 of file kdlHelper.cpp.

int KDLHelper::getJacobianTool ( std::vector< double >  jointPos,
Eigen::Matrix< double, 6, ARM_DOF > *  jacobianTool_eigen 
)

KDLHelper::getJacobianTool respect base frame of arm (link0)

Parameters
jointPos
jacobianTool_eigen
Returns

Definition at line 188 of file kdlHelper.cpp.

int KDLHelper::getToolpose ( std::vector< double >  jointPos,
Eigen::Matrix4d  eeTtool_eigen,
Eigen::Matrix4d *  toolPose_eigen 
)

debug

KDLHelper::getToolpose OnLY FOR DEBUG FOR NOW.

Parameters
jointPos
eePose_eigen
Returns

Definition at line 274 of file kdlHelper.cpp.

int KDLHelper::setEESolvers ( )

KDLHelper::setEESolvers Initialize the kinematic solvers (jacob and pose) for the arm End Effector.

Returns
0 for correct execution
Note
DH (denavit hartenberg) convention is used. So, link 0 is the base of the arm (FIXED respect to the vehicle)
it is ok do the same tree.getChain in this and other function because these setxxxSolvers are called only once to associate the solver to the kin chain

Definition at line 55 of file kdlHelper.cpp.

int KDLHelper::setToolSolvers ( Eigen::Matrix4d  eeTtool_eigen)

KDLHelper::setToolSolvers.

Returns
0 correct execution
Note
it is ok do the same tree.getChain in this and other function because these setxxxSolvers are called only once to associate the solver to the kin chain

kinChain until tool now

Definition at line 87 of file kdlHelper.cpp.

int KDLHelper::setToolSolvers ( )

KDLHelper::setToolSolvers version for when the peg is a link of the robot.

Returns

Definition at line 121 of file kdlHelper.cpp.

int KDLHelper::setToolSolvers_old ( Eigen::Matrix4d  eeTtool_eigen)

old

KDLHelper::setToolSolvers_old the one with link 0.

Returns
0 correct execution
Note
it is ok do the same tree.getChain in this and other function because these setxxxSolvers are called only once to associate the solver to the kin chain

kinChain until tool now

Definition at line 312 of file kdlHelper.cpp.


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