00001
00002 #ifndef WIIMOTE_MESSAGE_STATE_H
00003 #define WIIMOTE_MESSAGE_STATE_H
00004 #include <string>
00005 #include <vector>
00006 #include <map>
00007 #include <ostream>
00008 #include "ros/serialization.h"
00009 #include "ros/builtin_message_traits.h"
00010 #include "ros/message_operations.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/macros.h"
00014
00015 #include "ros/assert.h"
00016
00017 #include "std_msgs/Header.h"
00018 #include "geometry_msgs/Vector3.h"
00019 #include "geometry_msgs/Vector3.h"
00020 #include "geometry_msgs/Vector3.h"
00021 #include "geometry_msgs/Vector3.h"
00022 #include "geometry_msgs/Vector3.h"
00023 #include "geometry_msgs/Vector3.h"
00024 #include "wiimote/IrSourceInfo.h"
00025
00026 namespace wiimote
00027 {
00028 template <class ContainerAllocator>
00029 struct State_ {
00030 typedef State_<ContainerAllocator> Type;
00031
00032 State_()
00033 : header()
00034 , angular_velocity_zeroed()
00035 , angular_velocity_raw()
00036 , angular_velocity_covariance()
00037 , linear_acceleration_zeroed()
00038 , linear_acceleration_raw()
00039 , linear_acceleration_covariance()
00040 , nunchuk_acceleration_zeroed()
00041 , nunchuk_acceleration_raw()
00042 , nunchuk_joystick_zeroed()
00043 , nunchuk_joystick_raw()
00044 , buttons()
00045 , nunchuk_buttons()
00046 , LEDs()
00047 , rumble(false)
00048 , ir_tracking()
00049 , raw_battery(0.0)
00050 , percent_battery(0.0)
00051 , zeroing_time()
00052 , errors(0)
00053 {
00054 angular_velocity_covariance.assign(0.0);
00055 linear_acceleration_covariance.assign(0.0);
00056 nunchuk_joystick_zeroed.assign(0.0);
00057 nunchuk_joystick_raw.assign(0.0);
00058 buttons.assign(false);
00059 nunchuk_buttons.assign(false);
00060 LEDs.assign(false);
00061 }
00062
00063 State_(const ContainerAllocator& _alloc)
00064 : header(_alloc)
00065 , angular_velocity_zeroed(_alloc)
00066 , angular_velocity_raw(_alloc)
00067 , angular_velocity_covariance()
00068 , linear_acceleration_zeroed(_alloc)
00069 , linear_acceleration_raw(_alloc)
00070 , linear_acceleration_covariance()
00071 , nunchuk_acceleration_zeroed(_alloc)
00072 , nunchuk_acceleration_raw(_alloc)
00073 , nunchuk_joystick_zeroed()
00074 , nunchuk_joystick_raw()
00075 , buttons()
00076 , nunchuk_buttons()
00077 , LEDs()
00078 , rumble(false)
00079 , ir_tracking(_alloc)
00080 , raw_battery(0.0)
00081 , percent_battery(0.0)
00082 , zeroing_time()
00083 , errors(0)
00084 {
00085 angular_velocity_covariance.assign(0.0);
00086 linear_acceleration_covariance.assign(0.0);
00087 nunchuk_joystick_zeroed.assign(0.0);
00088 nunchuk_joystick_raw.assign(0.0);
00089 buttons.assign(false);
00090 nunchuk_buttons.assign(false);
00091 LEDs.assign(false);
00092 }
00093
00094 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00095 ::std_msgs::Header_<ContainerAllocator> header;
00096
00097 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _angular_velocity_zeroed_type;
00098 ::geometry_msgs::Vector3_<ContainerAllocator> angular_velocity_zeroed;
00099
00100 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _angular_velocity_raw_type;
00101 ::geometry_msgs::Vector3_<ContainerAllocator> angular_velocity_raw;
00102
00103 typedef boost::array<double, 9> _angular_velocity_covariance_type;
00104 boost::array<double, 9> angular_velocity_covariance;
00105
00106 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _linear_acceleration_zeroed_type;
00107 ::geometry_msgs::Vector3_<ContainerAllocator> linear_acceleration_zeroed;
00108
00109 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _linear_acceleration_raw_type;
00110 ::geometry_msgs::Vector3_<ContainerAllocator> linear_acceleration_raw;
00111
00112 typedef boost::array<double, 9> _linear_acceleration_covariance_type;
00113 boost::array<double, 9> linear_acceleration_covariance;
00114
00115 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _nunchuk_acceleration_zeroed_type;
00116 ::geometry_msgs::Vector3_<ContainerAllocator> nunchuk_acceleration_zeroed;
00117
00118 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _nunchuk_acceleration_raw_type;
00119 ::geometry_msgs::Vector3_<ContainerAllocator> nunchuk_acceleration_raw;
00120
00121 typedef boost::array<float, 2> _nunchuk_joystick_zeroed_type;
00122 boost::array<float, 2> nunchuk_joystick_zeroed;
00123
00124 typedef boost::array<float, 2> _nunchuk_joystick_raw_type;
00125 boost::array<float, 2> nunchuk_joystick_raw;
00126
00127 typedef boost::array<uint8_t, 11> _buttons_type;
00128 boost::array<uint8_t, 11> buttons;
00129
00130 typedef boost::array<uint8_t, 2> _nunchuk_buttons_type;
00131 boost::array<uint8_t, 2> nunchuk_buttons;
00132
00133 typedef boost::array<uint8_t, 4> _LEDs_type;
00134 boost::array<uint8_t, 4> LEDs;
00135
00136 typedef uint8_t _rumble_type;
00137 uint8_t rumble;
00138
00139 typedef std::vector< ::wiimote::IrSourceInfo_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::wiimote::IrSourceInfo_<ContainerAllocator> >::other > _ir_tracking_type;
00140 std::vector< ::wiimote::IrSourceInfo_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::wiimote::IrSourceInfo_<ContainerAllocator> >::other > ir_tracking;
00141
00142 typedef float _raw_battery_type;
00143 float raw_battery;
00144
00145 typedef float _percent_battery_type;
00146 float percent_battery;
00147
00148 typedef ros::Time _zeroing_time_type;
00149 ros::Time zeroing_time;
00150
00151 typedef uint64_t _errors_type;
00152 uint64_t errors;
00153
00154 enum { INVALID = -1 };
00155 static const float INVALID_FLOAT;
00156 enum { MSG_BTN_1 = 0 };
00157 enum { MSG_BTN_2 = 1 };
00158 enum { MSG_BTN_A = 2 };
00159 enum { MSG_BTN_B = 3 };
00160 enum { MSG_BTN_PLUS = 4 };
00161 enum { MSG_BTN_MINUS = 5 };
00162 enum { MSG_BTN_LEFT = 6 };
00163 enum { MSG_BTN_RIGHT = 7 };
00164 enum { MSG_BTN_UP = 8 };
00165 enum { MSG_BTN_DOWN = 9 };
00166 enum { MSG_BTN_HOME = 10 };
00167 enum { MSG_BTN_Z = 0 };
00168 enum { MSG_BTN_C = 1 };
00169 enum { MSG_CLASSIC_BTN_X = 0 };
00170 enum { MSG_CLASSIC_BTN_Y = 1 };
00171 enum { MSG_CLASSIC_BTN_A = 2 };
00172 enum { MSG_CLASSIC_BTN_B = 3 };
00173 enum { MSG_CLASSIC_BTN_PLUS = 4 };
00174 enum { MSG_CLASSIC_BTN_MINUS = 5 };
00175 enum { MSG_CLASSIC_BTN_LEFT = 6 };
00176 enum { MSG_CLASSIC_BTN_RIGHT = 7 };
00177 enum { MSG_CLASSIC_BTN_UP = 8 };
00178 enum { MSG_CLASSIC_BTN_DOWN = 9 };
00179 enum { MSG_CLASSIC_BTN_HOME = 10 };
00180 enum { MSG_CLASSIC_BTN_L = 11 };
00181 enum { MSG_CLASSIC_BTN_R = 12 };
00182 enum { MSG_CLASSIC_BTN_ZL = 13 };
00183 enum { MSG_CLASSIC_BTN_ZR = 14 };
00184
00185 typedef boost::shared_ptr< ::wiimote::State_<ContainerAllocator> > Ptr;
00186 typedef boost::shared_ptr< ::wiimote::State_<ContainerAllocator> const> ConstPtr;
00187 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00188 };
00189 typedef ::wiimote::State_<std::allocator<void> > State;
00190
00191 typedef boost::shared_ptr< ::wiimote::State> StatePtr;
00192 typedef boost::shared_ptr< ::wiimote::State const> StateConstPtr;
00193
00194 template<typename ContainerAllocator> const float State_<ContainerAllocator>::INVALID_FLOAT = -1.0;
00195
00196 template<typename ContainerAllocator>
00197 std::ostream& operator<<(std::ostream& s, const ::wiimote::State_<ContainerAllocator> & v)
00198 {
00199 ros::message_operations::Printer< ::wiimote::State_<ContainerAllocator> >::stream(s, "", v);
00200 return s;}
00201
00202 }
00203
00204 namespace ros
00205 {
00206 namespace message_traits
00207 {
00208 template<class ContainerAllocator> struct IsMessage< ::wiimote::State_<ContainerAllocator> > : public TrueType {};
00209 template<class ContainerAllocator> struct IsMessage< ::wiimote::State_<ContainerAllocator> const> : public TrueType {};
00210 template<class ContainerAllocator>
00211 struct MD5Sum< ::wiimote::State_<ContainerAllocator> > {
00212 static const char* value()
00213 {
00214 return "a69651e8129655c6ed3c5039e468362c";
00215 }
00216
00217 static const char* value(const ::wiimote::State_<ContainerAllocator> &) { return value(); }
00218 static const uint64_t static_value1 = 0xa69651e8129655c6ULL;
00219 static const uint64_t static_value2 = 0xed3c5039e468362cULL;
00220 };
00221
00222 template<class ContainerAllocator>
00223 struct DataType< ::wiimote::State_<ContainerAllocator> > {
00224 static const char* value()
00225 {
00226 return "wiimote/State";
00227 }
00228
00229 static const char* value(const ::wiimote::State_<ContainerAllocator> &) { return value(); }
00230 };
00231
00232 template<class ContainerAllocator>
00233 struct Definition< ::wiimote::State_<ContainerAllocator> > {
00234 static const char* value()
00235 {
00236 return "#\n\
00237 # Wiimote State message containing one complete Wiimote state\n\
00238 \n\
00239 # Note: For ease of manipulation this message often uses\n\
00240 # int8[] when a bit vector would work. One might\n\
00241 # wish to use uint8[], but then Python takes\n\
00242 # the respective structure as a string and disallows\n\
00243 # item assignment.\n\
00244 \n\
00245 int8 INVALID = -1\n\
00246 float32 INVALID_FLOAT = -1.0\n\
00247 \n\
00248 int8 MSG_BTN_1 = 0\n\
00249 int8 MSG_BTN_2 = 1\n\
00250 int8 MSG_BTN_A = 2\n\
00251 int8 MSG_BTN_B = 3\n\
00252 int8 MSG_BTN_PLUS = 4\n\
00253 int8 MSG_BTN_MINUS = 5\n\
00254 int8 MSG_BTN_LEFT = 6\n\
00255 int8 MSG_BTN_RIGHT = 7\n\
00256 int8 MSG_BTN_UP = 8\n\
00257 int8 MSG_BTN_DOWN = 9\n\
00258 int8 MSG_BTN_HOME = 10\n\
00259 int8 MSG_BTN_Z = 0\n\
00260 int8 MSG_BTN_C = 1\n\
00261 int8 MSG_CLASSIC_BTN_X = 0\n\
00262 int8 MSG_CLASSIC_BTN_Y = 1\n\
00263 int8 MSG_CLASSIC_BTN_A = 2\n\
00264 int8 MSG_CLASSIC_BTN_B = 3\n\
00265 int8 MSG_CLASSIC_BTN_PLUS = 4\n\
00266 int8 MSG_CLASSIC_BTN_MINUS = 5\n\
00267 int8 MSG_CLASSIC_BTN_LEFT = 6\n\
00268 int8 MSG_CLASSIC_BTN_RIGHT = 7\n\
00269 int8 MSG_CLASSIC_BTN_UP = 8\n\
00270 int8 MSG_CLASSIC_BTN_DOWN = 9\n\
00271 int8 MSG_CLASSIC_BTN_HOME = 10\n\
00272 int8 MSG_CLASSIC_BTN_L = 11\n\
00273 int8 MSG_CLASSIC_BTN_R = 12\n\
00274 int8 MSG_CLASSIC_BTN_ZL = 13\n\
00275 int8 MSG_CLASSIC_BTN_ZR = 14\n\
00276 \n\
00277 #-----------------------------\n\
00278 # Header\n\
00279 #----------------------\n\
00280 \n\
00281 Header header\n\
00282 \n\
00283 #----------------------\n\
00284 # Gyro reading\n\
00285 #-----------------------------\n\
00286 # In radians/sec. If reading is invalid,\n\
00287 # for instance b/c no gyro is attached to the Wii, then\n\
00288 # set first element of covariance to -1 (same as imu_data.msg):\n\
00289 # Covariance matrix (roll, pitch, yaw) in radians^2/sec^2.\n\
00290 \n\
00291 geometry_msgs/Vector3 angular_velocity_zeroed\n\
00292 geometry_msgs/Vector3 angular_velocity_raw\n\
00293 float64[9] angular_velocity_covariance\n\
00294 \n\
00295 #----------------------\n\
00296 # Accelerometer reading\n\
00297 #-----------------------------\n\
00298 # Acceleration in m/sec^2. Covariance matrix\n\
00299 # (x,y,z) in m^2/sec^4. (all same as imu_data.msg)\n\
00300 \n\
00301 geometry_msgs/Vector3 linear_acceleration_zeroed\n\
00302 geometry_msgs/Vector3 linear_acceleration_raw\n\
00303 float64[9] linear_acceleration_covariance\n\
00304 \n\
00305 #------------------------------\n\
00306 # Nunchuk Accelerometer reading\n\
00307 #------------------------------\n\
00308 geometry_msgs/Vector3 nunchuk_acceleration_zeroed\n\
00309 geometry_msgs/Vector3 nunchuk_acceleration_raw\n\
00310 \n\
00311 #-----------------\n\
00312 # Nunchuk Joystick\n\
00313 #-----------------\n\
00314 float32[2] nunchuk_joystick_zeroed\n\
00315 float32[2] nunchuk_joystick_raw\n\
00316 \n\
00317 #----------------------\n\
00318 # Wiimote buttons\n\
00319 #-----------------------------\n\
00320 # Mappings from Wiimote button name\n\
00321 # to array position are defined above.\n\
00322 #\n\
00323 bool[11] buttons\n\
00324 bool[2] nunchuk_buttons\n\
00325 \n\
00326 #----------------------\n\
00327 # Wiimote LED states:\n\
00328 #-----------------------------\n\
00329 \n\
00330 bool[4] LEDs\n\
00331 \n\
00332 #----------------------\n\
00333 # Wiimote Rumble\n\
00334 #-----------------------------\n\
00335 # State (True or False)\n\
00336 \n\
00337 bool rumble\n\
00338 \n\
00339 #----------------------\n\
00340 # IR Light sensor (Camera)\n\
00341 #-----------------------------\n\
00342 # The Wiimote handles up to four light sources, \n\
00343 # and the wiimote_node.py software is written to \n\
00344 # that limit as well. For future expansion\n\
00345 # we make the following array extensible, rather\n\
00346 # than locking its length down to four:\n\
00347 \n\
00348 wiimote/IrSourceInfo[] ir_tracking\n\
00349 \n\
00350 #----------------------\n\
00351 # Wiimote battery\n\
00352 #-----------------------------\n\
00353 # A battery reading consists of two numbers: \n\
00354 # the battery percentage, and the raw reading.\n\
00355 # Maximum battery is 208 units (unknown how this\n\
00356 # relates to electrical properties): \n\
00357 \n\
00358 float32 raw_battery\n\
00359 float32 percent_battery\n\
00360 \n\
00361 #----------------------\n\
00362 # Time of most recent zeroing:\n\
00363 #-----------------------------\n\
00364 \n\
00365 time zeroing_time\n\
00366 \n\
00367 #----------------------\n\
00368 # Error vector\n\
00369 #-----------------------------\n\
00370 # For error condition definitions see wiimoteConstants.py\n\
00371 # Value of zero means all is well. (Currently NOT used).\n\
00372 \n\
00373 uint64 errors\n\
00374 \n\
00375 ================================================================================\n\
00376 MSG: std_msgs/Header\n\
00377 # Standard metadata for higher-level stamped data types.\n\
00378 # This is generally used to communicate timestamped data \n\
00379 # in a particular coordinate frame.\n\
00380 # \n\
00381 # sequence ID: consecutively increasing ID \n\
00382 uint32 seq\n\
00383 #Two-integer timestamp that is expressed as:\n\
00384 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00385 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00386 # time-handling sugar is provided by the client library\n\
00387 time stamp\n\
00388 #Frame this data is associated with\n\
00389 # 0: no frame\n\
00390 # 1: global frame\n\
00391 string frame_id\n\
00392 \n\
00393 ================================================================================\n\
00394 MSG: geometry_msgs/Vector3\n\
00395 # This represents a vector in free space. \n\
00396 \n\
00397 float64 x\n\
00398 float64 y\n\
00399 float64 z\n\
00400 ================================================================================\n\
00401 MSG: wiimote/IrSourceInfo\n\
00402 # Sensor data pertaining to the Wiimote infrared camera.\n\
00403 # This message contains data for one of the four infrared \n\
00404 # light sources that the camera detects.\n\
00405 #\n\
00406 # Each light is specified with a 2D position and \n\
00407 # a 'source magnitude' (ir_size). If the x dimension\n\
00408 # is set to INVALID_FLOAT, then no light was detected for \n\
00409 # the respective light. The Wiimote handles up to\n\
00410 # four light sources, and the wiimote_node.py software\n\
00411 # is written to that limit as well.\n\
00412 #\n\
00413 # I am unsure what the 'ir_size' values represent. \n\
00414 # They are described as 'source magnitude' in some places. I\n\
00415 # *assume* this is signal amplitude, but it's unclear. \n\
00416 # Note that current lowest level cwiid driver does not \n\
00417 # seem to pass the ir_size value to the cwiid Wiimote.c. \n\
00418 # For now this size will therefore be set INVALID\n\
00419 \n\
00420 float64 x \n\
00421 float64 y \n\
00422 int64 ir_size\n\
00423 \n\
00424 ";
00425 }
00426
00427 static const char* value(const ::wiimote::State_<ContainerAllocator> &) { return value(); }
00428 };
00429
00430 template<class ContainerAllocator> struct HasHeader< ::wiimote::State_<ContainerAllocator> > : public TrueType {};
00431 template<class ContainerAllocator> struct HasHeader< const ::wiimote::State_<ContainerAllocator> > : public TrueType {};
00432 }
00433 }
00434
00435 namespace ros
00436 {
00437 namespace serialization
00438 {
00439
00440 template<class ContainerAllocator> struct Serializer< ::wiimote::State_<ContainerAllocator> >
00441 {
00442 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00443 {
00444 stream.next(m.header);
00445 stream.next(m.angular_velocity_zeroed);
00446 stream.next(m.angular_velocity_raw);
00447 stream.next(m.angular_velocity_covariance);
00448 stream.next(m.linear_acceleration_zeroed);
00449 stream.next(m.linear_acceleration_raw);
00450 stream.next(m.linear_acceleration_covariance);
00451 stream.next(m.nunchuk_acceleration_zeroed);
00452 stream.next(m.nunchuk_acceleration_raw);
00453 stream.next(m.nunchuk_joystick_zeroed);
00454 stream.next(m.nunchuk_joystick_raw);
00455 stream.next(m.buttons);
00456 stream.next(m.nunchuk_buttons);
00457 stream.next(m.LEDs);
00458 stream.next(m.rumble);
00459 stream.next(m.ir_tracking);
00460 stream.next(m.raw_battery);
00461 stream.next(m.percent_battery);
00462 stream.next(m.zeroing_time);
00463 stream.next(m.errors);
00464 }
00465
00466 ROS_DECLARE_ALLINONE_SERIALIZER;
00467 };
00468 }
00469 }
00470
00471 namespace ros
00472 {
00473 namespace message_operations
00474 {
00475
00476 template<class ContainerAllocator>
00477 struct Printer< ::wiimote::State_<ContainerAllocator> >
00478 {
00479 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::wiimote::State_<ContainerAllocator> & v)
00480 {
00481 s << indent << "header: ";
00482 s << std::endl;
00483 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00484 s << indent << "angular_velocity_zeroed: ";
00485 s << std::endl;
00486 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.angular_velocity_zeroed);
00487 s << indent << "angular_velocity_raw: ";
00488 s << std::endl;
00489 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.angular_velocity_raw);
00490 s << indent << "angular_velocity_covariance[]" << std::endl;
00491 for (size_t i = 0; i < v.angular_velocity_covariance.size(); ++i)
00492 {
00493 s << indent << " angular_velocity_covariance[" << i << "]: ";
00494 Printer<double>::stream(s, indent + " ", v.angular_velocity_covariance[i]);
00495 }
00496 s << indent << "linear_acceleration_zeroed: ";
00497 s << std::endl;
00498 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.linear_acceleration_zeroed);
00499 s << indent << "linear_acceleration_raw: ";
00500 s << std::endl;
00501 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.linear_acceleration_raw);
00502 s << indent << "linear_acceleration_covariance[]" << std::endl;
00503 for (size_t i = 0; i < v.linear_acceleration_covariance.size(); ++i)
00504 {
00505 s << indent << " linear_acceleration_covariance[" << i << "]: ";
00506 Printer<double>::stream(s, indent + " ", v.linear_acceleration_covariance[i]);
00507 }
00508 s << indent << "nunchuk_acceleration_zeroed: ";
00509 s << std::endl;
00510 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.nunchuk_acceleration_zeroed);
00511 s << indent << "nunchuk_acceleration_raw: ";
00512 s << std::endl;
00513 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.nunchuk_acceleration_raw);
00514 s << indent << "nunchuk_joystick_zeroed[]" << std::endl;
00515 for (size_t i = 0; i < v.nunchuk_joystick_zeroed.size(); ++i)
00516 {
00517 s << indent << " nunchuk_joystick_zeroed[" << i << "]: ";
00518 Printer<float>::stream(s, indent + " ", v.nunchuk_joystick_zeroed[i]);
00519 }
00520 s << indent << "nunchuk_joystick_raw[]" << std::endl;
00521 for (size_t i = 0; i < v.nunchuk_joystick_raw.size(); ++i)
00522 {
00523 s << indent << " nunchuk_joystick_raw[" << i << "]: ";
00524 Printer<float>::stream(s, indent + " ", v.nunchuk_joystick_raw[i]);
00525 }
00526 s << indent << "buttons[]" << std::endl;
00527 for (size_t i = 0; i < v.buttons.size(); ++i)
00528 {
00529 s << indent << " buttons[" << i << "]: ";
00530 Printer<uint8_t>::stream(s, indent + " ", v.buttons[i]);
00531 }
00532 s << indent << "nunchuk_buttons[]" << std::endl;
00533 for (size_t i = 0; i < v.nunchuk_buttons.size(); ++i)
00534 {
00535 s << indent << " nunchuk_buttons[" << i << "]: ";
00536 Printer<uint8_t>::stream(s, indent + " ", v.nunchuk_buttons[i]);
00537 }
00538 s << indent << "LEDs[]" << std::endl;
00539 for (size_t i = 0; i < v.LEDs.size(); ++i)
00540 {
00541 s << indent << " LEDs[" << i << "]: ";
00542 Printer<uint8_t>::stream(s, indent + " ", v.LEDs[i]);
00543 }
00544 s << indent << "rumble: ";
00545 Printer<uint8_t>::stream(s, indent + " ", v.rumble);
00546 s << indent << "ir_tracking[]" << std::endl;
00547 for (size_t i = 0; i < v.ir_tracking.size(); ++i)
00548 {
00549 s << indent << " ir_tracking[" << i << "]: ";
00550 s << std::endl;
00551 s << indent;
00552 Printer< ::wiimote::IrSourceInfo_<ContainerAllocator> >::stream(s, indent + " ", v.ir_tracking[i]);
00553 }
00554 s << indent << "raw_battery: ";
00555 Printer<float>::stream(s, indent + " ", v.raw_battery);
00556 s << indent << "percent_battery: ";
00557 Printer<float>::stream(s, indent + " ", v.percent_battery);
00558 s << indent << "zeroing_time: ";
00559 Printer<ros::Time>::stream(s, indent + " ", v.zeroing_time);
00560 s << indent << "errors: ";
00561 Printer<uint64_t>::stream(s, indent + " ", v.errors);
00562 }
00563 };
00564
00565
00566 }
00567 }
00568
00569 #endif // WIIMOTE_MESSAGE_STATE_H
00570