#include <motor_serial.h>
Public Member Functions | |
int | commandAvailable () |
MotorSerial (const std::string &port="/dev/ttyUSB0", uint32_t baud_rate=9600, double loopRate=100) | |
MotorMessage | receiveCommand () |
int | transmitCommand (MotorMessage command) |
int | transmitCommands (std::vector< MotorMessage > commands) |
~MotorSerial () | |
Private Member Functions | |
void | appendOutput (MotorMessage command) |
MotorMessage | getInputCommand () |
int | inputAvailable () |
void | SerialThread () |
Private Attributes | |
uint32_t | _baud_rate |
std::string | _port |
bool | have_input |
bool | have_output |
std::queue< MotorMessage > | input |
boost::mutex | input_mtx_ |
serial::Serial * | motors |
std::queue< MotorMessage > | output |
boost::mutex | output_mtx_ |
ros::Rate * | serial_loop_rate |
boost::thread * | serial_thread |
Copyright (c) 2016, Ubiquity Robotics All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
Neither the name of ubiquity_motor nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
Definition at line 40 of file motor_serial.h.
MotorSerial::MotorSerial | ( | const std::string & | port = "/dev/ttyUSB0" , |
uint32_t | baud_rate = 9600 , |
||
double | loopRate = 100 |
||
) |
Copyright (c) 2016, Ubiquity Robotics All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
Neither the name of ubiquity_motor nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
Definition at line 35 of file motor_serial.cc.
Definition at line 77 of file motor_serial.cc.
void MotorSerial::appendOutput | ( | MotorMessage | command | ) | [private] |
Definition at line 167 of file motor_serial.cc.
int MotorSerial::commandAvailable | ( | ) |
Definition at line 119 of file motor_serial.cc.
MotorMessage MotorSerial::getInputCommand | ( | ) | [private] |
Definition at line 156 of file motor_serial.cc.
int MotorSerial::inputAvailable | ( | ) | [private] |
Definition at line 137 of file motor_serial.cc.
Definition at line 107 of file motor_serial.cc.
void MotorSerial::SerialThread | ( | ) | [private] |
Definition at line 174 of file motor_serial.cc.
int MotorSerial::transmitCommand | ( | MotorMessage | command | ) |
Definition at line 86 of file motor_serial.cc.
int MotorSerial::transmitCommands | ( | std::vector< MotorMessage > | commands | ) |
Definition at line 95 of file motor_serial.cc.
uint32_t MotorSerial::_baud_rate [private] |
Definition at line 56 of file motor_serial.h.
std::string MotorSerial::_port [private] |
Definition at line 55 of file motor_serial.h.
bool MotorSerial::have_input [private] |
Definition at line 59 of file motor_serial.h.
bool MotorSerial::have_output [private] |
Definition at line 66 of file motor_serial.h.
std::queue<MotorMessage> MotorSerial::input [private] |
Definition at line 63 of file motor_serial.h.
boost::mutex MotorSerial::input_mtx_ [private] |
Definition at line 61 of file motor_serial.h.
serial::Serial* MotorSerial::motors [private] |
Definition at line 53 of file motor_serial.h.
std::queue<MotorMessage> MotorSerial::output [private] |
Definition at line 70 of file motor_serial.h.
boost::mutex MotorSerial::output_mtx_ [private] |
Definition at line 68 of file motor_serial.h.
ros::Rate* MotorSerial::serial_loop_rate [private] |
Definition at line 73 of file motor_serial.h.
boost::thread* MotorSerial::serial_thread [private] |
Definition at line 72 of file motor_serial.h.