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
CoordInterfaceCoord Class Reference

The CoordInterfaceCoord class. More...

#include <coordInterfaceCoord.h>

Public Member Functions

 CoordInterfaceCoord (ros::NodeHandle nh, std::string robotNameA, std::string robotNameB)
 
bool getReadyBothRob ()
 
int getMatricesFromRobs (Eigen::Matrix< double, VEHICLE_DOF, 1 > *nonCoopCartVelA, Eigen::Matrix< double, VEHICLE_DOF, 1 > *nonCoopCartVelB, Eigen::Matrix< double, VEHICLE_DOF, VEHICLE_DOF > *admisVelToolA, Eigen::Matrix< double, VEHICLE_DOF, VEHICLE_DOF > *admisVelToolB)
 CoordInterfaceCoord::getMatricesFromRobs get all matrices needed to algorithm The function call each get if this get isnt previously called with success (ie, arrived message) More...
 
void publishCoopVel (Eigen::Matrix< double, VEHICLE_DOF, 1 > coopVel)
 
void publishStartBoth (bool start)
 
int getForceTorque (Eigen::Vector3d *force, Eigen::Vector3d *torque)
 
void publishUpdatedGoal (Eigen::Matrix4d wTgoal)
 
 CoordInterfaceCoord (ros::NodeHandle nh, std::string robotName)
 
bool getReadyRob ()
 
int getNonCoopCartVel (Eigen::Matrix< double, VEHICLE_DOF, 1 > *nonCoopCartVel_eigen)
 CoordInterfaceCoord::getxDot. More...
 
int getJJsharp (Eigen::Matrix< double, VEHICLE_DOF, VEHICLE_DOF > *admisVelTool_eigen)
 CoordInterfaceCoord::getJJsharp. More...
 

Detailed Description

The CoordInterfaceCoord class.

Warning
the SpinOnce is made by caller of this class

Definition at line 21 of file coordInterfaceCoord.h.

Member Function Documentation

int CoordInterfaceCoord::getJJsharp ( Eigen::Matrix< double, VEHICLE_DOF, VEHICLE_DOF > *  admisVelTool_eigen)

CoordInterfaceCoord::getJJsharp.

Parameters
*admisVelTool_eigenthe eigen matrix in which we want to store the message passed by reference so we dont waste memory, already used for temp vars
Returns
0 correct executions, 1 Warning mess do not arrived, -1 Error about dimension of message arrived

Definition at line 69 of file coordInterfaceCoord_old.cpp.

int CoordInterfaceCoord::getMatricesFromRobs ( Eigen::Matrix< double, VEHICLE_DOF, 1 > *  nonCoopCartVelA,
Eigen::Matrix< double, VEHICLE_DOF, 1 > *  nonCoopCartVelB,
Eigen::Matrix< double, VEHICLE_DOF, VEHICLE_DOF > *  admisVelToolA,
Eigen::Matrix< double, VEHICLE_DOF, VEHICLE_DOF > *  admisVelToolB 
)

CoordInterfaceCoord::getMatricesFromRobs get all matrices needed to algorithm The function call each get if this get isnt previously called with success (ie, arrived message)

Parameters
*nonCoopCartVelAOUT the eigen vector in which we want to store the message passed by reference so we dont waste memory, already used for temp vars
*nonCoopCartVelBOUT
*admisVelToolAOUT the eigen matrix in which we want to store the message passed by reference so we dont waste memory, already used for temp vars
admisVelToolBOUT
Returns
0 if everything arrived, i>0 if i matrices didn't arrived -1 Error about dimension of one or more the messages arrived

Definition at line 73 of file coordInterfaceCoord.cpp.

int CoordInterfaceCoord::getNonCoopCartVel ( Eigen::Matrix< double, VEHICLE_DOF, 1 > *  nonCoopCartVel_eigen)

CoordInterfaceCoord::getxDot.

Parameters
*nonCoopCartVel_eigenthe eigen vector in which we want to store the message passed by reference so we dont waste memory, already used for temp vars
Returns
0 correct executions, 1 Warning mess do not arrived, -1 Error about dimension of message arrived

Definition at line 32 of file coordInterfaceCoord_old.cpp.


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