motor_serial.h
Go to the documentation of this file.
00001 
00031 #ifndef MOTORSERIAL_H
00032 #define MOTORSERIAL_H
00033 
00034 #include <ubiquity_motor/motor_message.h>
00035 #include <serial/serial.h>
00036 #include <boost/thread.hpp>
00037 #include <ros/ros.h>
00038 #include <queue>
00039 
00040 class MotorSerial
00041 {
00042         public:
00043                 MotorSerial(const std::string& port = "/dev/ttyUSB0" , uint32_t baud_rate = 9600, double loopRate = 100);
00044                 ~MotorSerial();
00045 
00046                 int transmitCommand(MotorMessage command);
00047                 int transmitCommands(std::vector<MotorMessage> commands);
00048                 
00049                 MotorMessage receiveCommand();
00050                 int commandAvailable();
00051 
00052         private:
00053                 serial::Serial* motors;
00054                 
00055                 std::string _port;
00056                 uint32_t _baud_rate;
00057 
00058                 // bool to check for input to avoid unnecessary locking                
00059                 bool have_input;
00060                 //locking mutex for the input queue
00061                 boost::mutex input_mtx_;
00062                 // queue for messages that are to be transmitted
00063                 std::queue<MotorMessage> input; 
00064                 
00065                 // bool to check for output to avoid unnecessary locking                
00066                 bool have_output;
00067                 //locking mutex for the output queue
00068                 boost::mutex output_mtx_;
00069                 //queue for messages that have been received
00070                 std::queue<MotorMessage> output; 
00071 
00072                 boost::thread* serial_thread;
00073                 ros::Rate* serial_loop_rate;
00074 
00075                 int inputAvailable();
00076                 MotorMessage getInputCommand();
00077                 void appendOutput(MotorMessage command);
00078 
00079                 // Thread that has manages the serial port 
00080                 void SerialThread();
00081 };
00082 
00083 #endif


ubiquity_motor
Author(s):
autogenerated on Thu Jun 6 2019 18:33:27