include
ubiquity_motor
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
>
36
#include <
ubiquity_motor/motor_message.h
>
37
#include <
ubiquity_motor/shared_queue.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);
47
~MotorSerial
();
48
49
int
transmitCommand
(
MotorMessage
command
);
50
int
transmitCommands
(
const
std::vector<MotorMessage>& commands);
51
52
MotorMessage
receiveCommand
();
53
int
commandAvailable
();
54
void
closePort
();
55
bool
openPort
();
56
57
MotorSerial
(
MotorSerial
const
&) =
delete
;
58
MotorSerial
&
operator=
(
MotorSerial
const
&) =
delete
;
59
60
private
:
61
serial::Serial
motors
;
62
63
shared_queue<MotorMessage>
output
;
64
65
boost::thread
serial_thread
;
66
67
void
appendOutput
(
MotorMessage
command);
68
69
int
serial_errors
;
70
int
error_threshold
;
71
72
// Thread that has manages serial reads
73
void
SerialThread
();
74
75
FRIEND_TEST
(
MotorSerialTests
, serialClosedOnInterupt);
76
};
77
78
#endif
MotorSerial::transmitCommands
int transmitCommands(const std::vector< MotorMessage > &commands)
Definition:
motor_serial.cc:55
MotorSerial::openPort
bool openPort()
Definition:
motor_serial.cc:82
MotorSerial::FRIEND_TEST
FRIEND_TEST(MotorSerialTests, serialClosedOnInterupt)
MotorSerial::receiveCommand
MotorMessage receiveCommand()
Definition:
motor_serial.cc:66
MotorSerial::SerialThread
void SerialThread()
Definition:
motor_serial.cc:109
MotorSerial::serial_errors
int serial_errors
Definition:
motor_serial.h:69
MotorSerial::motors
serial::Serial motors
Definition:
motor_serial.h:61
MotorSerial::~MotorSerial
~MotorSerial()
Definition:
motor_serial.cc:41
ros.h
command
ROSLIB_DECL std::string command(const std::string &cmd)
MotorSerial
Definition:
motor_serial.h:43
MotorSerial::commandAvailable
int commandAvailable()
Definition:
motor_serial.cc:74
MotorSerial::error_threshold
int error_threshold
Definition:
motor_serial.h:70
MotorSerial::transmitCommand
int transmitCommand(MotorMessage command)
Definition:
motor_serial.cc:47
MotorSerial::closePort
void closePort()
Definition:
motor_serial.cc:78
shared_queue.h
MotorSerial::operator=
MotorSerial & operator=(MotorSerial const &)=delete
MotorSerial::appendOutput
void appendOutput(MotorMessage command)
Definition:
motor_serial.cc:76
MotorSerialTests
Definition:
motor_serial_test.cc:45
serial::Serial
Definition:
serial.h:147
serial.h
motor_message.h
MotorSerial::serial_thread
boost::thread serial_thread
Definition:
motor_serial.h:65
MotorSerial::MotorSerial
MotorSerial(const std::string &port="/dev/ttyUSB0", uint32_t baud_rate=9600)
Definition:
motor_serial.cc:35
shared_queue< MotorMessage >
MotorMessage
Definition:
motor_message.h:67
MotorSerial::output
shared_queue< MotorMessage > output
Definition:
motor_serial.h:63
ubiquity_motor
Author(s):
autogenerated on Thu Nov 16 2023 03:30:55