#include <SensorState.h>
Public Types | |
enum | { Button0 = 1 } |
enum | { Button1 = 2 } |
enum | { Button2 = 4 } |
enum | { ADAPTER = 16 } |
enum | { DISCHARGING = 0 } |
enum | { CHARGED = 2 } |
enum | { CHARGING = 6 } |
typedef std::vector< uint16_t, typename ContainerAllocator::template rebind< uint16_t >::other > | _analog_input_type |
typedef uint8_t | _battery_type |
typedef std::vector< uint16_t, typename ContainerAllocator::template rebind< uint16_t >::other > | _bottom_type |
typedef uint8_t | _bumper_type |
typedef uint8_t | _buttons_type |
typedef uint8_t | _charger_type |
typedef uint8_t | _cliff_type |
typedef std::vector< uint8_t, typename ContainerAllocator::template rebind< uint8_t >::other > | _current_type |
typedef uint16_t | _digital_input_type |
typedef ::std_msgs::Header_ < ContainerAllocator > | _header_type |
typedef uint16_t | _left_encoder_type |
typedef int8_t | _left_pwm_type |
typedef uint16_t | _right_encoder_type |
typedef int8_t | _right_pwm_type |
typedef uint16_t | _time_stamp_type |
typedef uint8_t | _wheel_drop_type |
typedef boost::shared_ptr < ::kobuki_comms::SensorState_ < ContainerAllocator > const > | ConstPtr |
typedef boost::shared_ptr < ::kobuki_comms::SensorState_ < ContainerAllocator > > | Ptr |
typedef SensorState_ < ContainerAllocator > | Type |
Public Member Functions | |
SensorState_ () | |
SensorState_ (const ContainerAllocator &_alloc) | |
Public Attributes | |
boost::shared_ptr< std::map < std::string, std::string > > | __connection_header |
std::vector< uint16_t, typename ContainerAllocator::template rebind< uint16_t >::other > | analog_input |
uint8_t | battery |
std::vector< uint16_t, typename ContainerAllocator::template rebind< uint16_t >::other > | bottom |
uint8_t | bumper |
uint8_t | buttons |
uint8_t | charger |
uint8_t | cliff |
std::vector< uint8_t, typename ContainerAllocator::template rebind< uint8_t >::other > | current |
uint16_t | digital_input |
::std_msgs::Header_ < ContainerAllocator > | header |
uint16_t | left_encoder |
int8_t | left_pwm |
uint16_t | right_encoder |
int8_t | right_pwm |
uint16_t | time_stamp |
uint8_t | wheel_drop |
Definition at line 22 of file SensorState.h.
typedef std::vector<uint16_t, typename ContainerAllocator::template rebind<uint16_t>::other > kobuki_comms::SensorState_< ContainerAllocator >::_analog_input_type |
Definition at line 110 of file SensorState.h.
typedef uint8_t kobuki_comms::SensorState_< ContainerAllocator >::_battery_type |
Definition at line 98 of file SensorState.h.
typedef std::vector<uint16_t, typename ContainerAllocator::template rebind<uint16_t>::other > kobuki_comms::SensorState_< ContainerAllocator >::_bottom_type |
Definition at line 101 of file SensorState.h.
typedef uint8_t kobuki_comms::SensorState_< ContainerAllocator >::_bumper_type |
Definition at line 71 of file SensorState.h.
typedef uint8_t kobuki_comms::SensorState_< ContainerAllocator >::_buttons_type |
Definition at line 92 of file SensorState.h.
typedef uint8_t kobuki_comms::SensorState_< ContainerAllocator >::_charger_type |
Definition at line 95 of file SensorState.h.
typedef uint8_t kobuki_comms::SensorState_< ContainerAllocator >::_cliff_type |
Definition at line 77 of file SensorState.h.
typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > kobuki_comms::SensorState_< ContainerAllocator >::_current_type |
Definition at line 104 of file SensorState.h.
typedef uint16_t kobuki_comms::SensorState_< ContainerAllocator >::_digital_input_type |
Definition at line 107 of file SensorState.h.
typedef ::std_msgs::Header_<ContainerAllocator> kobuki_comms::SensorState_< ContainerAllocator >::_header_type |
Definition at line 65 of file SensorState.h.
typedef uint16_t kobuki_comms::SensorState_< ContainerAllocator >::_left_encoder_type |
Definition at line 80 of file SensorState.h.
typedef int8_t kobuki_comms::SensorState_< ContainerAllocator >::_left_pwm_type |
Definition at line 86 of file SensorState.h.
typedef uint16_t kobuki_comms::SensorState_< ContainerAllocator >::_right_encoder_type |
Definition at line 83 of file SensorState.h.
typedef int8_t kobuki_comms::SensorState_< ContainerAllocator >::_right_pwm_type |
Definition at line 89 of file SensorState.h.
typedef uint16_t kobuki_comms::SensorState_< ContainerAllocator >::_time_stamp_type |
Definition at line 68 of file SensorState.h.
typedef uint8_t kobuki_comms::SensorState_< ContainerAllocator >::_wheel_drop_type |
Definition at line 74 of file SensorState.h.
typedef boost::shared_ptr< ::kobuki_comms::SensorState_<ContainerAllocator> const> kobuki_comms::SensorState_< ContainerAllocator >::ConstPtr |
Definition at line 122 of file SensorState.h.
typedef boost::shared_ptr< ::kobuki_comms::SensorState_<ContainerAllocator> > kobuki_comms::SensorState_< ContainerAllocator >::Ptr |
Definition at line 121 of file SensorState.h.
typedef SensorState_<ContainerAllocator> kobuki_comms::SensorState_< ContainerAllocator >::Type |
Definition at line 23 of file SensorState.h.
anonymous enum |
Definition at line 113 of file SensorState.h.
anonymous enum |
Definition at line 114 of file SensorState.h.
anonymous enum |
Definition at line 115 of file SensorState.h.
anonymous enum |
Definition at line 116 of file SensorState.h.
anonymous enum |
Definition at line 117 of file SensorState.h.
anonymous enum |
Definition at line 118 of file SensorState.h.
anonymous enum |
Definition at line 119 of file SensorState.h.
kobuki_comms::SensorState_< ContainerAllocator >::SensorState_ | ( | ) | [inline] |
Definition at line 25 of file SensorState.h.
kobuki_comms::SensorState_< ContainerAllocator >::SensorState_ | ( | const ContainerAllocator & | _alloc | ) | [inline] |
Definition at line 45 of file SensorState.h.
boost::shared_ptr<std::map<std::string, std::string> > kobuki_comms::SensorState_< ContainerAllocator >::__connection_header |
Definition at line 123 of file SensorState.h.
std::vector<uint16_t, typename ContainerAllocator::template rebind<uint16_t>::other > kobuki_comms::SensorState_< ContainerAllocator >::analog_input |
Definition at line 111 of file SensorState.h.
uint8_t kobuki_comms::SensorState_< ContainerAllocator >::battery |
Definition at line 99 of file SensorState.h.
std::vector<uint16_t, typename ContainerAllocator::template rebind<uint16_t>::other > kobuki_comms::SensorState_< ContainerAllocator >::bottom |
Definition at line 102 of file SensorState.h.
uint8_t kobuki_comms::SensorState_< ContainerAllocator >::bumper |
Definition at line 72 of file SensorState.h.
uint8_t kobuki_comms::SensorState_< ContainerAllocator >::buttons |
Definition at line 93 of file SensorState.h.
uint8_t kobuki_comms::SensorState_< ContainerAllocator >::charger |
Definition at line 96 of file SensorState.h.
uint8_t kobuki_comms::SensorState_< ContainerAllocator >::cliff |
Definition at line 78 of file SensorState.h.
std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other > kobuki_comms::SensorState_< ContainerAllocator >::current |
Definition at line 105 of file SensorState.h.
uint16_t kobuki_comms::SensorState_< ContainerAllocator >::digital_input |
Definition at line 108 of file SensorState.h.
::std_msgs::Header_<ContainerAllocator> kobuki_comms::SensorState_< ContainerAllocator >::header |
Definition at line 66 of file SensorState.h.
uint16_t kobuki_comms::SensorState_< ContainerAllocator >::left_encoder |
Definition at line 81 of file SensorState.h.
int8_t kobuki_comms::SensorState_< ContainerAllocator >::left_pwm |
Definition at line 87 of file SensorState.h.
uint16_t kobuki_comms::SensorState_< ContainerAllocator >::right_encoder |
Definition at line 84 of file SensorState.h.
int8_t kobuki_comms::SensorState_< ContainerAllocator >::right_pwm |
Definition at line 90 of file SensorState.h.
uint16_t kobuki_comms::SensorState_< ContainerAllocator >::time_stamp |
Definition at line 69 of file SensorState.h.
uint8_t kobuki_comms::SensorState_< ContainerAllocator >::wheel_drop |
Definition at line 75 of file SensorState.h.