motor_serial.h
Go to the documentation of this file.
1 
31 #ifndef MOTORSERIAL_H
32 #define MOTORSERIAL_H
33 
34 #include <ros/ros.h>
35 #include <serial/serial.h>
38 #include <boost/thread.hpp>
39 #include <queue>
40 
41 #include <gtest/gtest_prod.h>
42 
43 class MotorSerial {
44 public:
45  MotorSerial(const std::string& port = "/dev/ttyUSB0",
46  uint32_t baud_rate = 9600, double loopRate = 100);
47  ~MotorSerial();
48 
50  int transmitCommands(const std::vector<MotorMessage>& commands);
51 
53  int commandAvailable();
54 
55  MotorSerial(const MotorSerial& other); // non construction-copyable
56  MotorSerial& operator=(const MotorSerial&); // non copyable
57 
58 private:
60 
61  // queue for messages that are to be transmitted
63 
65 
66  boost::thread serial_thread;
68 
69  int inputAvailable();
71  void appendOutput(MotorMessage command);
72 
73  // Thread that has manages the serial port
74  void SerialThread();
75 
76  FRIEND_TEST(MotorSerialTests, serialClosedOnInterupt);
77 };
78 
79 #endif
MotorSerial & operator=(const MotorSerial &)
shared_queue< MotorMessage > input
Definition: motor_serial.h:62
FRIEND_TEST(MotorSerialTests, serialClosedOnInterupt)
int transmitCommand(MotorMessage command)
Definition: motor_serial.cc:48
ros::Rate serial_loop_rate
Definition: motor_serial.h:67
int transmitCommands(const std::vector< MotorMessage > &commands)
Definition: motor_serial.cc:53
serial::Serial motors
Definition: motor_serial.h:59
int commandAvailable()
Definition: motor_serial.cc:67
ROSLIB_DECL std::string command(const std::string &cmd)
MotorSerial(const std::string &port="/dev/ttyUSB0", uint32_t baud_rate=9600, double loopRate=100)
Definition: motor_serial.cc:35
boost::thread serial_thread
Definition: motor_serial.h:66
MotorMessage getInputCommand()
Definition: motor_serial.cc:71
shared_queue< MotorMessage > output
Definition: motor_serial.h:64
MotorMessage receiveCommand()
Definition: motor_serial.cc:58
int inputAvailable()
Definition: motor_serial.cc:69
void appendOutput(MotorMessage command)
Definition: motor_serial.cc:80
void SerialThread()
Definition: motor_serial.cc:82


ubiquity_motor
Author(s):
autogenerated on Mon Jun 10 2019 15:37:24