$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-joystick_drivers/doc_stacks/2013-03-01_15-52-25.763642/joystick_drivers/wiimote/msg/State.msg */ 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 ROS_DEPRECATED uint32_t get_angular_velocity_covariance_size() const { return (uint32_t)angular_velocity_covariance.size(); } 00186 ROS_DEPRECATED uint32_t get_linear_acceleration_covariance_size() const { return (uint32_t)linear_acceleration_covariance.size(); } 00187 ROS_DEPRECATED uint32_t get_nunchuk_joystick_zeroed_size() const { return (uint32_t)nunchuk_joystick_zeroed.size(); } 00188 ROS_DEPRECATED uint32_t get_nunchuk_joystick_raw_size() const { return (uint32_t)nunchuk_joystick_raw.size(); } 00189 ROS_DEPRECATED uint32_t get_buttons_size() const { return (uint32_t)buttons.size(); } 00190 ROS_DEPRECATED uint32_t get_nunchuk_buttons_size() const { return (uint32_t)nunchuk_buttons.size(); } 00191 ROS_DEPRECATED uint32_t get_LEDs_size() const { return (uint32_t)LEDs.size(); } 00192 ROS_DEPRECATED uint32_t get_ir_tracking_size() const { return (uint32_t)ir_tracking.size(); } 00193 ROS_DEPRECATED void set_ir_tracking_size(uint32_t size) { ir_tracking.resize((size_t)size); } 00194 ROS_DEPRECATED void get_ir_tracking_vec(std::vector< ::wiimote::IrSourceInfo_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::wiimote::IrSourceInfo_<ContainerAllocator> >::other > & vec) const { vec = this->ir_tracking; } 00195 ROS_DEPRECATED void set_ir_tracking_vec(const std::vector< ::wiimote::IrSourceInfo_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::wiimote::IrSourceInfo_<ContainerAllocator> >::other > & vec) { this->ir_tracking = vec; } 00196 private: 00197 static const char* __s_getDataType_() { return "wiimote/State"; } 00198 public: 00199 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00200 00201 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00202 00203 private: 00204 static const char* __s_getMD5Sum_() { return "a69651e8129655c6ed3c5039e468362c"; } 00205 public: 00206 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00207 00208 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00209 00210 private: 00211 static const char* __s_getMessageDefinition_() { return "#\n\ 00212 # Wiimote State message containing one complete Wiimote state\n\ 00213 \n\ 00214 # Note: For ease of manipulation this message often uses\n\ 00215 # int8[] when a bit vector would work. One might\n\ 00216 # wish to use uint8[], but then Python takes\n\ 00217 # the respective structure as a string and disallows\n\ 00218 # item assignment.\n\ 00219 \n\ 00220 int8 INVALID = -1\n\ 00221 float32 INVALID_FLOAT = -1.0\n\ 00222 \n\ 00223 int8 MSG_BTN_1 = 0\n\ 00224 int8 MSG_BTN_2 = 1\n\ 00225 int8 MSG_BTN_A = 2\n\ 00226 int8 MSG_BTN_B = 3\n\ 00227 int8 MSG_BTN_PLUS = 4\n\ 00228 int8 MSG_BTN_MINUS = 5\n\ 00229 int8 MSG_BTN_LEFT = 6\n\ 00230 int8 MSG_BTN_RIGHT = 7\n\ 00231 int8 MSG_BTN_UP = 8\n\ 00232 int8 MSG_BTN_DOWN = 9\n\ 00233 int8 MSG_BTN_HOME = 10\n\ 00234 int8 MSG_BTN_Z = 0\n\ 00235 int8 MSG_BTN_C = 1\n\ 00236 int8 MSG_CLASSIC_BTN_X = 0\n\ 00237 int8 MSG_CLASSIC_BTN_Y = 1\n\ 00238 int8 MSG_CLASSIC_BTN_A = 2\n\ 00239 int8 MSG_CLASSIC_BTN_B = 3\n\ 00240 int8 MSG_CLASSIC_BTN_PLUS = 4\n\ 00241 int8 MSG_CLASSIC_BTN_MINUS = 5\n\ 00242 int8 MSG_CLASSIC_BTN_LEFT = 6\n\ 00243 int8 MSG_CLASSIC_BTN_RIGHT = 7\n\ 00244 int8 MSG_CLASSIC_BTN_UP = 8\n\ 00245 int8 MSG_CLASSIC_BTN_DOWN = 9\n\ 00246 int8 MSG_CLASSIC_BTN_HOME = 10\n\ 00247 int8 MSG_CLASSIC_BTN_L = 11\n\ 00248 int8 MSG_CLASSIC_BTN_R = 12\n\ 00249 int8 MSG_CLASSIC_BTN_ZL = 13\n\ 00250 int8 MSG_CLASSIC_BTN_ZR = 14\n\ 00251 \n\ 00252 #-----------------------------\n\ 00253 # Header\n\ 00254 #----------------------\n\ 00255 \n\ 00256 Header header\n\ 00257 \n\ 00258 #----------------------\n\ 00259 # Gyro reading\n\ 00260 #-----------------------------\n\ 00261 # In radians/sec. If reading is invalid,\n\ 00262 # for instance b/c no gyro is attached to the Wii, then\n\ 00263 # set first element of covariance to -1 (same as imu_data.msg):\n\ 00264 # Covariance matrix (roll, pitch, yaw) in radians^2/sec^2.\n\ 00265 \n\ 00266 geometry_msgs/Vector3 angular_velocity_zeroed\n\ 00267 geometry_msgs/Vector3 angular_velocity_raw\n\ 00268 float64[9] angular_velocity_covariance\n\ 00269 \n\ 00270 #----------------------\n\ 00271 # Accelerometer reading\n\ 00272 #-----------------------------\n\ 00273 # Acceleration in m/sec^2. Covariance matrix\n\ 00274 # (x,y,z) in m^2/sec^4. (all same as imu_data.msg)\n\ 00275 \n\ 00276 geometry_msgs/Vector3 linear_acceleration_zeroed\n\ 00277 geometry_msgs/Vector3 linear_acceleration_raw\n\ 00278 float64[9] linear_acceleration_covariance\n\ 00279 \n\ 00280 #------------------------------\n\ 00281 # Nunchuk Accelerometer reading\n\ 00282 #------------------------------\n\ 00283 geometry_msgs/Vector3 nunchuk_acceleration_zeroed\n\ 00284 geometry_msgs/Vector3 nunchuk_acceleration_raw\n\ 00285 \n\ 00286 #-----------------\n\ 00287 # Nunchuk Joystick\n\ 00288 #-----------------\n\ 00289 float32[2] nunchuk_joystick_zeroed\n\ 00290 float32[2] nunchuk_joystick_raw\n\ 00291 \n\ 00292 #----------------------\n\ 00293 # Wiimote buttons\n\ 00294 #-----------------------------\n\ 00295 # Mappings from Wiimote button name\n\ 00296 # to array position are defined above.\n\ 00297 #\n\ 00298 bool[11] buttons\n\ 00299 bool[2] nunchuk_buttons\n\ 00300 \n\ 00301 #----------------------\n\ 00302 # Wiimote LED states:\n\ 00303 #-----------------------------\n\ 00304 \n\ 00305 bool[4] LEDs\n\ 00306 \n\ 00307 #----------------------\n\ 00308 # Wiimote Rumble\n\ 00309 #-----------------------------\n\ 00310 # State (True or False)\n\ 00311 \n\ 00312 bool rumble\n\ 00313 \n\ 00314 #----------------------\n\ 00315 # IR Light sensor (Camera)\n\ 00316 #-----------------------------\n\ 00317 # The Wiimote handles up to four light sources, \n\ 00318 # and the wiimote_node.py software is written to \n\ 00319 # that limit as well. For future expansion\n\ 00320 # we make the following array extensible, rather\n\ 00321 # than locking its length down to four:\n\ 00322 \n\ 00323 wiimote/IrSourceInfo[] ir_tracking\n\ 00324 \n\ 00325 #----------------------\n\ 00326 # Wiimote battery\n\ 00327 #-----------------------------\n\ 00328 # A battery reading consists of two numbers: \n\ 00329 # the battery percentage, and the raw reading.\n\ 00330 # Maximum battery is 208 units (unknown how this\n\ 00331 # relates to electrical properties): \n\ 00332 \n\ 00333 float32 raw_battery\n\ 00334 float32 percent_battery\n\ 00335 \n\ 00336 #----------------------\n\ 00337 # Time of most recent zeroing:\n\ 00338 #-----------------------------\n\ 00339 \n\ 00340 time zeroing_time\n\ 00341 \n\ 00342 #----------------------\n\ 00343 # Error vector\n\ 00344 #-----------------------------\n\ 00345 # For error condition definitions see wiimoteConstants.py\n\ 00346 # Value of zero means all is well. (Currently NOT used).\n\ 00347 \n\ 00348 uint64 errors\n\ 00349 \n\ 00350 ================================================================================\n\ 00351 MSG: std_msgs/Header\n\ 00352 # Standard metadata for higher-level stamped data types.\n\ 00353 # This is generally used to communicate timestamped data \n\ 00354 # in a particular coordinate frame.\n\ 00355 # \n\ 00356 # sequence ID: consecutively increasing ID \n\ 00357 uint32 seq\n\ 00358 #Two-integer timestamp that is expressed as:\n\ 00359 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00360 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00361 # time-handling sugar is provided by the client library\n\ 00362 time stamp\n\ 00363 #Frame this data is associated with\n\ 00364 # 0: no frame\n\ 00365 # 1: global frame\n\ 00366 string frame_id\n\ 00367 \n\ 00368 ================================================================================\n\ 00369 MSG: geometry_msgs/Vector3\n\ 00370 # This represents a vector in free space. \n\ 00371 \n\ 00372 float64 x\n\ 00373 float64 y\n\ 00374 float64 z\n\ 00375 ================================================================================\n\ 00376 MSG: wiimote/IrSourceInfo\n\ 00377 # Sensor data pertaining to the Wiimote infrared camera.\n\ 00378 # This message contains data for one of the four infrared \n\ 00379 # light sources that the camera detects.\n\ 00380 #\n\ 00381 # Each light is specified with a 2D position and \n\ 00382 # a 'source magnitude' (ir_size). If the x dimension\n\ 00383 # is set to INVALID_FLOAT, then no light was detected for \n\ 00384 # the respective light. The Wiimote handles up to\n\ 00385 # four light sources, and the wiimote_node.py software\n\ 00386 # is written to that limit as well.\n\ 00387 #\n\ 00388 # I am unsure what the 'ir_size' values represent. \n\ 00389 # They are described as 'source magnitude' in some places. I\n\ 00390 # *assume* this is signal amplitude, but it's unclear. \n\ 00391 # Note that current lowest level cwiid driver does not \n\ 00392 # seem to pass the ir_size value to the cwiid Wiimote.c. \n\ 00393 # For now this size will therefore be set INVALID\n\ 00394 \n\ 00395 float64 x \n\ 00396 float64 y \n\ 00397 int64 ir_size\n\ 00398 \n\ 00399 "; } 00400 public: 00401 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00402 00403 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00404 00405 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00406 { 00407 ros::serialization::OStream stream(write_ptr, 1000000000); 00408 ros::serialization::serialize(stream, header); 00409 ros::serialization::serialize(stream, angular_velocity_zeroed); 00410 ros::serialization::serialize(stream, angular_velocity_raw); 00411 ros::serialization::serialize(stream, angular_velocity_covariance); 00412 ros::serialization::serialize(stream, linear_acceleration_zeroed); 00413 ros::serialization::serialize(stream, linear_acceleration_raw); 00414 ros::serialization::serialize(stream, linear_acceleration_covariance); 00415 ros::serialization::serialize(stream, nunchuk_acceleration_zeroed); 00416 ros::serialization::serialize(stream, nunchuk_acceleration_raw); 00417 ros::serialization::serialize(stream, nunchuk_joystick_zeroed); 00418 ros::serialization::serialize(stream, nunchuk_joystick_raw); 00419 ros::serialization::serialize(stream, buttons); 00420 ros::serialization::serialize(stream, nunchuk_buttons); 00421 ros::serialization::serialize(stream, LEDs); 00422 ros::serialization::serialize(stream, rumble); 00423 ros::serialization::serialize(stream, ir_tracking); 00424 ros::serialization::serialize(stream, raw_battery); 00425 ros::serialization::serialize(stream, percent_battery); 00426 ros::serialization::serialize(stream, zeroing_time); 00427 ros::serialization::serialize(stream, errors); 00428 return stream.getData(); 00429 } 00430 00431 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00432 { 00433 ros::serialization::IStream stream(read_ptr, 1000000000); 00434 ros::serialization::deserialize(stream, header); 00435 ros::serialization::deserialize(stream, angular_velocity_zeroed); 00436 ros::serialization::deserialize(stream, angular_velocity_raw); 00437 ros::serialization::deserialize(stream, angular_velocity_covariance); 00438 ros::serialization::deserialize(stream, linear_acceleration_zeroed); 00439 ros::serialization::deserialize(stream, linear_acceleration_raw); 00440 ros::serialization::deserialize(stream, linear_acceleration_covariance); 00441 ros::serialization::deserialize(stream, nunchuk_acceleration_zeroed); 00442 ros::serialization::deserialize(stream, nunchuk_acceleration_raw); 00443 ros::serialization::deserialize(stream, nunchuk_joystick_zeroed); 00444 ros::serialization::deserialize(stream, nunchuk_joystick_raw); 00445 ros::serialization::deserialize(stream, buttons); 00446 ros::serialization::deserialize(stream, nunchuk_buttons); 00447 ros::serialization::deserialize(stream, LEDs); 00448 ros::serialization::deserialize(stream, rumble); 00449 ros::serialization::deserialize(stream, ir_tracking); 00450 ros::serialization::deserialize(stream, raw_battery); 00451 ros::serialization::deserialize(stream, percent_battery); 00452 ros::serialization::deserialize(stream, zeroing_time); 00453 ros::serialization::deserialize(stream, errors); 00454 return stream.getData(); 00455 } 00456 00457 ROS_DEPRECATED virtual uint32_t serializationLength() const 00458 { 00459 uint32_t size = 0; 00460 size += ros::serialization::serializationLength(header); 00461 size += ros::serialization::serializationLength(angular_velocity_zeroed); 00462 size += ros::serialization::serializationLength(angular_velocity_raw); 00463 size += ros::serialization::serializationLength(angular_velocity_covariance); 00464 size += ros::serialization::serializationLength(linear_acceleration_zeroed); 00465 size += ros::serialization::serializationLength(linear_acceleration_raw); 00466 size += ros::serialization::serializationLength(linear_acceleration_covariance); 00467 size += ros::serialization::serializationLength(nunchuk_acceleration_zeroed); 00468 size += ros::serialization::serializationLength(nunchuk_acceleration_raw); 00469 size += ros::serialization::serializationLength(nunchuk_joystick_zeroed); 00470 size += ros::serialization::serializationLength(nunchuk_joystick_raw); 00471 size += ros::serialization::serializationLength(buttons); 00472 size += ros::serialization::serializationLength(nunchuk_buttons); 00473 size += ros::serialization::serializationLength(LEDs); 00474 size += ros::serialization::serializationLength(rumble); 00475 size += ros::serialization::serializationLength(ir_tracking); 00476 size += ros::serialization::serializationLength(raw_battery); 00477 size += ros::serialization::serializationLength(percent_battery); 00478 size += ros::serialization::serializationLength(zeroing_time); 00479 size += ros::serialization::serializationLength(errors); 00480 return size; 00481 } 00482 00483 typedef boost::shared_ptr< ::wiimote::State_<ContainerAllocator> > Ptr; 00484 typedef boost::shared_ptr< ::wiimote::State_<ContainerAllocator> const> ConstPtr; 00485 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00486 }; // struct State 00487 typedef ::wiimote::State_<std::allocator<void> > State; 00488 00489 typedef boost::shared_ptr< ::wiimote::State> StatePtr; 00490 typedef boost::shared_ptr< ::wiimote::State const> StateConstPtr; 00491 00492 template<typename ContainerAllocator> const float State_<ContainerAllocator>::INVALID_FLOAT = -1.0; 00493 00494 template<typename ContainerAllocator> 00495 std::ostream& operator<<(std::ostream& s, const ::wiimote::State_<ContainerAllocator> & v) 00496 { 00497 ros::message_operations::Printer< ::wiimote::State_<ContainerAllocator> >::stream(s, "", v); 00498 return s;} 00499 00500 } // namespace wiimote 00501 00502 namespace ros 00503 { 00504 namespace message_traits 00505 { 00506 template<class ContainerAllocator> struct IsMessage< ::wiimote::State_<ContainerAllocator> > : public TrueType {}; 00507 template<class ContainerAllocator> struct IsMessage< ::wiimote::State_<ContainerAllocator> const> : public TrueType {}; 00508 template<class ContainerAllocator> 00509 struct MD5Sum< ::wiimote::State_<ContainerAllocator> > { 00510 static const char* value() 00511 { 00512 return "a69651e8129655c6ed3c5039e468362c"; 00513 } 00514 00515 static const char* value(const ::wiimote::State_<ContainerAllocator> &) { return value(); } 00516 static const uint64_t static_value1 = 0xa69651e8129655c6ULL; 00517 static const uint64_t static_value2 = 0xed3c5039e468362cULL; 00518 }; 00519 00520 template<class ContainerAllocator> 00521 struct DataType< ::wiimote::State_<ContainerAllocator> > { 00522 static const char* value() 00523 { 00524 return "wiimote/State"; 00525 } 00526 00527 static const char* value(const ::wiimote::State_<ContainerAllocator> &) { return value(); } 00528 }; 00529 00530 template<class ContainerAllocator> 00531 struct Definition< ::wiimote::State_<ContainerAllocator> > { 00532 static const char* value() 00533 { 00534 return "#\n\ 00535 # Wiimote State message containing one complete Wiimote state\n\ 00536 \n\ 00537 # Note: For ease of manipulation this message often uses\n\ 00538 # int8[] when a bit vector would work. One might\n\ 00539 # wish to use uint8[], but then Python takes\n\ 00540 # the respective structure as a string and disallows\n\ 00541 # item assignment.\n\ 00542 \n\ 00543 int8 INVALID = -1\n\ 00544 float32 INVALID_FLOAT = -1.0\n\ 00545 \n\ 00546 int8 MSG_BTN_1 = 0\n\ 00547 int8 MSG_BTN_2 = 1\n\ 00548 int8 MSG_BTN_A = 2\n\ 00549 int8 MSG_BTN_B = 3\n\ 00550 int8 MSG_BTN_PLUS = 4\n\ 00551 int8 MSG_BTN_MINUS = 5\n\ 00552 int8 MSG_BTN_LEFT = 6\n\ 00553 int8 MSG_BTN_RIGHT = 7\n\ 00554 int8 MSG_BTN_UP = 8\n\ 00555 int8 MSG_BTN_DOWN = 9\n\ 00556 int8 MSG_BTN_HOME = 10\n\ 00557 int8 MSG_BTN_Z = 0\n\ 00558 int8 MSG_BTN_C = 1\n\ 00559 int8 MSG_CLASSIC_BTN_X = 0\n\ 00560 int8 MSG_CLASSIC_BTN_Y = 1\n\ 00561 int8 MSG_CLASSIC_BTN_A = 2\n\ 00562 int8 MSG_CLASSIC_BTN_B = 3\n\ 00563 int8 MSG_CLASSIC_BTN_PLUS = 4\n\ 00564 int8 MSG_CLASSIC_BTN_MINUS = 5\n\ 00565 int8 MSG_CLASSIC_BTN_LEFT = 6\n\ 00566 int8 MSG_CLASSIC_BTN_RIGHT = 7\n\ 00567 int8 MSG_CLASSIC_BTN_UP = 8\n\ 00568 int8 MSG_CLASSIC_BTN_DOWN = 9\n\ 00569 int8 MSG_CLASSIC_BTN_HOME = 10\n\ 00570 int8 MSG_CLASSIC_BTN_L = 11\n\ 00571 int8 MSG_CLASSIC_BTN_R = 12\n\ 00572 int8 MSG_CLASSIC_BTN_ZL = 13\n\ 00573 int8 MSG_CLASSIC_BTN_ZR = 14\n\ 00574 \n\ 00575 #-----------------------------\n\ 00576 # Header\n\ 00577 #----------------------\n\ 00578 \n\ 00579 Header header\n\ 00580 \n\ 00581 #----------------------\n\ 00582 # Gyro reading\n\ 00583 #-----------------------------\n\ 00584 # In radians/sec. If reading is invalid,\n\ 00585 # for instance b/c no gyro is attached to the Wii, then\n\ 00586 # set first element of covariance to -1 (same as imu_data.msg):\n\ 00587 # Covariance matrix (roll, pitch, yaw) in radians^2/sec^2.\n\ 00588 \n\ 00589 geometry_msgs/Vector3 angular_velocity_zeroed\n\ 00590 geometry_msgs/Vector3 angular_velocity_raw\n\ 00591 float64[9] angular_velocity_covariance\n\ 00592 \n\ 00593 #----------------------\n\ 00594 # Accelerometer reading\n\ 00595 #-----------------------------\n\ 00596 # Acceleration in m/sec^2. Covariance matrix\n\ 00597 # (x,y,z) in m^2/sec^4. (all same as imu_data.msg)\n\ 00598 \n\ 00599 geometry_msgs/Vector3 linear_acceleration_zeroed\n\ 00600 geometry_msgs/Vector3 linear_acceleration_raw\n\ 00601 float64[9] linear_acceleration_covariance\n\ 00602 \n\ 00603 #------------------------------\n\ 00604 # Nunchuk Accelerometer reading\n\ 00605 #------------------------------\n\ 00606 geometry_msgs/Vector3 nunchuk_acceleration_zeroed\n\ 00607 geometry_msgs/Vector3 nunchuk_acceleration_raw\n\ 00608 \n\ 00609 #-----------------\n\ 00610 # Nunchuk Joystick\n\ 00611 #-----------------\n\ 00612 float32[2] nunchuk_joystick_zeroed\n\ 00613 float32[2] nunchuk_joystick_raw\n\ 00614 \n\ 00615 #----------------------\n\ 00616 # Wiimote buttons\n\ 00617 #-----------------------------\n\ 00618 # Mappings from Wiimote button name\n\ 00619 # to array position are defined above.\n\ 00620 #\n\ 00621 bool[11] buttons\n\ 00622 bool[2] nunchuk_buttons\n\ 00623 \n\ 00624 #----------------------\n\ 00625 # Wiimote LED states:\n\ 00626 #-----------------------------\n\ 00627 \n\ 00628 bool[4] LEDs\n\ 00629 \n\ 00630 #----------------------\n\ 00631 # Wiimote Rumble\n\ 00632 #-----------------------------\n\ 00633 # State (True or False)\n\ 00634 \n\ 00635 bool rumble\n\ 00636 \n\ 00637 #----------------------\n\ 00638 # IR Light sensor (Camera)\n\ 00639 #-----------------------------\n\ 00640 # The Wiimote handles up to four light sources, \n\ 00641 # and the wiimote_node.py software is written to \n\ 00642 # that limit as well. For future expansion\n\ 00643 # we make the following array extensible, rather\n\ 00644 # than locking its length down to four:\n\ 00645 \n\ 00646 wiimote/IrSourceInfo[] ir_tracking\n\ 00647 \n\ 00648 #----------------------\n\ 00649 # Wiimote battery\n\ 00650 #-----------------------------\n\ 00651 # A battery reading consists of two numbers: \n\ 00652 # the battery percentage, and the raw reading.\n\ 00653 # Maximum battery is 208 units (unknown how this\n\ 00654 # relates to electrical properties): \n\ 00655 \n\ 00656 float32 raw_battery\n\ 00657 float32 percent_battery\n\ 00658 \n\ 00659 #----------------------\n\ 00660 # Time of most recent zeroing:\n\ 00661 #-----------------------------\n\ 00662 \n\ 00663 time zeroing_time\n\ 00664 \n\ 00665 #----------------------\n\ 00666 # Error vector\n\ 00667 #-----------------------------\n\ 00668 # For error condition definitions see wiimoteConstants.py\n\ 00669 # Value of zero means all is well. (Currently NOT used).\n\ 00670 \n\ 00671 uint64 errors\n\ 00672 \n\ 00673 ================================================================================\n\ 00674 MSG: std_msgs/Header\n\ 00675 # Standard metadata for higher-level stamped data types.\n\ 00676 # This is generally used to communicate timestamped data \n\ 00677 # in a particular coordinate frame.\n\ 00678 # \n\ 00679 # sequence ID: consecutively increasing ID \n\ 00680 uint32 seq\n\ 00681 #Two-integer timestamp that is expressed as:\n\ 00682 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00683 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00684 # time-handling sugar is provided by the client library\n\ 00685 time stamp\n\ 00686 #Frame this data is associated with\n\ 00687 # 0: no frame\n\ 00688 # 1: global frame\n\ 00689 string frame_id\n\ 00690 \n\ 00691 ================================================================================\n\ 00692 MSG: geometry_msgs/Vector3\n\ 00693 # This represents a vector in free space. \n\ 00694 \n\ 00695 float64 x\n\ 00696 float64 y\n\ 00697 float64 z\n\ 00698 ================================================================================\n\ 00699 MSG: wiimote/IrSourceInfo\n\ 00700 # Sensor data pertaining to the Wiimote infrared camera.\n\ 00701 # This message contains data for one of the four infrared \n\ 00702 # light sources that the camera detects.\n\ 00703 #\n\ 00704 # Each light is specified with a 2D position and \n\ 00705 # a 'source magnitude' (ir_size). If the x dimension\n\ 00706 # is set to INVALID_FLOAT, then no light was detected for \n\ 00707 # the respective light. The Wiimote handles up to\n\ 00708 # four light sources, and the wiimote_node.py software\n\ 00709 # is written to that limit as well.\n\ 00710 #\n\ 00711 # I am unsure what the 'ir_size' values represent. \n\ 00712 # They are described as 'source magnitude' in some places. I\n\ 00713 # *assume* this is signal amplitude, but it's unclear. \n\ 00714 # Note that current lowest level cwiid driver does not \n\ 00715 # seem to pass the ir_size value to the cwiid Wiimote.c. \n\ 00716 # For now this size will therefore be set INVALID\n\ 00717 \n\ 00718 float64 x \n\ 00719 float64 y \n\ 00720 int64 ir_size\n\ 00721 \n\ 00722 "; 00723 } 00724 00725 static const char* value(const ::wiimote::State_<ContainerAllocator> &) { return value(); } 00726 }; 00727 00728 template<class ContainerAllocator> struct HasHeader< ::wiimote::State_<ContainerAllocator> > : public TrueType {}; 00729 template<class ContainerAllocator> struct HasHeader< const ::wiimote::State_<ContainerAllocator> > : public TrueType {}; 00730 } // namespace message_traits 00731 } // namespace ros 00732 00733 namespace ros 00734 { 00735 namespace serialization 00736 { 00737 00738 template<class ContainerAllocator> struct Serializer< ::wiimote::State_<ContainerAllocator> > 00739 { 00740 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00741 { 00742 stream.next(m.header); 00743 stream.next(m.angular_velocity_zeroed); 00744 stream.next(m.angular_velocity_raw); 00745 stream.next(m.angular_velocity_covariance); 00746 stream.next(m.linear_acceleration_zeroed); 00747 stream.next(m.linear_acceleration_raw); 00748 stream.next(m.linear_acceleration_covariance); 00749 stream.next(m.nunchuk_acceleration_zeroed); 00750 stream.next(m.nunchuk_acceleration_raw); 00751 stream.next(m.nunchuk_joystick_zeroed); 00752 stream.next(m.nunchuk_joystick_raw); 00753 stream.next(m.buttons); 00754 stream.next(m.nunchuk_buttons); 00755 stream.next(m.LEDs); 00756 stream.next(m.rumble); 00757 stream.next(m.ir_tracking); 00758 stream.next(m.raw_battery); 00759 stream.next(m.percent_battery); 00760 stream.next(m.zeroing_time); 00761 stream.next(m.errors); 00762 } 00763 00764 ROS_DECLARE_ALLINONE_SERIALIZER; 00765 }; // struct State_ 00766 } // namespace serialization 00767 } // namespace ros 00768 00769 namespace ros 00770 { 00771 namespace message_operations 00772 { 00773 00774 template<class ContainerAllocator> 00775 struct Printer< ::wiimote::State_<ContainerAllocator> > 00776 { 00777 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::wiimote::State_<ContainerAllocator> & v) 00778 { 00779 s << indent << "header: "; 00780 s << std::endl; 00781 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00782 s << indent << "angular_velocity_zeroed: "; 00783 s << std::endl; 00784 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.angular_velocity_zeroed); 00785 s << indent << "angular_velocity_raw: "; 00786 s << std::endl; 00787 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.angular_velocity_raw); 00788 s << indent << "angular_velocity_covariance[]" << std::endl; 00789 for (size_t i = 0; i < v.angular_velocity_covariance.size(); ++i) 00790 { 00791 s << indent << " angular_velocity_covariance[" << i << "]: "; 00792 Printer<double>::stream(s, indent + " ", v.angular_velocity_covariance[i]); 00793 } 00794 s << indent << "linear_acceleration_zeroed: "; 00795 s << std::endl; 00796 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.linear_acceleration_zeroed); 00797 s << indent << "linear_acceleration_raw: "; 00798 s << std::endl; 00799 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.linear_acceleration_raw); 00800 s << indent << "linear_acceleration_covariance[]" << std::endl; 00801 for (size_t i = 0; i < v.linear_acceleration_covariance.size(); ++i) 00802 { 00803 s << indent << " linear_acceleration_covariance[" << i << "]: "; 00804 Printer<double>::stream(s, indent + " ", v.linear_acceleration_covariance[i]); 00805 } 00806 s << indent << "nunchuk_acceleration_zeroed: "; 00807 s << std::endl; 00808 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.nunchuk_acceleration_zeroed); 00809 s << indent << "nunchuk_acceleration_raw: "; 00810 s << std::endl; 00811 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.nunchuk_acceleration_raw); 00812 s << indent << "nunchuk_joystick_zeroed[]" << std::endl; 00813 for (size_t i = 0; i < v.nunchuk_joystick_zeroed.size(); ++i) 00814 { 00815 s << indent << " nunchuk_joystick_zeroed[" << i << "]: "; 00816 Printer<float>::stream(s, indent + " ", v.nunchuk_joystick_zeroed[i]); 00817 } 00818 s << indent << "nunchuk_joystick_raw[]" << std::endl; 00819 for (size_t i = 0; i < v.nunchuk_joystick_raw.size(); ++i) 00820 { 00821 s << indent << " nunchuk_joystick_raw[" << i << "]: "; 00822 Printer<float>::stream(s, indent + " ", v.nunchuk_joystick_raw[i]); 00823 } 00824 s << indent << "buttons[]" << std::endl; 00825 for (size_t i = 0; i < v.buttons.size(); ++i) 00826 { 00827 s << indent << " buttons[" << i << "]: "; 00828 Printer<uint8_t>::stream(s, indent + " ", v.buttons[i]); 00829 } 00830 s << indent << "nunchuk_buttons[]" << std::endl; 00831 for (size_t i = 0; i < v.nunchuk_buttons.size(); ++i) 00832 { 00833 s << indent << " nunchuk_buttons[" << i << "]: "; 00834 Printer<uint8_t>::stream(s, indent + " ", v.nunchuk_buttons[i]); 00835 } 00836 s << indent << "LEDs[]" << std::endl; 00837 for (size_t i = 0; i < v.LEDs.size(); ++i) 00838 { 00839 s << indent << " LEDs[" << i << "]: "; 00840 Printer<uint8_t>::stream(s, indent + " ", v.LEDs[i]); 00841 } 00842 s << indent << "rumble: "; 00843 Printer<uint8_t>::stream(s, indent + " ", v.rumble); 00844 s << indent << "ir_tracking[]" << std::endl; 00845 for (size_t i = 0; i < v.ir_tracking.size(); ++i) 00846 { 00847 s << indent << " ir_tracking[" << i << "]: "; 00848 s << std::endl; 00849 s << indent; 00850 Printer< ::wiimote::IrSourceInfo_<ContainerAllocator> >::stream(s, indent + " ", v.ir_tracking[i]); 00851 } 00852 s << indent << "raw_battery: "; 00853 Printer<float>::stream(s, indent + " ", v.raw_battery); 00854 s << indent << "percent_battery: "; 00855 Printer<float>::stream(s, indent + " ", v.percent_battery); 00856 s << indent << "zeroing_time: "; 00857 Printer<ros::Time>::stream(s, indent + " ", v.zeroing_time); 00858 s << indent << "errors: "; 00859 Printer<uint64_t>::stream(s, indent + " ", v.errors); 00860 } 00861 }; 00862 00863 00864 } // namespace message_operations 00865 } // namespace ros 00866 00867 #endif // WIIMOTE_MESSAGE_STATE_H 00868