class implements a gateway to communicate with the PIC to rotate the LMS200
More...
#include <laser_rotate3D.h>
|
| void | Publish () |
| | Publish mutex protected publish. More...
|
| |
| void | ReadLinesSerialPort (boost::function< void(std::string *)> f) |
| | ReadLinesSerialPort thread to read from the serial port, inherited from SerialCom. More...
|
| |
| | RotateLaser () |
| | constructor More...
|
| |
| void | RotateLaserCallback (std::string *readdata) |
| |
| bool | SendCommand () |
| | SendCommand send a command to the PIC controlling the stepper motor. More...
|
| |
| 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. More...
|
| |
| bool | SetPosition (int desiredposition) |
| | SetPosition set the external angular position of the laser. More...
|
| |
| bool | SetSpeed (int desiredrpm) |
| | SetSpeed set the external angular velocity of the laser. More...
|
| |
| | ~RotateLaser () |
| | destructor More...
|
| |
class implements a gateway to communicate with the PIC to rotate the LMS200
Definition at line 76 of file laser_rotate3D.h.
| RotateLaser::RotateLaser |
( |
| ) |
|
| RotateLaser::~RotateLaser |
( |
| ) |
|
| void RotateLaser::Publish |
( |
| ) |
|
| 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 | ) |
|
| 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.
| int RotateLaser::baud_rate_ |
|
private |
| boost::function<void(std::string*)> RotateLaser::BoostRotateLaserCallback |
| char RotateLaser::command2send[8] |
|
private |
| sensor_msgs::JointState RotateLaser::joint_state |
|
private |
| std::string RotateLaser::port_name_ |
|
private |
| int RotateLaser::previous_position_request |
|
private |
| int RotateLaser::previous_speed_request |
|
private |
| ros::NodeHandle RotateLaser::RotateLaser_nh |
|
protected |
| ros::Publisher RotateLaser::RotateLaser_pub |
| ros::Subscriber RotateLaser::RotateLaser_sub |
| int RotateLaser::sizeofcommand |
|
private |
| tf::TransformBroadcaster RotateLaser::TransfBroadcaster |
|
private |
| tf::Transform RotateLaser::Transform2Laser |
|
private |
| boost::mutex RotateLaser::want2publish_mutex |
|
private |
The documentation for this class was generated from the following file: