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

robotInterface: a ros node responsible of taken info from simulator and robot sensors, and of given commands back. It is the intermiate layer between robot and mission manager ("main") This "Vision" Version is specialized for a robot with no arm and horizontal cameras used to detect hole and help the insertion phase. More...

#include <robotVisionInterface.h>

Public Member Functions

 RobotVisionInterface (ros::NodeHandle nh, std::string robotName)
 RobotVisionInterface::RobotInterfaceVision Constructor. More...
 
int init ()
 
int getwTv (Eigen::Matrix4d *wTv_eigen)
 
int sendyDot (std::vector< double > yDot)
 
int getLeftImage (cv::Mat *imageCV)
 RobotVisionInterface::getLeftImage for now convert in 8bit grayscale image. More...
 
int getRightImage (cv::Mat *imageCV)
 
int getRangeRightImage (cv::Mat *imageCV)
 
void imageLeftCallback (const sensor_msgs::ImageConstPtr &msg)
 RobotVisionInterface::imageLeftCallback store in member class the image arrived, process it only when really needed (that are, functions getImageL/R) More...
 
void imageRightCallback (const sensor_msgs::ImageConstPtr &msg)
 
void imageRangeRightCallback (const sensor_msgs::ImageConstPtr &msg)
 

Detailed Description

robotInterface: a ros node responsible of taken info from simulator and robot sensors, and of given commands back. It is the intermiate layer between robot and mission manager ("main") This "Vision" Version is specialized for a robot with no arm and horizontal cameras used to detect hole and help the insertion phase.

Note
from ROS doc: "image_transport should always be used to publish and subscribe to images" (instead of simple ros::subscriber)

Definition at line 27 of file robotVisionInterface.h.

Constructor & Destructor Documentation

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

RobotVisionInterface::RobotInterfaceVision Constructor.

Parameters
argcthe standard argument of c++ main needed for ros::init
argvthe standard argument of c++ main needed for ros::init and for know robot names: argv[1]=robotName, argv[2] = otherRobotName
toolNamename of the peg in the xml file of the scene

Definition at line 11 of file robotVisionInterface.cpp.

Member Function Documentation

int RobotVisionInterface::getLeftImage ( cv::Mat *  imageCV)

RobotVisionInterface::getLeftImage for now convert in 8bit grayscale image.

Parameters
imageCV
Returns
Warning
cropped image!
Todo:
return in color which can be useful for some algos

Definition at line 115 of file robotVisionInterface.cpp.

void RobotVisionInterface::imageLeftCallback ( const sensor_msgs::ImageConstPtr &  msg)

RobotVisionInterface::imageLeftCallback store in member class the image arrived, process it only when really needed (that are, functions getImageL/R)

Parameters
msg

Definition at line 155 of file robotVisionInterface.cpp.


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