motor_serial.cc
Go to the documentation of this file.
1 
31 #include <ros/ros.h>
32 #include <serial/serial.h>
34 
35 MotorSerial::MotorSerial(const std::string& port, uint32_t baud_rate)
36  : motors(port, baud_rate, serial::Timeout::simpleTimeout(100)),
37  serial_errors(0), error_threshold(20) {
38  serial_thread = boost::thread(&MotorSerial::SerialThread, this);
39 }
40 
42  serial_thread.interrupt();
43  serial_thread.join();
44  motors.close();
45 }
46 
48  RawMotorMessage out = command.serialize();
49  ROS_DEBUG("out %02x %02x %02x %02x %02x %02x %02x %02x", out[0], out[1],
50  out[2], out[3], out[4], out[5], out[6], out[7]);
51  motors.write(out.c_array(), out.size());
52  return 0;
53 }
54 
55 int MotorSerial::transmitCommands(const std::vector<MotorMessage>& commands) {
56  for (auto& command : commands) {
57  RawMotorMessage out = command.serialize();
58  ROS_DEBUG("out %02x %02x %02x %02x %02x %02x %02x %02x", out[0], out[1],
59  out[2], out[3], out[4], out[5], out[6], out[7]);
60  motors.write(out.c_array(), out.size());
61  boost::this_thread::sleep(boost::posix_time::milliseconds(2));
62  }
63  return 0;
64 }
65 
67  MotorMessage mc;
68  if (!this->output.empty()) {
69  mc = output.front_pop();
70  }
71  return mc;
72 }
73 
75 
77 
78 void MotorSerial::closePort() { return motors.close(); }
79 
80 // After we have been offine this is called to re-open serial port
81 // This returns true if port was open or if port opened with success
83  bool retCode = true;
84 
85  if (motors.isOpen() == true) {
86  return true;
87  }
88 
89  // Port was closed so must open it using info from prior open()
90  try {
91  motors.open();
92  } catch (const serial::IOException& e) {
93  ROS_ERROR("%s", e.what());
94  retCode = false;
95  } catch (const std::invalid_argument) {
96  ROS_ERROR("MotorSerial::openPort Invalid argument");
97  retCode = false;
98  } catch (const serial::SerialException& e) {
99  ROS_ERROR("%s", e.what());
100  retCode = false;
101  } catch (...) {
102  ROS_ERROR("Unknown Error");
103  retCode = false;
104  }
105 
106  return retCode;
107 }
108 
110  try {
111  while (motors.isOpen()) {
112  boost::this_thread::interruption_point();
113  if (motors.waitReadable()) {
114  RawMotorMessage innew = {0, 0, 0, 0, 0, 0, 0, 0};
115 
116  motors.read(innew.c_array(), 1);
117  if (innew[0] != MotorMessage::delimeter) {
118  // The first byte was not the delimiter, so re-loop
119  if (++serial_errors > error_threshold) {
120  ROS_WARN("REJECT %02x", innew[0]);
121  }
122  continue;
123  }
124 
125  // This will wait for the transmission time of 8 bytes
126  motors.waitByteTimes(innew.size());
127 
128  // Read in next 7 bytes
129  motors.read(&innew.c_array()[1], 7);
130  ROS_DEBUG("Got message %x %x %x %x %x %x %x %x", innew[0],
131  innew[1], innew[2], innew[3], innew[4], innew[5],
132  innew[6], innew[7]);
133 
134  MotorMessage mc;
135  int error_code = mc.deserialize(innew);
136  if (error_code == 0) {
137  appendOutput(mc);
138  if (mc.getType() == MotorMessage::TYPE_ERROR) {
139  ROS_ERROR("GOT error from Firm 0x%02x",
140  mc.getRegister());
141  }
142  } else {
143  if (++serial_errors > error_threshold) {
144  if (error_code == MotorMessage::ERR_UNKNOWN_REGISTER) {
145  ROS_WARN_ONCE("Message deserialize found an unrecognized firmware register");
146  } else {
147  ROS_ERROR("DESERIALIZATION ERROR! - %d", error_code);
148  }
149  }
150  }
151  }
152  }
153 
154  } catch (const boost::thread_interrupted& e) {
155  motors.close();
156  } catch (const serial::IOException& e) {
157  ROS_ERROR("%s", e.what());
158  } catch (const serial::PortNotOpenedException& e) {
159  ROS_ERROR("%s", e.what());
160  } catch (...) {
161  ROS_ERROR("Unknown Error");
162  throw;
163  }
164 }
MotorSerial::transmitCommands
int transmitCommands(const std::vector< MotorMessage > &commands)
Definition: motor_serial.cc:55
MotorSerial::openPort
bool openPort()
Definition: motor_serial.cc:82
MotorSerial::receiveCommand
MotorMessage receiveCommand()
Definition: motor_serial.cc:66
MotorSerial::SerialThread
void SerialThread()
Definition: motor_serial.cc:109
serial
Definition: unix.h:47
MotorMessage::deserialize
MotorMessage::ErrorCodes deserialize(const RawMotorMessage &serialized)
Definition: motor_message.cc:151
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
MotorMessage::delimeter
const static uint8_t delimeter
Definition: motor_message.h:267
ros.h
command
ROSLIB_DECL std::string command(const std::string &cmd)
MotorMessage::getType
MotorMessage::MessageTypes getType() const
Definition: motor_message.cc:112
shared_queue::fast_empty
bool fast_empty() const
Definition: shared_queue.h:117
serial::Serial::close
void close()
Definition: serial.cc:87
MotorSerial::commandAvailable
int commandAvailable()
Definition: motor_serial.cc:74
shared_queue::push
void push(const T &value)
Definition: shared_queue.h:68
MotorMessage::ERR_UNKNOWN_REGISTER
@ ERR_UNKNOWN_REGISTER
Definition: motor_message.h:262
shared_queue::empty
bool empty() const
Definition: shared_queue.h:112
serial::IOException::what
virtual const char * what() const
Definition: serial.h:722
ROS_WARN_ONCE
#define ROS_WARN_ONCE(...)
MotorSerial::error_threshold
int error_threshold
Definition: motor_serial.h:70
MotorMessage::TYPE_ERROR
@ TYPE_ERROR
Definition: motor_message.h:78
serial::Serial::waitReadable
bool waitReadable()
Definition: serial.cc:105
MotorSerial::transmitCommand
int transmitCommand(MotorMessage command)
Definition: motor_serial.cc:47
serial::PortNotOpenedException::what
virtual const char * what() const
Definition: serial.h:740
serial::IOException
Definition: serial.h:688
MotorSerial::closePort
void closePort()
Definition: motor_serial.cc:78
ROS_DEBUG
#define ROS_DEBUG(...)
motor_serial.h
serial::SerialException::what
virtual const char * what() const
Definition: serial.h:683
ROS_WARN
#define ROS_WARN(...)
MotorSerial::appendOutput
void appendOutput(MotorMessage command)
Definition: motor_serial.cc:76
serial.h
serial::Serial::open
void open()
Definition: serial.cc:81
shared_queue::front_pop
T front_pop()
Definition: shared_queue.h:95
MotorMessage::getRegister
MotorMessage::Registers getRegister() const
Definition: motor_message.cc:122
MotorSerial::serial_thread
boost::thread serial_thread
Definition: motor_serial.h:65
serial::Serial::isOpen
bool isOpen() const
Definition: serial.cc:93
MotorSerial::MotorSerial
MotorSerial(const std::string &port="/dev/ttyUSB0", uint32_t baud_rate=9600)
Definition: motor_serial.cc:35
ROS_ERROR
#define ROS_ERROR(...)
serial::Serial::waitByteTimes
void waitByteTimes(size_t count)
Definition: serial.cc:112
serial::SerialException
Definition: serial.h:670
RawMotorMessage
boost::array< uint8_t, 8 > RawMotorMessage
Definition: motor_message.h:38
serial::PortNotOpenedException
Definition: serial.h:727
serial::Serial::write
size_t write(const uint8_t *data, size_t size)
Definition: serial.cc:252
serial::Serial::read
size_t read(uint8_t *buffer, size_t size)
Definition: serial.cc:124
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