Public Types | Public Member Functions | Public Attributes
roomba_500_series::Diagnostic_< ContainerAllocator > Struct Template Reference

#include <Diagnostic.h>

List of all members.

Public Types

typedef int16_t _battery_current_type
typedef int8_t _battery_temperature_type
typedef int16_t _battery_voltage_type
typedef ::std_msgs::Header_
< ContainerAllocator > 
_header_type
typedef int16_t _left_motor_current_type
typedef uint8_t _left_motor_overcurrent_type
typedef int16_t _main_brush_current_type
typedef uint8_t _main_brush_overcurrent_type
typedef int16_t _right_motor_current_type
typedef uint8_t _right_motor_overcurrent_type
typedef int16_t _side_brush_current_type
typedef uint8_t _side_brush_overcurrent_type
typedef boost::shared_ptr
< ::roomba_500_series::Diagnostic_
< ContainerAllocator > const > 
ConstPtr
typedef boost::shared_ptr
< ::roomba_500_series::Diagnostic_
< ContainerAllocator > > 
Ptr
typedef Diagnostic_
< ContainerAllocator > 
Type

Public Member Functions

 Diagnostic_ ()
 Diagnostic_ (const ContainerAllocator &_alloc)

Public Attributes

boost::shared_ptr< std::map
< std::string, std::string > > 
__connection_header
int16_t battery_current
int8_t battery_temperature
int16_t battery_voltage
::std_msgs::Header_
< ContainerAllocator > 
header
int16_t left_motor_current
uint8_t left_motor_overcurrent
int16_t main_brush_current
uint8_t main_brush_overcurrent
int16_t right_motor_current
uint8_t right_motor_overcurrent
int16_t side_brush_current
uint8_t side_brush_overcurrent

Detailed Description

template<class ContainerAllocator>
struct roomba_500_series::Diagnostic_< ContainerAllocator >

Definition at line 22 of file Diagnostic.h.


Member Typedef Documentation

template<class ContainerAllocator >
typedef int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::_battery_current_type

Definition at line 84 of file Diagnostic.h.

template<class ContainerAllocator >
typedef int8_t roomba_500_series::Diagnostic_< ContainerAllocator >::_battery_temperature_type

Definition at line 90 of file Diagnostic.h.

template<class ContainerAllocator >
typedef int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::_battery_voltage_type

Definition at line 87 of file Diagnostic.h.

template<class ContainerAllocator >
typedef ::std_msgs::Header_<ContainerAllocator> roomba_500_series::Diagnostic_< ContainerAllocator >::_header_type

Definition at line 57 of file Diagnostic.h.

template<class ContainerAllocator >
typedef int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::_left_motor_current_type

Definition at line 60 of file Diagnostic.h.

template<class ContainerAllocator >
typedef uint8_t roomba_500_series::Diagnostic_< ContainerAllocator >::_left_motor_overcurrent_type

Definition at line 72 of file Diagnostic.h.

template<class ContainerAllocator >
typedef int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::_main_brush_current_type

Definition at line 66 of file Diagnostic.h.

template<class ContainerAllocator >
typedef uint8_t roomba_500_series::Diagnostic_< ContainerAllocator >::_main_brush_overcurrent_type

Definition at line 78 of file Diagnostic.h.

template<class ContainerAllocator >
typedef int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::_right_motor_current_type

Definition at line 63 of file Diagnostic.h.

template<class ContainerAllocator >
typedef uint8_t roomba_500_series::Diagnostic_< ContainerAllocator >::_right_motor_overcurrent_type

Definition at line 75 of file Diagnostic.h.

template<class ContainerAllocator >
typedef int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::_side_brush_current_type

Definition at line 69 of file Diagnostic.h.

template<class ContainerAllocator >
typedef uint8_t roomba_500_series::Diagnostic_< ContainerAllocator >::_side_brush_overcurrent_type

Definition at line 81 of file Diagnostic.h.

template<class ContainerAllocator >
typedef boost::shared_ptr< ::roomba_500_series::Diagnostic_<ContainerAllocator> const> roomba_500_series::Diagnostic_< ContainerAllocator >::ConstPtr

Definition at line 95 of file Diagnostic.h.

template<class ContainerAllocator >
typedef boost::shared_ptr< ::roomba_500_series::Diagnostic_<ContainerAllocator> > roomba_500_series::Diagnostic_< ContainerAllocator >::Ptr

Definition at line 94 of file Diagnostic.h.

template<class ContainerAllocator >
typedef Diagnostic_<ContainerAllocator> roomba_500_series::Diagnostic_< ContainerAllocator >::Type

Definition at line 23 of file Diagnostic.h.


Constructor & Destructor Documentation

template<class ContainerAllocator >
roomba_500_series::Diagnostic_< ContainerAllocator >::Diagnostic_ ( ) [inline]

Definition at line 25 of file Diagnostic.h.

template<class ContainerAllocator >
roomba_500_series::Diagnostic_< ContainerAllocator >::Diagnostic_ ( const ContainerAllocator &  _alloc) [inline]

Definition at line 41 of file Diagnostic.h.


Member Data Documentation

template<class ContainerAllocator >
boost::shared_ptr<std::map<std::string, std::string> > roomba_500_series::Diagnostic_< ContainerAllocator >::__connection_header

Definition at line 96 of file Diagnostic.h.

template<class ContainerAllocator >
int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::battery_current

Definition at line 85 of file Diagnostic.h.

template<class ContainerAllocator >
int8_t roomba_500_series::Diagnostic_< ContainerAllocator >::battery_temperature

Definition at line 91 of file Diagnostic.h.

template<class ContainerAllocator >
int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::battery_voltage

Definition at line 88 of file Diagnostic.h.

template<class ContainerAllocator >
::std_msgs::Header_<ContainerAllocator> roomba_500_series::Diagnostic_< ContainerAllocator >::header

Definition at line 58 of file Diagnostic.h.

template<class ContainerAllocator >
int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::left_motor_current

Definition at line 61 of file Diagnostic.h.

template<class ContainerAllocator >
uint8_t roomba_500_series::Diagnostic_< ContainerAllocator >::left_motor_overcurrent

Definition at line 73 of file Diagnostic.h.

template<class ContainerAllocator >
int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::main_brush_current

Definition at line 67 of file Diagnostic.h.

template<class ContainerAllocator >
uint8_t roomba_500_series::Diagnostic_< ContainerAllocator >::main_brush_overcurrent

Definition at line 79 of file Diagnostic.h.

template<class ContainerAllocator >
int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::right_motor_current

Definition at line 64 of file Diagnostic.h.

template<class ContainerAllocator >
uint8_t roomba_500_series::Diagnostic_< ContainerAllocator >::right_motor_overcurrent

Definition at line 76 of file Diagnostic.h.

template<class ContainerAllocator >
int16_t roomba_500_series::Diagnostic_< ContainerAllocator >::side_brush_current

Definition at line 70 of file Diagnostic.h.

template<class ContainerAllocator >
uint8_t roomba_500_series::Diagnostic_< ContainerAllocator >::side_brush_overcurrent

Definition at line 82 of file Diagnostic.h.


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


roomba_500_series
Author(s): Gonçalo Cabrita
autogenerated on Mon Jan 6 2014 11:26:40