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