RFLEX Driver to handle input and output to RFlex devices. More...
#include <rflex_driver.h>

Public Member Functions | |
| void | configureSonar (const unsigned long echoDelay, const unsigned long pingDelay, const unsigned long setDelay, const unsigned long val) |
| bool | getBrakePower () const |
| int | getIrCount () const |
| int | initialize (const char *devname) |
| void | motionSetDefaults () |
| RFLEX () | |
| void | sendSystemStatusCommand () |
| void | setBrakePower (const bool power) |
| void | setDigitalIoPeriod (const long period) |
| void | setIrPower (const bool power) |
| void | setOdometryPeriod (const long period) |
| void | setVelocity (const long transVelocity, const long rotVelocity, const long acceleration) |
| virtual | ~RFLEX () |
Protected Member Functions | |
| virtual void | processDioEvent (unsigned char address, unsigned short data) |
Protected Attributes | |
| int | bearing |
| Raw rotational odometry. | |
| bool | brake |
| Brake Status. | |
| unsigned short | dioData [24] |
| Storage for digital IO values. | |
| int | distance |
| Raw translational odometry. | |
| int | home_bearing_found |
| unsigned char * | irRanges |
| Raw values from IR sensors. | |
| unsigned char * | lcdData |
| int | lcdX |
| int | lcdY |
| int | numIr |
| Number of IR sensors. | |
| int | odomReady |
| int | rotVelocity |
| Raw rotational velocity. | |
| int | sonar_ranges [SONAR_MAX_COUNT] |
| Raw Sonar readings (including unconnected ports) | |
| int | transVelocity |
| Raw translational velocity. | |
| long | voltage |
| Raw voltage reading. | |
Private Member Functions | |
| unsigned char | computeCRC (const unsigned char *buffer, const int n) |
| Calculates error checking code for specified buffer. | |
| RFLEX & | operator= (const RFLEX &rflex) |
| Private constructor - Don't use. | |
| void | parseDioReport (const unsigned char *buffer) |
| void | parseIrReport (const unsigned char *buffer) |
| void | parseJoyReport (const unsigned char *buffer) |
| void | parseMotReport (const unsigned char *buffer) |
| void | parsePacket (const unsigned char *buffer) |
| void | parseSonarReport (const unsigned char *buffer) |
| void | parseSysReport (const unsigned char *buffer) |
| int | readData () |
| Reads in a packet until it finds and end of packet signal. | |
| void | readPacket () |
| After reading the data, it checks for errors and then parses. | |
| RFLEX (const RFLEX &rflex) | |
| Private constructor - Don't use. | |
| bool | sendCommand (const unsigned char port, const unsigned char id, const unsigned char opcode, const int length, unsigned char *data) |
| bool | writePacket (const int length) const |
| Writes packet currently in write buffer to device. | |
Static Private Member Functions | |
| static void * | readThread (void *ptr) |
| Read Thread. | |
Private Attributes | |
| int | fd |
| File descriptor for serial port. | |
| bool | found |
| int | offset |
| unsigned char | readBuffer [BUFFER_SIZE] |
| pthread_t | thread |
| Thread which reads input upon arrival. | |
| unsigned char | writeBuffer [BUFFER_SIZE] |
| pthread_mutex_t | writeMutex |
| Mutex around writing to port. | |
RFLEX Driver to handle input and output to RFlex devices.
RFLEX Driver - 2/2010 Modified from Player code by David Lu!! Original Input Output code by Bill Smart
Player - One Hell of a Robot Server Copyright (C) 2000 Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard
This program is free software; you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.
This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
You should have received a copy of the GNU General Public License along with this program; if not, write to the Free Software Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
Definition at line 34 of file rflex_driver.h.
| RFLEX::RFLEX | ( | ) |
Definition at line 70 of file rflex_driver.cc.
| RFLEX::~RFLEX | ( | ) | [virtual] |
Definition at line 134 of file rflex_driver.cc.
| RFLEX::RFLEX | ( | const RFLEX & | rflex | ) | [private] |
Private constructor - Don't use.
| unsigned char RFLEX::computeCRC | ( | const unsigned char * | buffer, |
| const int | n | ||
| ) | [private] |
Calculates error checking code for specified buffer.
Definition at line 693 of file rflex_driver.cc.
| void RFLEX::configureSonar | ( | const unsigned long | echoDelay, |
| const unsigned long | pingDelay, | ||
| const unsigned long | setDelay, | ||
| const unsigned long | val | ||
| ) |
Configure the sonar parameters and send message to RFlex.
| echoDelay | Echo Delay |
| pingDelay | Ping Delay |
| setDelay | Set Delay |
| val | Unknown |
Definition at line 138 of file rflex_driver.cc.
| bool RFLEX::getBrakePower | ( | ) | const [inline] |
| int RFLEX::getIrCount | ( | ) | const [inline] |
Gets the number of IR sensors
Definition at line 85 of file rflex_driver.h.
| int RFLEX::initialize | ( | const char * | devname | ) |
Opens connection to serial port with specified device name
| devname | Device name assigned to serial port |
Definition at line 86 of file rflex_driver.cc.
| void RFLEX::motionSetDefaults | ( | ) |
Sends a set motion defaults message to the device.
Definition at line 184 of file rflex_driver.cc.
| void RFLEX::parseDioReport | ( | const unsigned char * | buffer | ) | [private] |
Definition at line 280 of file rflex_driver.cc.
| void RFLEX::parseIrReport | ( | const unsigned char * | buffer | ) | [private] |
Definition at line 308 of file rflex_driver.cc.
| void RFLEX::parseJoyReport | ( | const unsigned char * | buffer | ) | [private] |
Definition at line 451 of file rflex_driver.cc.
| void RFLEX::parseMotReport | ( | const unsigned char * | buffer | ) | [private] |
Definition at line 253 of file rflex_driver.cc.
| void RFLEX::parsePacket | ( | const unsigned char * | buffer | ) | [private] |
Definition at line 491 of file rflex_driver.cc.
| void RFLEX::parseSonarReport | ( | const unsigned char * | buffer | ) | [private] |
Definition at line 429 of file rflex_driver.cc.
| void RFLEX::parseSysReport | ( | const unsigned char * | buffer | ) | [private] |
Definition at line 363 of file rflex_driver.cc.
| void RFLEX::processDioEvent | ( | unsigned char | address, |
| unsigned short | data | ||
| ) | [protected, virtual] |
Reimplemented in ATRVJR, and B21.
Definition at line 303 of file rflex_driver.cc.
| int RFLEX::readData | ( | ) | [private] |
Reads in a packet until it finds and end of packet signal.
Definition at line 581 of file rflex_driver.cc.
| void RFLEX::readPacket | ( | ) | [private] |
After reading the data, it checks for errors and then parses.
Definition at line 542 of file rflex_driver.cc.
| void * RFLEX::readThread | ( | void * | ptr | ) | [static, private] |
Read Thread.
Definition at line 522 of file rflex_driver.cc.
| bool RFLEX::sendCommand | ( | const unsigned char | port, |
| const unsigned char | id, | ||
| const unsigned char | opcode, | ||
| const int | length, | ||
| unsigned char * | data | ||
| ) | [private] |
Send a command to the serial port
| port | Should be one of these: SYS_PORT, MOT_PORT, JSTK_PORT, SONAR_PORT, DIO_PORT, IR_PORT |
| id | |
| opcode | See opcodes in rflex_info.h |
| length | length of the data |
| data | actual data |
Definition at line 649 of file rflex_driver.cc.
| void RFLEX::sendSystemStatusCommand | ( | ) |
Sends a system status command to the device. Updates the brake and battery status.
Definition at line 249 of file rflex_driver.cc.
| void RFLEX::setBrakePower | ( | const bool | power | ) |
Turn Brake on or off Note: Brake on means the controller cannot move the robot and external forces CAN move it.
| power | true for on, false for off |
Definition at line 174 of file rflex_driver.cc.
| void RFLEX::setDigitalIoPeriod | ( | const long | period | ) |
Set the frequency that the Digital IO devices are checked.
| period | Period in milliseconds |
Definition at line 188 of file rflex_driver.cc.
| void RFLEX::setIrPower | ( | const bool | power | ) |
Turn IR on or off
| power | true for on, false for off |
Definition at line 149 of file rflex_driver.cc.
| void RFLEX::setOdometryPeriod | ( | const long | period | ) |
Set the frequency that the odometry is checked.
| period | Period in milliseconds |
Definition at line 194 of file rflex_driver.cc.
| void RFLEX::setVelocity | ( | const long | transVelocity, |
| const long | rotVelocity, | ||
| const long | acceleration | ||
| ) |
Sets the velocity
| transVelocity | Translational velocity in arbitrary units |
| rotVelocity | Rotational velocity in arbitrary units |
| acceleration | Acceleration (also in arbitrary units) |
Definition at line 207 of file rflex_driver.cc.
| bool RFLEX::writePacket | ( | const int | length | ) | const [private] |
Writes packet currently in write buffer to device.
Definition at line 673 of file rflex_driver.cc.
int RFLEX::bearing [protected] |
Raw rotational odometry.
Definition at line 105 of file rflex_driver.h.
bool RFLEX::brake [protected] |
Brake Status.
Definition at line 111 of file rflex_driver.h.
unsigned short RFLEX::dioData[24] [protected] |
Storage for digital IO values.
Definition at line 113 of file rflex_driver.h.
int RFLEX::distance [protected] |
Raw translational odometry.
Definition at line 104 of file rflex_driver.h.
int RFLEX::fd [private] |
File descriptor for serial port.
Definition at line 133 of file rflex_driver.h.
bool RFLEX::found [private] |
Definition at line 140 of file rflex_driver.h.
int RFLEX::home_bearing_found [protected] |
Definition at line 120 of file rflex_driver.h.
unsigned char* RFLEX::irRanges [protected] |
Raw values from IR sensors.
Definition at line 119 of file rflex_driver.h.
unsigned char* RFLEX::lcdData [protected] |
Definition at line 116 of file rflex_driver.h.
int RFLEX::lcdX [protected] |
Definition at line 115 of file rflex_driver.h.
int RFLEX::lcdY [protected] |
Definition at line 115 of file rflex_driver.h.
int RFLEX::numIr [protected] |
Number of IR sensors.
Definition at line 118 of file rflex_driver.h.
int RFLEX::odomReady [protected] |
Definition at line 121 of file rflex_driver.h.
int RFLEX::offset [private] |
Definition at line 141 of file rflex_driver.h.
unsigned char RFLEX::readBuffer[BUFFER_SIZE] [private] |
Definition at line 137 of file rflex_driver.h.
int RFLEX::rotVelocity [protected] |
Raw rotational velocity.
Definition at line 107 of file rflex_driver.h.
int RFLEX::sonar_ranges[SONAR_MAX_COUNT] [protected] |
Raw Sonar readings (including unconnected ports)
Definition at line 109 of file rflex_driver.h.
pthread_t RFLEX::thread [private] |
Thread which reads input upon arrival.
Definition at line 134 of file rflex_driver.h.
int RFLEX::transVelocity [protected] |
Raw translational velocity.
Definition at line 106 of file rflex_driver.h.
long RFLEX::voltage [protected] |
Raw voltage reading.
Definition at line 110 of file rflex_driver.h.
unsigned char RFLEX::writeBuffer[BUFFER_SIZE] [private] |
Definition at line 138 of file rflex_driver.h.
pthread_mutex_t RFLEX::writeMutex [private] |
Mutex around writing to port.
Definition at line 135 of file rflex_driver.h.