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
RobotInterface 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 actual robot and mission manager ("main") More...

#include <robotInterface.h>

Public Member Functions

 RobotInterface (ros::NodeHandle nh, std::string robotName)
 robotInterface::robotInterface Constructor More...
 
int init ()
 
int getwTv (Eigen::Matrix4d *wTv_eigen)
 
int getJointState (std::vector< double > *jState)
 robotInterface::getJointState More...
 
int sendyDot (std::vector< double > yDot)
 
int getForceTorque (Eigen::Vector3d *force, Eigen::Vector3d *torque)
 

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 actual robot and mission manager ("main")

Note
about the force/torque sensor: NOT VALID ANYMORE WITH RESOLVED LAG ISSUE WITH SIMULATION? BUT MAYBE USEFUL TO HAVE A SMOOTH BEHAVIOUR ********************************************** we have to make a mean: the sensor on uwsim give values but often they are intervalled with values = 0. this cause chattering and the robot dont move at all because 0-x velocity are intermittely given. So idea is use a queue and make a mean of the last 10 15 20 values of the sensor, and give the mean when caller calls getForceTorque. This problem can be given by simulator, by the sensor, or even by the physics engine which has difficulty in calculating collision between cilinder and inner hole. This is done with two vectors (one for force, one for torque) of circular buffers. Each vector contain 3 fixed size circular buffer of double, one for each direction (x y z) in this way we can use std::accumulate to sum all element of each buffer to the divided and make the mean NOT VALID ANYMORE WITH RESOLVED LAG ISSUE WITH SIMULATION? *************************************************

Definition at line 38 of file robotInterface.h.

Constructor & Destructor Documentation

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

robotInterface::robotInterface Constructor

Parameters
nhthe nodehandle to deal with ros sub and pub
nameof the robot itself (for sub to topics and print purposes)

Definition at line 9 of file robotInterface.cpp.

Member Function Documentation

int RobotInterface::getJointState ( std::vector< double > *  jState)

robotInterface::getJointState

Parameters
jState
Returns
Note
Doing so, only when main call this function it gets the joint state position

Definition at line 105 of file robotInterface.cpp.


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