Public Member Functions | Private Attributes | List of all members
OptoelectricVehiclePose Class Reference

OptoelectricVehiclePose. More...

Public Member Functions

void carMarker (geometry_msgs::Vector3 pose)
 carMarker Function responsible publish the car marker. More...
 
bool checkMessageIntegrety (string msg)
 checkMessageIntegrety Function responsible evaluate is the message is valid. More...
 
void loop ()
 loop Function responsible to put the program running forever. More...
 
void loop ()
 loop Function responsible to put the program running forever. More...
 
void loop ()
 loop Function responsible to put the program running forever. More...
 
 OptoelectricVehiclePose (const ros::NodeHandle &nh)
 Class constructor Init the serial port, open the txt file and the yaml file. More...
 
 OptoelectricVehiclePose (const ros::NodeHandle &nh)
 Class constructor Init the serial port, open the txt file and the yaml file. More...
 
 OptoelectricVehiclePose (const ros::NodeHandle &nh)
 Class constructor Init the serial port, open the txt file and the yaml file. More...
 
void setupMessaging ()
 setupMessaging Function responsible for creat the publishers. More...
 
void setupMessaging ()
 setupMessaging Function responsible for creat the publishers. More...
 
void setupMessaging ()
 setupMessaging Function responsible for creat the publishers. More...
 
void sharpCallback (const sensor_msgs::Range::ConstPtr msg, int i)
 sharpCallback Function responsible evaluate is the message is valid. More...
 
void sharpCallback (const sensor_msgs::Range::ConstPtr msg, int i)
 sharpCallback Function responsible evaluate is the message is valid. More...
 

Private Attributes

ros::Publisher car_mark_pub
 
visualization_msgs::Marker car_marker
 
vector< bool > new_data
 
ros::NodeHandle nh_
 
ofstream outfile1
 
string parameters_url
 
double pitch
 
ros::Publisher pose_publisher
 
vector< ros::Publisher > publishers
 
double roll
 
SharpMath s
 
BufferedAsyncSerial serial
 
vector< ros::Subscriber > sharp_subscriber
 
int sharp_values [8]
 

Detailed Description

OptoelectricVehiclePose.

This class is responsible for open the serial port to recive the data from arduino. Also open a txt file to save the read values. And publish a range menssage with the sensors distance.

This class is responsible for subscribe to sensors message and calculate the calibration of the system.

Definition at line 252 of file orientation_base.cpp.

Constructor & Destructor Documentation

OptoelectricVehiclePose::OptoelectricVehiclePose ( const ros::NodeHandle &  nh)
inline

Class constructor Init the serial port, open the txt file and the yaml file.

Definition at line 259 of file orientation_base.cpp.

OptoelectricVehiclePose::OptoelectricVehiclePose ( const ros::NodeHandle &  nh)
inline

Class constructor Init the serial port, open the txt file and the yaml file.

Definition at line 654 of file orientation_calibration.cpp.

OptoelectricVehiclePose::OptoelectricVehiclePose ( const ros::NodeHandle &  nh)
inline

Class constructor Init the serial port, open the txt file and the yaml file.

Definition at line 251 of file orientation_preception_base.cpp.

Member Function Documentation

void OptoelectricVehiclePose::carMarker ( geometry_msgs::Vector3  pose)
inline

carMarker Function responsible publish the car marker.

Parameters
pose- geometry_msgs::Vector3 with the pose of the vehicle.

Definition at line 310 of file orientation_preception_base.cpp.

bool OptoelectricVehiclePose::checkMessageIntegrety ( string  msg)
inline

checkMessageIntegrety Function responsible evaluate is the message is valid.

Parameters
msg- string with the message.
Returns
bool true is the message is valid.

Definition at line 314 of file orientation_base.cpp.

void OptoelectricVehiclePose::loop ( )
inline

loop Function responsible to put the program running forever.

Definition at line 351 of file orientation_base.cpp.

void OptoelectricVehiclePose::loop ( )
inline

loop Function responsible to put the program running forever.

Definition at line 356 of file orientation_preception_base.cpp.

void OptoelectricVehiclePose::loop ( )
inline

loop Function responsible to put the program running forever.

Definition at line 716 of file orientation_calibration.cpp.

void OptoelectricVehiclePose::setupMessaging ( )
inline

setupMessaging Function responsible for creat the publishers.

SUBSCREVER

PUBLICAR

Definition at line 271 of file orientation_preception_base.cpp.

void OptoelectricVehiclePose::setupMessaging ( )
inline

setupMessaging Function responsible for creat the publishers.

SUBSCREVER

PUBLICAR

Definition at line 294 of file orientation_base.cpp.

void OptoelectricVehiclePose::setupMessaging ( )
inline

setupMessaging Function responsible for creat the publishers.

SUBSCREVER

PUBLICAR

Definition at line 682 of file orientation_calibration.cpp.

void OptoelectricVehiclePose::sharpCallback ( const sensor_msgs::Range::ConstPtr  msg,
int  i 
)
inline

sharpCallback Function responsible evaluate is the message is valid.

Parameters
msg- const sensor_msgs::Range::ConstPtr with the message.
i- 1 if the message is valid.

Definition at line 296 of file orientation_preception_base.cpp.

void OptoelectricVehiclePose::sharpCallback ( const sensor_msgs::Range::ConstPtr  msg,
int  i 
)
inline

sharpCallback Function responsible evaluate is the message is valid.

Parameters
msg- const sensor_msgs::Range::ConstPtr with the message.
i- 1 if the message is valid.

Definition at line 706 of file orientation_calibration.cpp.

Member Data Documentation

ros::Publisher OptoelectricVehiclePose::car_mark_pub
private

Definition at line 430 of file orientation_preception_base.cpp.

visualization_msgs::Marker OptoelectricVehiclePose::car_marker
private

Definition at line 429 of file orientation_preception_base.cpp.

vector< bool > OptoelectricVehiclePose::new_data
private

Definition at line 775 of file orientation_calibration.cpp.

ros::NodeHandle OptoelectricVehiclePose::nh_
private

Definition at line 429 of file orientation_base.cpp.

ofstream OptoelectricVehiclePose::outfile1
private

Definition at line 434 of file orientation_base.cpp.

string OptoelectricVehiclePose::parameters_url
private

Definition at line 777 of file orientation_calibration.cpp.

double OptoelectricVehiclePose::pitch
private

Definition at line 431 of file orientation_base.cpp.

ros::Publisher OptoelectricVehiclePose::pose_publisher
private

Definition at line 439 of file orientation_preception_base.cpp.

vector<ros::Publisher> OptoelectricVehiclePose::publishers
private

Definition at line 439 of file orientation_base.cpp.

double OptoelectricVehiclePose::roll
private

Definition at line 432 of file orientation_base.cpp.

SharpMath OptoelectricVehiclePose::s
private

Definition at line 436 of file orientation_base.cpp.

BufferedAsyncSerial OptoelectricVehiclePose::serial
private

Definition at line 437 of file orientation_base.cpp.

vector< ros::Subscriber > OptoelectricVehiclePose::sharp_subscriber
private

Definition at line 772 of file orientation_calibration.cpp.

int OptoelectricVehiclePose::sharp_values
private

Definition at line 774 of file orientation_calibration.cpp.


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


optoelectric
Author(s): Pedro Salvado, Gonçalo Carpinteiro
autogenerated on Mon Mar 2 2015 01:32:31