BatteryState.h
Go to the documentation of this file.
1 // Generated by gencpp from file sensor_msgs/BatteryState.msg
2 // DO NOT EDIT!
3 
4 
5 #ifndef SENSOR_MSGS_MESSAGE_BATTERYSTATE_H
6 #define SENSOR_MSGS_MESSAGE_BATTERYSTATE_H
7 
8 
9 #include <string>
10 #include <vector>
11 #include <map>
12 
13 #include <ros/types.h>
14 #include <ros/serialization.h>
16 #include <ros/message_operations.h>
17 
18 #include <std_msgs/Header.h>
19 
20 namespace sensor_msgs
21 {
22 template <class ContainerAllocator>
24 {
26 
28  : header()
29  , voltage(0.0)
30  , current(0.0)
31  , charge(0.0)
32  , capacity(0.0)
33  , design_capacity(0.0)
34  , percentage(0.0)
38  , present(false)
39  , cell_voltage()
40  , location()
41  , serial_number() {
42  }
43  BatteryState_(const ContainerAllocator& _alloc)
44  : header(_alloc)
45  , voltage(0.0)
46  , current(0.0)
47  , charge(0.0)
48  , capacity(0.0)
49  , design_capacity(0.0)
50  , percentage(0.0)
54  , present(false)
55  , cell_voltage(_alloc)
56  , location(_alloc)
57  , serial_number(_alloc) {
58  (void)_alloc;
59  }
60 
61 
62 
63  typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
65 
66  typedef float _voltage_type;
68 
69  typedef float _current_type;
71 
72  typedef float _charge_type;
74 
75  typedef float _capacity_type;
77 
78  typedef float _design_capacity_type;
80 
81  typedef float _percentage_type;
83 
86 
89 
92 
95 
96  typedef std::vector<float, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< float > > _cell_voltage_type;
98 
99  typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _location_type;
101 
102  typedef std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _serial_number_type;
104 
105 
127 
128 
129  typedef std::shared_ptr< ::sensor_msgs::BatteryState_<ContainerAllocator> > Ptr;
130  typedef std::shared_ptr< ::sensor_msgs::BatteryState_<ContainerAllocator> const> ConstPtr;
131 
132 }; // struct BatteryState_
133 
134 typedef ::sensor_msgs::BatteryState_<std::allocator<void> > BatteryState;
135 
136 typedef std::shared_ptr< ::sensor_msgs::BatteryState > BatteryStatePtr;
137 typedef std::shared_ptr< ::sensor_msgs::BatteryState const> BatteryStateConstPtr;
138 
139 // constants requiring out of line definition
140 
141 
142 
143 
144 
145 
146 
147 
148 
149 
150 
151 
152 
153 
154 
155 
156 
157 
158 
159 
160 
161 
162 
163 
164 
165 
166 
167 
168 
169 
170 
171 
172 
173 
174 
175 
176 
177 
178 
179 
180 
181 
182 
183 
184 
185 template<typename ContainerAllocator>
186 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::BatteryState_<ContainerAllocator> & v)
187 {
189 return s;
190 }
191 
192 } // namespace sensor_msgs
193 
194 namespace rs2rosinternal
195 {
196 namespace message_traits
197 {
198 
199 
200 
201 // BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True}
202 // {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']}
203 
204 // !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types']
205 
206 
207 
208 
209 template <class ContainerAllocator>
210 struct IsFixedSize< ::sensor_msgs::BatteryState_<ContainerAllocator> >
211  : std::false_type
212  { };
213 
214 template <class ContainerAllocator>
215 struct IsFixedSize< ::sensor_msgs::BatteryState_<ContainerAllocator> const>
216  : std::false_type
217  { };
218 
219 template <class ContainerAllocator>
220 struct IsMessage< ::sensor_msgs::BatteryState_<ContainerAllocator> >
221  : std::true_type
222  { };
223 
224 template <class ContainerAllocator>
225 struct IsMessage< ::sensor_msgs::BatteryState_<ContainerAllocator> const>
226  : std::true_type
227  { };
228 
229 template <class ContainerAllocator>
230 struct HasHeader< ::sensor_msgs::BatteryState_<ContainerAllocator> >
231  : std::true_type
232  { };
233 
234 template <class ContainerAllocator>
235 struct HasHeader< ::sensor_msgs::BatteryState_<ContainerAllocator> const>
236  : std::true_type
237  { };
238 
239 
240 template<class ContainerAllocator>
241 struct MD5Sum< ::sensor_msgs::BatteryState_<ContainerAllocator> >
242 {
243  static const char* value()
244  {
245  return "476f837fa6771f6e16e3bf4ef96f8770";
246  }
247 
248  static const char* value(const ::sensor_msgs::BatteryState_<ContainerAllocator>&) { return value(); }
249  static const uint64_t static_value1 = 0x476f837fa6771f6eULL;
250  static const uint64_t static_value2 = 0x16e3bf4ef96f8770ULL;
251 };
252 
253 template<class ContainerAllocator>
254 struct DataType< ::sensor_msgs::BatteryState_<ContainerAllocator> >
255 {
256  static const char* value()
257  {
258  return "sensor_msgs/BatteryState";
259  }
260 
261  static const char* value(const ::sensor_msgs::BatteryState_<ContainerAllocator>&) { return value(); }
262 };
263 
264 template<class ContainerAllocator>
265 struct Definition< ::sensor_msgs::BatteryState_<ContainerAllocator> >
266 {
267  static const char* value()
268  {
269  return "\n\
270 # Constants are chosen to match the enums in the linux kernel\n\
271 # defined in include/linux/power_supply.h as of version 3.7\n\
272 # The one difference is for style reasons the constants are\n\
273 # all uppercase not mixed case.\n\
274 \n\
275 # Power supply status constants\n\
276 uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0\n\
277 uint8 POWER_SUPPLY_STATUS_CHARGING = 1\n\
278 uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2\n\
279 uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3\n\
280 uint8 POWER_SUPPLY_STATUS_FULL = 4\n\
281 \n\
282 # Power supply health constants\n\
283 uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0\n\
284 uint8 POWER_SUPPLY_HEALTH_GOOD = 1\n\
285 uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2\n\
286 uint8 POWER_SUPPLY_HEALTH_DEAD = 3\n\
287 uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4\n\
288 uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5\n\
289 uint8 POWER_SUPPLY_HEALTH_COLD = 6\n\
290 uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7\n\
291 uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8\n\
292 \n\
293 # Power supply technology (chemistry) constants\n\
294 uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0\n\
295 uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1\n\
296 uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2\n\
297 uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3\n\
298 uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4\n\
299 uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5\n\
300 uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6\n\
301 \n\
302 Header header\n\
303 float32 voltage # Voltage in Volts (Mandatory)\n\
304 float32 current # Negative when discharging (A) (If unmeasured NaN)\n\
305 float32 charge # Current charge in Ah (If unmeasured NaN)\n\
306 float32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN)\n\
307 float32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN)\n\
308 float32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN)\n\
309 uint8 power_supply_status # The charging status as reported. Values defined above\n\
310 uint8 power_supply_health # The battery health metric. Values defined above\n\
311 uint8 power_supply_technology # The battery chemistry. Values defined above\n\
312 bool present # True if the battery is present\n\
313 \n\
314 float32[] cell_voltage # An array of individual cell voltages for each cell in the pack\n\
315  # If individual voltages unknown but number of cells known set each to NaN\n\
316 string location # The location into which the battery is inserted. (slot number or plug)\n\
317 string serial_number # The best approximation of the battery serial number\n\
318 \n\
319 ================================================================================\n\
320 MSG: std_msgs/Header\n\
321 # Standard metadata for higher-level stamped data types.\n\
322 # This is generally used to communicate timestamped data \n\
323 # in a particular coordinate frame.\n\
324 # \n\
325 # sequence ID: consecutively increasing ID \n\
326 uint32 seq\n\
327 #Two-integer timestamp that is expressed as:\n\
328 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
329 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
330 # time-handling sugar is provided by the client library\n\
331 time stamp\n\
332 #Frame this data is associated with\n\
333 # 0: no frame\n\
334 # 1: global frame\n\
335 string frame_id\n\
336 ";
337  }
338 
339  static const char* value(const ::sensor_msgs::BatteryState_<ContainerAllocator>&) { return value(); }
340 };
341 
342 } // namespace message_traits
343 } // namespace rs2rosinternal
344 
345 namespace rs2rosinternal
346 {
347 namespace serialization
348 {
349 
350  template<class ContainerAllocator> struct Serializer< ::sensor_msgs::BatteryState_<ContainerAllocator> >
351  {
352  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
353  {
354  stream.next(m.header);
355  stream.next(m.voltage);
356  stream.next(m.current);
357  stream.next(m.charge);
358  stream.next(m.capacity);
359  stream.next(m.design_capacity);
360  stream.next(m.percentage);
361  stream.next(m.power_supply_status);
362  stream.next(m.power_supply_health);
363  stream.next(m.power_supply_technology);
364  stream.next(m.present);
365  stream.next(m.cell_voltage);
366  stream.next(m.location);
367  stream.next(m.serial_number);
368  }
369 
371  }; // struct BatteryState_
372 
373 } // namespace serialization
374 } // namespace rs2rosinternal
375 
376 namespace rs2rosinternal
377 {
378 namespace message_operations
379 {
380 
381 template<class ContainerAllocator>
382 struct Printer< ::sensor_msgs::BatteryState_<ContainerAllocator> >
383 {
384  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::BatteryState_<ContainerAllocator>& v)
385  {
386  s << indent << "header: ";
387  s << std::endl;
389  s << indent << "voltage: ";
390  Printer<float>::stream(s, indent + " ", v.voltage);
391  s << indent << "current: ";
392  Printer<float>::stream(s, indent + " ", v.current);
393  s << indent << "charge: ";
394  Printer<float>::stream(s, indent + " ", v.charge);
395  s << indent << "capacity: ";
396  Printer<float>::stream(s, indent + " ", v.capacity);
397  s << indent << "design_capacity: ";
398  Printer<float>::stream(s, indent + " ", v.design_capacity);
399  s << indent << "percentage: ";
400  Printer<float>::stream(s, indent + " ", v.percentage);
401  s << indent << "power_supply_status: ";
402  Printer<uint8_t>::stream(s, indent + " ", v.power_supply_status);
403  s << indent << "power_supply_health: ";
404  Printer<uint8_t>::stream(s, indent + " ", v.power_supply_health);
405  s << indent << "power_supply_technology: ";
406  Printer<uint8_t>::stream(s, indent + " ", v.power_supply_technology);
407  s << indent << "present: ";
408  Printer<uint8_t>::stream(s, indent + " ", v.present);
409  s << indent << "cell_voltage[]" << std::endl;
410  for (size_t i = 0; i < v.cell_voltage.size(); ++i)
411  {
412  s << indent << " cell_voltage[" << i << "]: ";
413  Printer<float>::stream(s, indent + " ", v.cell_voltage[i]);
414  }
415  s << indent << "location: ";
416  Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.location);
417  s << indent << "serial_number: ";
418  Printer<std::basic_string<char, std::char_traits<char>, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > >::stream(s, indent + " ", v.serial_number);
419  }
420 };
421 
422 } // namespace message_operations
423 } // namespace rs2rosinternal
424 
425 #endif // SENSOR_MSGS_MESSAGE_BATTERYSTATE_H
sensor_msgs::BatteryStateConstPtr
std::shared_ptr< ::sensor_msgs::BatteryState const > BatteryStateConstPtr
Definition: BatteryState.h:137
uint8_t
unsigned char uint8_t
Definition: stdint.h:78
sensor_msgs::BatteryState_::cell_voltage
_cell_voltage_type cell_voltage
Definition: BatteryState.h:97
sensor_msgs::BatteryState_::Type
BatteryState_< ContainerAllocator > Type
Definition: BatteryState.h:25
sensor_msgs::BatteryState_::_charge_type
float _charge_type
Definition: BatteryState.h:72
sensor_msgs::BatteryState_::POWER_SUPPLY_HEALTH_DEAD
@ POWER_SUPPLY_HEALTH_DEAD
Definition: BatteryState.h:114
sensor_msgs::BatteryState_::current
_current_type current
Definition: BatteryState.h:70
sensor_msgs::BatteryState_::POWER_SUPPLY_STATUS_UNKNOWN
@ POWER_SUPPLY_STATUS_UNKNOWN
Definition: BatteryState.h:106
sensor_msgs::BatteryState_::POWER_SUPPLY_TECHNOLOGY_LIMN
@ POWER_SUPPLY_TECHNOLOGY_LIMN
Definition: BatteryState.h:126
sensor_msgs::BatteryState_::_power_supply_technology_type
uint8_t _power_supply_technology_type
Definition: BatteryState.h:90
sensor_msgs::BatteryState_::_power_supply_status_type
uint8_t _power_supply_status_type
Definition: BatteryState.h:84
sensor_msgs::BatteryState_::power_supply_status
_power_supply_status_type power_supply_status
Definition: BatteryState.h:85
sensor_msgs::BatteryState_::_design_capacity_type
float _design_capacity_type
Definition: BatteryState.h:78
sensor_msgs::BatteryState_::_current_type
float _current_type
Definition: BatteryState.h:69
v
GLdouble v
Definition: glad/glad/glad.h:2144
sensor_msgs::BatteryState_::_header_type
::std_msgs::Header_< ContainerAllocator > _header_type
Definition: BatteryState.h:63
string
GLsizei const GLchar *const * string
Definition: glad/glad/glad.h:2861
rs2rosinternal::message_operations::Printer< ::sensor_msgs::BatteryState_< ContainerAllocator > >::stream
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::BatteryState_< ContainerAllocator > &v)
Definition: BatteryState.h:384
sensor_msgs::BatteryState_::ConstPtr
std::shared_ptr< ::sensor_msgs::BatteryState_< ContainerAllocator > const > ConstPtr
Definition: BatteryState.h:130
sensor_msgs::BatteryState_::_power_supply_health_type
uint8_t _power_supply_health_type
Definition: BatteryState.h:87
void
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
sensor_msgs::BatteryState_::_capacity_type
float _capacity_type
Definition: BatteryState.h:75
sensor_msgs::BatteryState_::POWER_SUPPLY_TECHNOLOGY_NIMH
@ POWER_SUPPLY_TECHNOLOGY_NIMH
Definition: BatteryState.h:121
sensor_msgs::BatteryState_::POWER_SUPPLY_HEALTH_UNKNOWN
@ POWER_SUPPLY_HEALTH_UNKNOWN
Definition: BatteryState.h:111
rs2rosinternal::message_traits::IsFixedSize
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
Definition: message_traits.h:81
sensor_msgs::BatteryState_::serial_number
_serial_number_type serial_number
Definition: BatteryState.h:103
rs2rosinternal
Definition: datatypes.h:39
sensor_msgs::BatteryState_::POWER_SUPPLY_STATUS_FULL
@ POWER_SUPPLY_STATUS_FULL
Definition: BatteryState.h:110
sensor_msgs::BatteryState_::voltage
_voltage_type voltage
Definition: BatteryState.h:67
sensor_msgs::BatteryState_::POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE
@ POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE
Definition: BatteryState.h:119
sensor_msgs::BatteryState_::_serial_number_type
std::basic_string< char, std::char_traits< char >, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _serial_number_type
Definition: BatteryState.h:102
sensor_msgs::BatteryState_::BatteryState_
BatteryState_()
Definition: BatteryState.h:27
sensor_msgs::BatteryState_::header
_header_type header
Definition: BatteryState.h:64
sensor_msgs::BatteryState_::present
_present_type present
Definition: BatteryState.h:94
serialization.h
sensor_msgs::BatteryState_::_percentage_type
float _percentage_type
Definition: BatteryState.h:81
rs2rosinternal::message_traits::IsMessage
Am I message or not.
Definition: message_traits.h:90
sensor_msgs::BatteryState_::POWER_SUPPLY_TECHNOLOGY_LION
@ POWER_SUPPLY_TECHNOLOGY_LION
Definition: BatteryState.h:122
m
std::mutex m
Definition: test-waiting-on.cpp:126
sensor_msgs::BatteryState_::capacity
_capacity_type capacity
Definition: BatteryState.h:76
sensor_msgs::BatteryState_::charge
_charge_type charge
Definition: BatteryState.h:73
builtin_message_traits.h
sensor_msgs::BatteryState_::POWER_SUPPLY_TECHNOLOGY_NICD
@ POWER_SUPPLY_TECHNOLOGY_NICD
Definition: BatteryState.h:125
sensor_msgs::operator<<
std::ostream & operator<<(std::ostream &s, const ::sensor_msgs::BatteryState_< ContainerAllocator > &v)
Definition: BatteryState.h:186
sensor_msgs::BatteryState_::POWER_SUPPLY_STATUS_DISCHARGING
@ POWER_SUPPLY_STATUS_DISCHARGING
Definition: BatteryState.h:108
sensor_msgs::BatteryState_
Definition: BatteryState.h:23
sensor_msgs::BatteryState_::POWER_SUPPLY_HEALTH_UNSPEC_FAILURE
@ POWER_SUPPLY_HEALTH_UNSPEC_FAILURE
Definition: BatteryState.h:116
uint64_t
unsigned __int64 uint64_t
Definition: stdint.h:90
i
int i
Definition: rs-pcl-color.cpp:54
sensor_msgs::BatteryState_::_location_type
std::basic_string< char, std::char_traits< char >, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< char > > _location_type
Definition: BatteryState.h:99
location
GLint location
Definition: glad/glad/glad.h:2834
sensor_msgs::BatteryState_::power_supply_technology
_power_supply_technology_type power_supply_technology
Definition: BatteryState.h:91
sensor_msgs::BatteryState_::POWER_SUPPLY_HEALTH_OVERHEAT
@ POWER_SUPPLY_HEALTH_OVERHEAT
Definition: BatteryState.h:113
sensor_msgs::BatteryState_::POWER_SUPPLY_STATUS_CHARGING
@ POWER_SUPPLY_STATUS_CHARGING
Definition: BatteryState.h:107
sensor_msgs::BatteryState_::_present_type
uint8_t _present_type
Definition: BatteryState.h:93
sensor_msgs::BatteryState_::Ptr
std::shared_ptr< ::sensor_msgs::BatteryState_< ContainerAllocator > > Ptr
Definition: BatteryState.h:129
sensor_msgs::BatteryState_::design_capacity
_design_capacity_type design_capacity
Definition: BatteryState.h:79
std_msgs::Header_
Definition: Header.h:22
test-device-discovery.stream
stream
Definition: test-device-discovery.py:295
rspy.log.indent
def indent(str, line_prefix=' ')
Definition: log.py:122
sensor_msgs::BatteryState_::location
_location_type location
Definition: BatteryState.h:100
sensor_msgs::BatteryState_::POWER_SUPPLY_HEALTH_COLD
@ POWER_SUPPLY_HEALTH_COLD
Definition: BatteryState.h:117
rs2rosinternal::message_traits::Definition< ::sensor_msgs::BatteryState_< ContainerAllocator > >::value
static const char * value(const ::sensor_msgs::BatteryState_< ContainerAllocator > &)
Definition: BatteryState.h:339
sensor_msgs::BatteryState
::sensor_msgs::BatteryState_< std::allocator< void > > BatteryState
Definition: BatteryState.h:134
rs2rosinternal::message_traits::Definition
Specialize to provide the definition for a message.
Definition: message_traits.h:130
rs2rosinternal::message_traits::DataType< ::sensor_msgs::BatteryState_< ContainerAllocator > >::value
static const char * value(const ::sensor_msgs::BatteryState_< ContainerAllocator > &)
Definition: BatteryState.h:261
rs2rosinternal::message_traits::MD5Sum
Specialize to provide the md5sum for a message.
Definition: message_traits.h:96
sensor_msgs::BatteryState_::POWER_SUPPLY_HEALTH_GOOD
@ POWER_SUPPLY_HEALTH_GOOD
Definition: BatteryState.h:112
sensor_msgs::BatteryState_::power_supply_health
_power_supply_health_type power_supply_health
Definition: BatteryState.h:88
sensor_msgs::BatteryState_::POWER_SUPPLY_HEALTH_OVERVOLTAGE
@ POWER_SUPPLY_HEALTH_OVERVOLTAGE
Definition: BatteryState.h:115
rs2rosinternal::serialization::Serializer
Templated serialization class. Default implementation provides backwards compatibility with old messa...
Definition: third-party/realsense-file/rosbag/roscpp_serialization/include/ros/serialization.h:111
rs2rosinternal::message_traits::HasHeader
HasHeader informs whether or not there is a header that gets serialized as the first thing in the mes...
Definition: message_traits.h:85
rs2rosinternal::serialization::Serializer< ::sensor_msgs::BatteryState_< ContainerAllocator > >::allInOne
static void allInOne(Stream &stream, T m)
Definition: BatteryState.h:352
rs2rosinternal::message_traits::Definition< ::sensor_msgs::BatteryState_< ContainerAllocator > >::value
static const char * value()
Definition: BatteryState.h:267
sensor_msgs::BatteryState_::POWER_SUPPLY_TECHNOLOGY_LIFE
@ POWER_SUPPLY_TECHNOLOGY_LIFE
Definition: BatteryState.h:124
sensor_msgs::BatteryState_::POWER_SUPPLY_STATUS_NOT_CHARGING
@ POWER_SUPPLY_STATUS_NOT_CHARGING
Definition: BatteryState.h:109
ROS_DECLARE_ALLINONE_SERIALIZER
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
Definition: third-party/realsense-file/rosbag/roscpp_serialization/include/ros/serialization.h:66
sensor_msgs::BatteryState_::POWER_SUPPLY_TECHNOLOGY_UNKNOWN
@ POWER_SUPPLY_TECHNOLOGY_UNKNOWN
Definition: BatteryState.h:120
sensor_msgs::BatteryState_::_voltage_type
float _voltage_type
Definition: BatteryState.h:66
rs2rosinternal::message_operations::Printer::stream
static void stream(Stream &s, const std::string &indent, const M &value)
Definition: message_operations.h:42
rs2rosinternal::message_operations::Printer
Definition: message_operations.h:39
rs2rosinternal::message_traits::DataType
Specialize to provide the datatype for a message.
Definition: message_traits.h:113
sensor_msgs::BatteryStatePtr
std::shared_ptr< ::sensor_msgs::BatteryState > BatteryStatePtr
Definition: BatteryState.h:136
rs2rosinternal::message_traits::MD5Sum< ::sensor_msgs::BatteryState_< ContainerAllocator > >::value
static const char * value()
Definition: BatteryState.h:243
sensor_msgs::BatteryState_::POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE
@ POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE
Definition: BatteryState.h:118
rs2rosinternal::serialization::Stream
Stream base-class, provides common functionality for IStream and OStream.
Definition: third-party/realsense-file/rosbag/roscpp_serialization/include/ros/serialization.h:694
sensor_msgs
Tools for manipulating sensor_msgs.
Definition: image-msg.h:23
sensor_msgs::BatteryState_::POWER_SUPPLY_TECHNOLOGY_LIPO
@ POWER_SUPPLY_TECHNOLOGY_LIPO
Definition: BatteryState.h:123
rs2rosinternal::message_traits::DataType< ::sensor_msgs::BatteryState_< ContainerAllocator > >::value
static const char * value()
Definition: BatteryState.h:256
s
GLdouble s
Definition: glad/glad/glad.h:2441
Header.h
rs2rosinternal::message_traits::MD5Sum< ::sensor_msgs::BatteryState_< ContainerAllocator > >::value
static const char * value(const ::sensor_msgs::BatteryState_< ContainerAllocator > &)
Definition: BatteryState.h:248
types.h
message_operations.h
sensor_msgs::BatteryState_::BatteryState_
BatteryState_(const ContainerAllocator &_alloc)
Definition: BatteryState.h:43
sensor_msgs::BatteryState_::percentage
_percentage_type percentage
Definition: BatteryState.h:82
sensor_msgs::BatteryState_::_cell_voltage_type
std::vector< float, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< float > > _cell_voltage_type
Definition: BatteryState.h:96


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Mon Apr 22 2024 02:12:55