RotateLaser Class Reference

class implements a gateway to communicate with the PIC to rotate the LMS200 More...

#include <laser_rotate3D.h>

List of all members.

Public Member Functions

void Publish ()
 Publish mutex protected publish.
void ReadLinesSerialPort (boost::function< void(std::string *)> f)
 ReadLinesSerialPort thread to read from the serial port, inherited from SerialCom.
 RotateLaser ()
 constructor
void RotateLaserCallback (std::string *readdata)
bool SendCommand ()
 SendCommand send a command to the PIC controlling the stepper motor.
void SetJointState (const sensor_msgs::JointState::ConstPtr &set_joint_state)
 SetJointState selects setting the angular position or rate for the external LM200 joint calls SetSpeed or SetPosition.
bool SetPosition (int desiredposition)
 SetPosition set the external angular position of the laser.
bool SetSpeed (int desiredrpm)
 SetSpeed set the external angular velocity of the laser.
 ~RotateLaser ()
 destructor

Public Attributes

boost::function< void(std::string *) BoostRotateLaserCallback )
ros::Publisher RotateLaser_pub
ros::Subscriber RotateLaser_sub

Protected Attributes

ros::NodeHandle RotateLaser_nh

Private Attributes

int baud_rate_
char command2send [8]
sensor_msgs::JointState joint_state
std::string port_name_
int previous_position_request
int previous_speed_request
int sizeofcommand
tf::TransformBroadcaster TransfBroadcaster
tf::Transform Transform2Laser
boost::mutex want2publish_mutex

Detailed Description

class implements a gateway to communicate with the PIC to rotate the LMS200

Definition at line 76 of file laser_rotate3D.h.


Constructor & Destructor Documentation

RotateLaser::RotateLaser (  ) 

constructor

Definition at line 147 of file laser_rotate3D.h.

RotateLaser::~RotateLaser (  ) 

destructor

Definition at line 136 of file laser_rotate3D.h.


Member Function Documentation

void RotateLaser::Publish (  ) 

Publish mutex protected publish.

Definition at line 345 of file laser_rotate3D.h.

void RotateLaser::ReadLinesSerialPort ( boost::function< void(std::string *)>  f  ) 

ReadLinesSerialPort thread to read from the serial port, inherited from SerialCom.

Definition at line 336 of file laser_rotate3D.h.

void RotateLaser::RotateLaserCallback ( std::string *  readdata  ) 

Definition at line 383 of file laser_rotate3D.h.

bool RotateLaser::SendCommand (  ) 

SendCommand send a command to the PIC controlling the stepper motor.

Definition at line 318 of file laser_rotate3D.h.

void RotateLaser::SetJointState ( const sensor_msgs::JointState::ConstPtr &  set_joint_state  ) 

SetJointState selects setting the angular position or rate for the external LM200 joint calls SetSpeed or SetPosition.

Parameters:
set_joint_state - JointState type for set speed / position

Definition at line 215 of file laser_rotate3D.h.

bool RotateLaser::SetPosition ( int  desiredposition  ) 

SetPosition set the external angular position of the laser.

Definition at line 251 of file laser_rotate3D.h.

bool RotateLaser::SetSpeed ( int  desiredrpm  ) 

SetSpeed set the external angular velocity of the laser.

Definition at line 292 of file laser_rotate3D.h.


Member Data Documentation

int RotateLaser::baud_rate_ [private]

Definition at line 98 of file laser_rotate3D.h.

boost::function<void(std::string*) RotateLaser::BoostRotateLaserCallback)

Definition at line 123 of file laser_rotate3D.h.

char RotateLaser::command2send[8] [private]

Definition at line 102 of file laser_rotate3D.h.

sensor_msgs::JointState RotateLaser::joint_state [private]

Definition at line 92 of file laser_rotate3D.h.

std::string RotateLaser::port_name_ [private]

Definition at line 99 of file laser_rotate3D.h.

Definition at line 94 of file laser_rotate3D.h.

Definition at line 95 of file laser_rotate3D.h.

ros::NodeHandle RotateLaser::RotateLaser_nh [protected]

Definition at line 80 of file laser_rotate3D.h.

Definition at line 113 of file laser_rotate3D.h.

Definition at line 114 of file laser_rotate3D.h.

Definition at line 101 of file laser_rotate3D.h.

tf::TransformBroadcaster RotateLaser::TransfBroadcaster [private]

Definition at line 105 of file laser_rotate3D.h.

tf::Transform RotateLaser::Transform2Laser [private]

Definition at line 106 of file laser_rotate3D.h.

boost::mutex RotateLaser::want2publish_mutex [private]

Definition at line 87 of file laser_rotate3D.h.


The documentation for this class was generated from the following file:
 All Classes Files Functions Variables Defines


laser_rotate3D
Author(s): Ricardo Pascoal
autogenerated on Wed Jul 23 04:33:38 2014