Public Types | Public Member Functions | Public Attributes
pr2_hardware_interface::AccelerometerCommand Class Reference

#include <hardware_interface.h>

List of all members.

Public Types

enum  { RANGE_2G = 0, RANGE_4G = 1, RANGE_8G = 2 }
enum  {
  BANDWIDTH_1500HZ = 6, BANDWIDTH_750HZ = 5, BANDWIDTH_375HZ = 4, BANDWIDTH_190HZ = 3,
  BANDWIDTH_100HZ = 2, BANDWIDTH_50HZ = 1, BANDWIDTH_25HZ = 0
}
 Enums for possible accelerometer range settings. More...

Public Member Functions

 AccelerometerCommand ()
 Enums for possible accelerometer bandwidth settings.

Public Attributes

int bandwidth_
 Accelerometer bandwidth setting. Value is passed directly to Bosch accelerometer (BMA 150). The maximum bandwidth of 1500Hz is appropriate in almost all cases. Instead of changing bandwidth value, use software filter to remove high frequencies from accelerometer data. This way, other accerometer users are not affected. Read accelerometer datasheet for more information about possible bandwidth setting.
int range_
 The range of the values to be returned (range of 0 means within +/- 2g, 1 means within +/-4g, 2 means /- 8g). Value is reported in m/s/s.

Detailed Description

Definition at line 185 of file hardware_interface.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
RANGE_2G 
RANGE_4G 
RANGE_8G 

Definition at line 188 of file hardware_interface.h.

anonymous enum

Enums for possible accelerometer range settings.

Enumerator:
BANDWIDTH_1500HZ 
BANDWIDTH_750HZ 
BANDWIDTH_375HZ 
BANDWIDTH_190HZ 
BANDWIDTH_100HZ 
BANDWIDTH_50HZ 
BANDWIDTH_25HZ 

Definition at line 189 of file hardware_interface.h.


Constructor & Destructor Documentation

Enums for possible accelerometer bandwidth settings.

Definition at line 190 of file hardware_interface.h.


Member Data Documentation

Accelerometer bandwidth setting. Value is passed directly to Bosch accelerometer (BMA 150). The maximum bandwidth of 1500Hz is appropriate in almost all cases. Instead of changing bandwidth value, use software filter to remove high frequencies from accelerometer data. This way, other accerometer users are not affected. Read accelerometer datasheet for more information about possible bandwidth setting.

Definition at line 192 of file hardware_interface.h.

The range of the values to be returned (range of 0 means within +/- 2g, 1 means within +/-4g, 2 means /- 8g). Value is reported in m/s/s.

Definition at line 191 of file hardware_interface.h.


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


pr2_hardware_interface
Author(s): Eric Berger berger@willowgarage.com
autogenerated on Thu Dec 12 2013 12:03:52