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

The CoordInterface class class to deal with ros comunications (pub/sub) from MissionManager node to Coordinator node. More...

#include <coordInterfaceMissMan.h>

Public Member Functions

 CoordInterfaceMissMan (ros::NodeHandle nh, std::string robotName)
 
bool getStartFromCoord ()
 
void pubIamReadyOrNot (bool ready)
 
int publishToCoord (Eigen::Matrix< double, VEHICLE_DOF, 1 > nonCoopCartVel_eigen, Eigen::Matrix< double, VEHICLE_DOF, VEHICLE_DOF > admisVelTool_eigen)
 CoordInterface::publishToCoord publish the necessary thing to the coordinator node. More...
 
int getCoopCartVel (Eigen::Matrix< double, VEHICLE_DOF, 1 > *coopCartVel_eigen)
 
int getUpdatedGoal (Eigen::Matrix4d *wTgoalTool_eigen)
 change goal thingss
 

Detailed Description

The CoordInterface class class to deal with ros comunications (pub/sub) from MissionManager node to Coordinator node.

Definition at line 20 of file coordInterfaceMissMan.h.

Constructor & Destructor Documentation

CoordInterfaceMissMan::CoordInterfaceMissMan ( ros::NodeHandle  nh,
std::string  robotName 
)

initialize JJsharp to send to coordinator (dimensions, the actual size of data after this will remain 0) this dimension are fixed so it is useless to create a new message each time we have to publish

goal change things

Definition at line 3 of file coordInterfaceMissMan.cpp.

Member Function Documentation

int CoordInterfaceMissMan::publishToCoord ( Eigen::Matrix< double, VEHICLE_DOF, 1 >  nonCoopCartVel_eigen,
Eigen::Matrix< double, VEHICLE_DOF, VEHICLE_DOF >  admisVelTool_eigen 
)

CoordInterface::publishToCoord publish the necessary thing to the coordinator node.

Parameters
nonCoopCartVel_eigen(barDotX = w_Jtool_robot * yDot) it is the non-cooperative, tool-frame Cartesian velocities that would be resulted if the yDot computed (at the first TPIK, normal one without cooperation things) were applied.
admisVelTool_eigen(w_Jtool_robot * w_Jtool_robot^#) computation to express the space of achievable object velocities at the current, overall-system constrained, configuration
Returns
0 correct exec

Definition at line 76 of file coordInterfaceMissMan.cpp.


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