Public Member Functions | Private Member Functions | Private Attributes
B21 Class Reference

B21 Driver class B21 Driver - By David Lu!! 2/2010 Modified from Player code. More...

#include <b21_driver.h>

Inheritance diagram for B21:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 B21 ()
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 ~B21 ()

Private Member Functions

 B21 (const B21 &b21)
 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
B21operator= (const B21 &b21)
 Private constructor - Don't use.

Private Attributes

int ** bumps
int first_distance
bool found_distance
int home_bearing
 Last home bearing (arbitrary units)

Detailed Description

B21 Driver class 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 32 of file b21_driver.h.


Constructor & Destructor Documentation

B21::B21 ( )

Definition at line 30 of file b21_driver.cc.

B21::~B21 ( ) [virtual]

Definition at line 43 of file b21_driver.cc.

B21::B21 ( const B21 b21) [private]

Private constructor - Don't use.


Member Function Documentation

int B21::getBaseBumps ( sensor_msgs::PointCloud *  cloud) const

Gets a point cloud for the bump sensors on the base

Parameters:
cloudData structure into which the bump readings are saved
Returns:
number of active bump sensors

Definition at line 112 of file b21_driver.cc.

void B21::getBaseSonarPoints ( sensor_msgs::PointCloud *  cloud) const

Gets a point cloud for sonar readings from base

Parameters:
cloudData structure into which the sonar readings are saved

Definition at line 104 of file b21_driver.cc.

void B21::getBaseSonarReadings ( float *  readings) const

Get readings from the sonar on the base of the B21 in meters

Parameters:
readingsData structure into which the sonar readings are saved

Definition at line 97 of file b21_driver.cc.

float B21::getBearing ( )

Definition at line 58 of file b21_driver.cc.

int B21::getBodyBumps ( sensor_msgs::PointCloud *  cloud) const

Gets a point cloud for the bump sensors on the body

Parameters:
cloudData structure into which the bump readings are saved
Returns:
number of active bump sensors

Definition at line 108 of file b21_driver.cc.

void B21::getBodySonarPoints ( sensor_msgs::PointCloud *  cloud) const

Gets a point cloud for sonar readings from body

Parameters:
cloudData structure into which the sonar readings are saved

Definition at line 101 of file b21_driver.cc.

void B21::getBodySonarReadings ( float *  readings) const

Get readings from the sonar on the body of the B21 in meters

Parameters:
readingsData structure into which the sonar readings are saved

Definition at line 93 of file b21_driver.cc.

int B21::getBumps ( const int  index,
sensor_msgs::PointCloud *  cloud 
) const [private]
Parameters:
indexBODY_INDEX or BASE_INDEX
cloudData structure into which the bump sensors are saved
Returns:
number of active bump sensors

Definition at line 172 of file b21_driver.cc.

float B21::getDistance ( )

Definition at line 49 of file b21_driver.cc.

int B21::getNumBaseSonars ( ) const

Definition at line 89 of file b21_driver.cc.

int B21::getNumBodySonars ( ) const

Definition at line 85 of file b21_driver.cc.

float B21::getRotationalVelocity ( ) const

Definition at line 66 of file b21_driver.cc.

void B21::getSonarPoints ( const int  ringi,
sensor_msgs::PointCloud *  cloud 
) const [private]
Parameters:
ringiBODY_INDEX or BASE_INDEX
cloudData structure into which the sonar readings are saved

Definition at line 152 of file b21_driver.cc.

void B21::getSonarReadings ( const int  ringi,
float *  readings 
) const [private]
Parameters:
ringiBODY_INDEX or BASE_INDEX
readingsData structure into which the sonar readings are saved

Definition at line 138 of file b21_driver.cc.

Definition at line 62 of file b21_driver.cc.

float B21::getVoltage ( ) const

Definition at line 70 of file b21_driver.cc.

bool B21::isOdomReady ( ) const [inline]

Detects whether the robot has all the necessary components to calculate odometry

Returns:
bool true if robot has read its distance, bearing and home bearing

Definition at line 88 of file b21_driver.h.

bool B21::isPluggedIn ( ) const

Definition at line 77 of file b21_driver.cc.

B21& B21::operator= ( const B21 b21) [private]

Private constructor - Don't use.

void B21::processDioEvent ( unsigned char  address,
unsigned short  data 
) [virtual]

Processes the DIO packets - called from RFflex Driver

Parameters:
addressorigin
datavalues

Reimplemented from RFLEX.

Definition at line 208 of file b21_driver.cc.

void B21::setMovement ( float  tvel,
float  rvel,
float  acceleration 
)

Sets the motion of the robot

Parameters:
tvelTranslational velocity (in m/s)
rvelRotational velocity (in radian/s)
accelerationTranslational acceleration (in m/s/s)

Definition at line 130 of file b21_driver.cc.

void B21::setSonarPower ( bool  on)

Definition at line 116 of file b21_driver.cc.


Member Data Documentation

int** B21::bumps [private]

Definition at line 109 of file b21_driver.h.

int B21::first_distance [private]

Definition at line 106 of file b21_driver.h.

bool B21::found_distance [private]

Definition at line 107 of file b21_driver.h.

int B21::home_bearing [private]

Last home bearing (arbitrary units)

Definition at line 108 of file b21_driver.h.


The documentation for this class was generated from the following files:


rflex
Author(s): David V. Lu!!, Mikhail Medvedev
autogenerated on Fri Aug 28 2015 12:58:58