Public Types | Public Member Functions | Public Attributes
bmc050_driver::bmc050_measurement_< ContainerAllocator > Struct Template Reference

#include <bmc050_measurement.h>

List of all members.

Public Types

typedef std::vector< double,
typename
ContainerAllocator::template
rebind< double >::other > 
_AccelerationX_type
typedef std::vector< double,
typename
ContainerAllocator::template
rebind< double >::other > 
_AccelerationY_type
typedef std::vector< double,
typename
ContainerAllocator::template
rebind< double >::other > 
_AccelerationZ_type
typedef std::vector< uint16_t,
typename
ContainerAllocator::template
rebind< uint16_t >::other > 
_HallResistance_type
typedef ::std_msgs::Header_
< ContainerAllocator > 
_header_type
typedef std::vector< double,
typename
ContainerAllocator::template
rebind< double >::other > 
_MagneticFieldIntensityX_type
typedef std::vector< double,
typename
ContainerAllocator::template
rebind< double >::other > 
_MagneticFieldIntensityY_type
typedef std::vector< double,
typename
ContainerAllocator::template
rebind< double >::other > 
_MagneticFieldIntensityZ_type
typedef std::vector< double,
typename
ContainerAllocator::template
rebind< double >::other > 
_Temperature_type
typedef boost::shared_ptr
< ::bmc050_driver::bmc050_measurement_
< ContainerAllocator > const > 
ConstPtr
typedef boost::shared_ptr
< ::bmc050_driver::bmc050_measurement_
< ContainerAllocator > > 
Ptr
typedef bmc050_measurement_
< ContainerAllocator > 
Type

Public Member Functions

 bmc050_measurement_ ()
 bmc050_measurement_ (const ContainerAllocator &_alloc)

Public Attributes

boost::shared_ptr< std::map
< std::string, std::string > > 
__connection_header
std::vector< double, typename
ContainerAllocator::template
rebind< double >::other > 
AccelerationX
std::vector< double, typename
ContainerAllocator::template
rebind< double >::other > 
AccelerationY
std::vector< double, typename
ContainerAllocator::template
rebind< double >::other > 
AccelerationZ
std::vector< uint16_t,
typename
ContainerAllocator::template
rebind< uint16_t >::other > 
HallResistance
::std_msgs::Header_
< ContainerAllocator > 
header
std::vector< double, typename
ContainerAllocator::template
rebind< double >::other > 
MagneticFieldIntensityX
std::vector< double, typename
ContainerAllocator::template
rebind< double >::other > 
MagneticFieldIntensityY
std::vector< double, typename
ContainerAllocator::template
rebind< double >::other > 
MagneticFieldIntensityZ
std::vector< double, typename
ContainerAllocator::template
rebind< double >::other > 
Temperature

Detailed Description

template<class ContainerAllocator>
struct bmc050_driver::bmc050_measurement_< ContainerAllocator >

Definition at line 22 of file bmc050_measurement.h.


Member Typedef Documentation

template<class ContainerAllocator >
typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::_AccelerationX_type

Definition at line 54 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::_AccelerationY_type

Definition at line 57 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::_AccelerationZ_type

Definition at line 60 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef std::vector<uint16_t, typename ContainerAllocator::template rebind<uint16_t>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::_HallResistance_type

Definition at line 75 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef ::std_msgs::Header_<ContainerAllocator> bmc050_driver::bmc050_measurement_< ContainerAllocator >::_header_type

Definition at line 51 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::_MagneticFieldIntensityX_type

Definition at line 66 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::_MagneticFieldIntensityY_type

Definition at line 69 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::_MagneticFieldIntensityZ_type

Definition at line 72 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::_Temperature_type

Definition at line 63 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef boost::shared_ptr< ::bmc050_driver::bmc050_measurement_<ContainerAllocator> const> bmc050_driver::bmc050_measurement_< ContainerAllocator >::ConstPtr

Definition at line 80 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef boost::shared_ptr< ::bmc050_driver::bmc050_measurement_<ContainerAllocator> > bmc050_driver::bmc050_measurement_< ContainerAllocator >::Ptr

Definition at line 79 of file bmc050_measurement.h.

template<class ContainerAllocator >
typedef bmc050_measurement_<ContainerAllocator> bmc050_driver::bmc050_measurement_< ContainerAllocator >::Type

Definition at line 23 of file bmc050_measurement.h.


Constructor & Destructor Documentation

template<class ContainerAllocator >
bmc050_driver::bmc050_measurement_< ContainerAllocator >::bmc050_measurement_ ( ) [inline]

Definition at line 25 of file bmc050_measurement.h.

template<class ContainerAllocator >
bmc050_driver::bmc050_measurement_< ContainerAllocator >::bmc050_measurement_ ( const ContainerAllocator &  _alloc) [inline]

Definition at line 38 of file bmc050_measurement.h.


Member Data Documentation

template<class ContainerAllocator >
boost::shared_ptr<std::map<std::string, std::string> > bmc050_driver::bmc050_measurement_< ContainerAllocator >::__connection_header

Definition at line 81 of file bmc050_measurement.h.

template<class ContainerAllocator >
std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::AccelerationX

Definition at line 55 of file bmc050_measurement.h.

template<class ContainerAllocator >
std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::AccelerationY

Definition at line 58 of file bmc050_measurement.h.

template<class ContainerAllocator >
std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::AccelerationZ

Definition at line 61 of file bmc050_measurement.h.

template<class ContainerAllocator >
std::vector<uint16_t, typename ContainerAllocator::template rebind<uint16_t>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::HallResistance

Definition at line 76 of file bmc050_measurement.h.

template<class ContainerAllocator >
::std_msgs::Header_<ContainerAllocator> bmc050_driver::bmc050_measurement_< ContainerAllocator >::header

Definition at line 52 of file bmc050_measurement.h.

template<class ContainerAllocator >
std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::MagneticFieldIntensityX

Definition at line 67 of file bmc050_measurement.h.

template<class ContainerAllocator >
std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::MagneticFieldIntensityY

Definition at line 70 of file bmc050_measurement.h.

template<class ContainerAllocator >
std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::MagneticFieldIntensityZ

Definition at line 73 of file bmc050_measurement.h.

template<class ContainerAllocator >
std::vector<double, typename ContainerAllocator::template rebind<double>::other > bmc050_driver::bmc050_measurement_< ContainerAllocator >::Temperature

Definition at line 64 of file bmc050_measurement.h.


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


bmc050_driver
Author(s): Joshua Vasquez, Philip Roan. Maintained by Philip Roan
autogenerated on Sat Dec 28 2013 16:48:51