ATRVJR Driver class Modified from B21 Driver - By David Lu!! 2/2010 Modified from Player code. More...
#include <atrvjr_driver.h>
Public Member Functions | |
ATRVJR () | |
int | getBaseBumps (sensor_msgs::PointCloud *cloud) const |
void | getBaseSonarPoints (sensor_msgs::PointCloud *cloud) const |
void | getBaseSonarReadings (float *readings) const |
float | getBearing () |
int | getBodyBumps (sensor_msgs::PointCloud *cloud) const |
void | getBodySonarPoints (sensor_msgs::PointCloud *cloud) const |
void | getBodySonarReadings (float *readings) const |
float | getDistance () |
int | getNumBaseSonars () const |
int | getNumBodySonars () const |
float | getRotationalVelocity () const |
float | getTranslationalVelocity () const |
float | getVoltage () const |
bool | isOdomReady () const |
bool | isPluggedIn () const |
void | processDioEvent (unsigned char address, unsigned short data) |
void | setMovement (float tvel, float rvel, float acceleration) |
void | setSonarPower (bool) |
virtual | ~ATRVJR () |
Private Member Functions | |
ATRVJR (const ATRVJR &atrvjr) | |
Private constructor - Don't use. | |
int | getBumps (const int index, sensor_msgs::PointCloud *cloud) const |
void | getSonarPoints (const int ringi, sensor_msgs::PointCloud *cloud) const |
void | getSonarReadings (const int ringi, float *readings) const |
ATRVJR & | operator= (const ATRVJR &atrvjr) |
Private constructor - Don't use. | |
Private Attributes | |
int ** | bumps |
int | first_distance |
bool | found_distance |
int | home_bearing |
Last home bearing (arbitrary units) |
ATRVJR Driver class Modified from B21 Driver - By David Lu!! 2/2010 Modified from Player code.
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 33 of file atrvjr_driver.h.
ATRVJR::ATRVJR | ( | ) |
Definition at line 31 of file atrvjr_driver.cc.
ATRVJR::~ATRVJR | ( | ) | [virtual] |
Definition at line 44 of file atrvjr_driver.cc.
ATRVJR::ATRVJR | ( | const ATRVJR & | atrvjr | ) | [private] |
Private constructor - Don't use.
int ATRVJR::getBaseBumps | ( | sensor_msgs::PointCloud * | cloud | ) | const |
Gets a point cloud for the bump sensors on the base
cloud | Data structure into which the bump readings are saved |
Definition at line 113 of file atrvjr_driver.cc.
void ATRVJR::getBaseSonarPoints | ( | sensor_msgs::PointCloud * | cloud | ) | const |
Gets a point cloud for sonar readings from base
cloud | Data structure into which the sonar readings are saved |
Definition at line 105 of file atrvjr_driver.cc.
void ATRVJR::getBaseSonarReadings | ( | float * | readings | ) | const |
Get readings from the sonar on the base of the ATRVJR in meters
readings | Data structure into which the sonar readings are saved |
Definition at line 98 of file atrvjr_driver.cc.
float ATRVJR::getBearing | ( | ) |
Definition at line 59 of file atrvjr_driver.cc.
int ATRVJR::getBodyBumps | ( | sensor_msgs::PointCloud * | cloud | ) | const |
Gets a point cloud for the bump sensors on the body
cloud | Data structure into which the bump readings are saved |
Definition at line 109 of file atrvjr_driver.cc.
void ATRVJR::getBodySonarPoints | ( | sensor_msgs::PointCloud * | cloud | ) | const |
Gets a point cloud for sonar readings from body
cloud | Data structure into which the sonar readings are saved |
Definition at line 102 of file atrvjr_driver.cc.
void ATRVJR::getBodySonarReadings | ( | float * | readings | ) | const |
Get readings from the sonar on the body of the ATRVJR in meters
readings | Data structure into which the sonar readings are saved |
Definition at line 94 of file atrvjr_driver.cc.
int ATRVJR::getBumps | ( | const int | index, |
sensor_msgs::PointCloud * | cloud | ||
) | const [private] |
index | BODY_INDEX or BASE_INDEX |
cloud | Data structure into which the bump sensors are saved |
Definition at line 173 of file atrvjr_driver.cc.
float ATRVJR::getDistance | ( | ) |
Definition at line 50 of file atrvjr_driver.cc.
int ATRVJR::getNumBaseSonars | ( | ) | const |
Definition at line 90 of file atrvjr_driver.cc.
int ATRVJR::getNumBodySonars | ( | ) | const |
Definition at line 86 of file atrvjr_driver.cc.
float ATRVJR::getRotationalVelocity | ( | ) | const |
Definition at line 67 of file atrvjr_driver.cc.
void ATRVJR::getSonarPoints | ( | const int | ringi, |
sensor_msgs::PointCloud * | cloud | ||
) | const [private] |
ringi | BODY_INDEX or BASE_INDEX |
cloud | Data structure into which the sonar readings are saved |
Definition at line 153 of file atrvjr_driver.cc.
void ATRVJR::getSonarReadings | ( | const int | ringi, |
float * | readings | ||
) | const [private] |
ringi | BODY_INDEX or BASE_INDEX |
readings | Data structure into which the sonar readings are saved |
Definition at line 139 of file atrvjr_driver.cc.
float ATRVJR::getTranslationalVelocity | ( | ) | const |
Definition at line 63 of file atrvjr_driver.cc.
float ATRVJR::getVoltage | ( | ) | const |
Definition at line 71 of file atrvjr_driver.cc.
bool ATRVJR::isOdomReady | ( | ) | const [inline] |
Detects whether the robot has all the necessary components to calculate odometry
Definition at line 89 of file atrvjr_driver.h.
bool ATRVJR::isPluggedIn | ( | ) | const |
Definition at line 78 of file atrvjr_driver.cc.
void ATRVJR::processDioEvent | ( | unsigned char | address, |
unsigned short | data | ||
) | [virtual] |
Processes the DIO packets - called from RFflex Driver
address | origin |
data | values |
Reimplemented from RFLEX.
Definition at line 209 of file atrvjr_driver.cc.
void ATRVJR::setMovement | ( | float | tvel, |
float | rvel, | ||
float | acceleration | ||
) |
Sets the motion of the robot
tvel | Translational velocity (in m/s) |
rvel | Rotational velocity (in radian/s) |
acceleration | Translational acceleration (in m/s/s) |
Definition at line 131 of file atrvjr_driver.cc.
void ATRVJR::setSonarPower | ( | bool | on | ) |
Definition at line 117 of file atrvjr_driver.cc.
int** ATRVJR::bumps [private] |
Definition at line 110 of file atrvjr_driver.h.
int ATRVJR::first_distance [private] |
Definition at line 107 of file atrvjr_driver.h.
bool ATRVJR::found_distance [private] |
Definition at line 108 of file atrvjr_driver.h.
int ATRVJR::home_bearing [private] |
Last home bearing (arbitrary units)
Definition at line 109 of file atrvjr_driver.h.