$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-brown_drivers/doc_stacks/2013-03-01_14-22-08.485471/brown_drivers/irobot_create_2_1/msg/SensorPacket.msg */ 00002 #ifndef IROBOT_CREATE_2_1_MESSAGE_SENSORPACKET_H 00003 #define IROBOT_CREATE_2_1_MESSAGE_SENSORPACKET_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 00019 namespace irobot_create_2_1 00020 { 00021 template <class ContainerAllocator> 00022 struct SensorPacket_ { 00023 typedef SensorPacket_<ContainerAllocator> Type; 00024 00025 SensorPacket_() 00026 : header() 00027 , wheeldropCaster(false) 00028 , wheeldropLeft(false) 00029 , wheeldropRight(false) 00030 , bumpLeft(false) 00031 , bumpRight(false) 00032 , wall(false) 00033 , cliffLeft(false) 00034 , cliffFronLeft(false) 00035 , cliffFrontRight(false) 00036 , cliffRight(false) 00037 , virtualWall(false) 00038 , infraredByte(0) 00039 , advance(false) 00040 , play(false) 00041 , distance(0) 00042 , angle(0) 00043 , chargingState(0) 00044 , voltage(0) 00045 , current(0) 00046 , batteryTemperature(0) 00047 , batteryCharge(0) 00048 , batteryCapacity(0) 00049 , wallSignal(0) 00050 , cliffLeftSignal(0) 00051 , cliffFrontLeftSignal(0) 00052 , cliffFrontRightSignal(0) 00053 , cliffRightSignal(0) 00054 , homeBase(false) 00055 , internalCharger(false) 00056 , songNumber(0) 00057 , songPlaying(0) 00058 { 00059 } 00060 00061 SensorPacket_(const ContainerAllocator& _alloc) 00062 : header(_alloc) 00063 , wheeldropCaster(false) 00064 , wheeldropLeft(false) 00065 , wheeldropRight(false) 00066 , bumpLeft(false) 00067 , bumpRight(false) 00068 , wall(false) 00069 , cliffLeft(false) 00070 , cliffFronLeft(false) 00071 , cliffFrontRight(false) 00072 , cliffRight(false) 00073 , virtualWall(false) 00074 , infraredByte(0) 00075 , advance(false) 00076 , play(false) 00077 , distance(0) 00078 , angle(0) 00079 , chargingState(0) 00080 , voltage(0) 00081 , current(0) 00082 , batteryTemperature(0) 00083 , batteryCharge(0) 00084 , batteryCapacity(0) 00085 , wallSignal(0) 00086 , cliffLeftSignal(0) 00087 , cliffFrontLeftSignal(0) 00088 , cliffFrontRightSignal(0) 00089 , cliffRightSignal(0) 00090 , homeBase(false) 00091 , internalCharger(false) 00092 , songNumber(0) 00093 , songPlaying(0) 00094 { 00095 } 00096 00097 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00098 ::std_msgs::Header_<ContainerAllocator> header; 00099 00100 typedef uint8_t _wheeldropCaster_type; 00101 uint8_t wheeldropCaster; 00102 00103 typedef uint8_t _wheeldropLeft_type; 00104 uint8_t wheeldropLeft; 00105 00106 typedef uint8_t _wheeldropRight_type; 00107 uint8_t wheeldropRight; 00108 00109 typedef uint8_t _bumpLeft_type; 00110 uint8_t bumpLeft; 00111 00112 typedef uint8_t _bumpRight_type; 00113 uint8_t bumpRight; 00114 00115 typedef uint8_t _wall_type; 00116 uint8_t wall; 00117 00118 typedef uint8_t _cliffLeft_type; 00119 uint8_t cliffLeft; 00120 00121 typedef uint8_t _cliffFronLeft_type; 00122 uint8_t cliffFronLeft; 00123 00124 typedef uint8_t _cliffFrontRight_type; 00125 uint8_t cliffFrontRight; 00126 00127 typedef uint8_t _cliffRight_type; 00128 uint8_t cliffRight; 00129 00130 typedef uint8_t _virtualWall_type; 00131 uint8_t virtualWall; 00132 00133 typedef uint8_t _infraredByte_type; 00134 uint8_t infraredByte; 00135 00136 typedef uint8_t _advance_type; 00137 uint8_t advance; 00138 00139 typedef uint8_t _play_type; 00140 uint8_t play; 00141 00142 typedef int16_t _distance_type; 00143 int16_t distance; 00144 00145 typedef int16_t _angle_type; 00146 int16_t angle; 00147 00148 typedef uint8_t _chargingState_type; 00149 uint8_t chargingState; 00150 00151 typedef uint16_t _voltage_type; 00152 uint16_t voltage; 00153 00154 typedef int16_t _current_type; 00155 int16_t current; 00156 00157 typedef int8_t _batteryTemperature_type; 00158 int8_t batteryTemperature; 00159 00160 typedef uint16_t _batteryCharge_type; 00161 uint16_t batteryCharge; 00162 00163 typedef uint16_t _batteryCapacity_type; 00164 uint16_t batteryCapacity; 00165 00166 typedef uint16_t _wallSignal_type; 00167 uint16_t wallSignal; 00168 00169 typedef uint16_t _cliffLeftSignal_type; 00170 uint16_t cliffLeftSignal; 00171 00172 typedef uint16_t _cliffFrontLeftSignal_type; 00173 uint16_t cliffFrontLeftSignal; 00174 00175 typedef uint16_t _cliffFrontRightSignal_type; 00176 uint16_t cliffFrontRightSignal; 00177 00178 typedef uint16_t _cliffRightSignal_type; 00179 uint16_t cliffRightSignal; 00180 00181 typedef uint8_t _homeBase_type; 00182 uint8_t homeBase; 00183 00184 typedef uint8_t _internalCharger_type; 00185 uint8_t internalCharger; 00186 00187 typedef uint8_t _songNumber_type; 00188 uint8_t songNumber; 00189 00190 typedef uint8_t _songPlaying_type; 00191 uint8_t songPlaying; 00192 00193 00194 private: 00195 static const char* __s_getDataType_() { return "irobot_create_2_1/SensorPacket"; } 00196 public: 00197 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00198 00199 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00200 00201 private: 00202 static const char* __s_getMD5Sum_() { return "56f92e8d70d283e7e15aa47855e73ea7"; } 00203 public: 00204 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00205 00206 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00207 00208 private: 00209 static const char* __s_getMessageDefinition_() { return "Header header\n\ 00210 bool wheeldropCaster\n\ 00211 bool wheeldropLeft\n\ 00212 bool wheeldropRight\n\ 00213 bool bumpLeft\n\ 00214 bool bumpRight\n\ 00215 bool wall\n\ 00216 bool cliffLeft\n\ 00217 bool cliffFronLeft\n\ 00218 bool cliffFrontRight\n\ 00219 bool cliffRight\n\ 00220 bool virtualWall\n\ 00221 uint8 infraredByte\n\ 00222 bool advance\n\ 00223 bool play\n\ 00224 int16 distance\n\ 00225 int16 angle\n\ 00226 uint8 chargingState\n\ 00227 uint16 voltage\n\ 00228 int16 current\n\ 00229 int8 batteryTemperature\n\ 00230 uint16 batteryCharge\n\ 00231 uint16 batteryCapacity\n\ 00232 uint16 wallSignal\n\ 00233 uint16 cliffLeftSignal\n\ 00234 uint16 cliffFrontLeftSignal\n\ 00235 uint16 cliffFrontRightSignal\n\ 00236 uint16 cliffRightSignal\n\ 00237 bool homeBase\n\ 00238 bool internalCharger\n\ 00239 uint8 songNumber\n\ 00240 uint8 songPlaying\n\ 00241 \n\ 00242 ================================================================================\n\ 00243 MSG: std_msgs/Header\n\ 00244 # Standard metadata for higher-level stamped data types.\n\ 00245 # This is generally used to communicate timestamped data \n\ 00246 # in a particular coordinate frame.\n\ 00247 # \n\ 00248 # sequence ID: consecutively increasing ID \n\ 00249 uint32 seq\n\ 00250 #Two-integer timestamp that is expressed as:\n\ 00251 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00252 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00253 # time-handling sugar is provided by the client library\n\ 00254 time stamp\n\ 00255 #Frame this data is associated with\n\ 00256 # 0: no frame\n\ 00257 # 1: global frame\n\ 00258 string frame_id\n\ 00259 \n\ 00260 "; } 00261 public: 00262 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00263 00264 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00265 00266 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00267 { 00268 ros::serialization::OStream stream(write_ptr, 1000000000); 00269 ros::serialization::serialize(stream, header); 00270 ros::serialization::serialize(stream, wheeldropCaster); 00271 ros::serialization::serialize(stream, wheeldropLeft); 00272 ros::serialization::serialize(stream, wheeldropRight); 00273 ros::serialization::serialize(stream, bumpLeft); 00274 ros::serialization::serialize(stream, bumpRight); 00275 ros::serialization::serialize(stream, wall); 00276 ros::serialization::serialize(stream, cliffLeft); 00277 ros::serialization::serialize(stream, cliffFronLeft); 00278 ros::serialization::serialize(stream, cliffFrontRight); 00279 ros::serialization::serialize(stream, cliffRight); 00280 ros::serialization::serialize(stream, virtualWall); 00281 ros::serialization::serialize(stream, infraredByte); 00282 ros::serialization::serialize(stream, advance); 00283 ros::serialization::serialize(stream, play); 00284 ros::serialization::serialize(stream, distance); 00285 ros::serialization::serialize(stream, angle); 00286 ros::serialization::serialize(stream, chargingState); 00287 ros::serialization::serialize(stream, voltage); 00288 ros::serialization::serialize(stream, current); 00289 ros::serialization::serialize(stream, batteryTemperature); 00290 ros::serialization::serialize(stream, batteryCharge); 00291 ros::serialization::serialize(stream, batteryCapacity); 00292 ros::serialization::serialize(stream, wallSignal); 00293 ros::serialization::serialize(stream, cliffLeftSignal); 00294 ros::serialization::serialize(stream, cliffFrontLeftSignal); 00295 ros::serialization::serialize(stream, cliffFrontRightSignal); 00296 ros::serialization::serialize(stream, cliffRightSignal); 00297 ros::serialization::serialize(stream, homeBase); 00298 ros::serialization::serialize(stream, internalCharger); 00299 ros::serialization::serialize(stream, songNumber); 00300 ros::serialization::serialize(stream, songPlaying); 00301 return stream.getData(); 00302 } 00303 00304 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00305 { 00306 ros::serialization::IStream stream(read_ptr, 1000000000); 00307 ros::serialization::deserialize(stream, header); 00308 ros::serialization::deserialize(stream, wheeldropCaster); 00309 ros::serialization::deserialize(stream, wheeldropLeft); 00310 ros::serialization::deserialize(stream, wheeldropRight); 00311 ros::serialization::deserialize(stream, bumpLeft); 00312 ros::serialization::deserialize(stream, bumpRight); 00313 ros::serialization::deserialize(stream, wall); 00314 ros::serialization::deserialize(stream, cliffLeft); 00315 ros::serialization::deserialize(stream, cliffFronLeft); 00316 ros::serialization::deserialize(stream, cliffFrontRight); 00317 ros::serialization::deserialize(stream, cliffRight); 00318 ros::serialization::deserialize(stream, virtualWall); 00319 ros::serialization::deserialize(stream, infraredByte); 00320 ros::serialization::deserialize(stream, advance); 00321 ros::serialization::deserialize(stream, play); 00322 ros::serialization::deserialize(stream, distance); 00323 ros::serialization::deserialize(stream, angle); 00324 ros::serialization::deserialize(stream, chargingState); 00325 ros::serialization::deserialize(stream, voltage); 00326 ros::serialization::deserialize(stream, current); 00327 ros::serialization::deserialize(stream, batteryTemperature); 00328 ros::serialization::deserialize(stream, batteryCharge); 00329 ros::serialization::deserialize(stream, batteryCapacity); 00330 ros::serialization::deserialize(stream, wallSignal); 00331 ros::serialization::deserialize(stream, cliffLeftSignal); 00332 ros::serialization::deserialize(stream, cliffFrontLeftSignal); 00333 ros::serialization::deserialize(stream, cliffFrontRightSignal); 00334 ros::serialization::deserialize(stream, cliffRightSignal); 00335 ros::serialization::deserialize(stream, homeBase); 00336 ros::serialization::deserialize(stream, internalCharger); 00337 ros::serialization::deserialize(stream, songNumber); 00338 ros::serialization::deserialize(stream, songPlaying); 00339 return stream.getData(); 00340 } 00341 00342 ROS_DEPRECATED virtual uint32_t serializationLength() const 00343 { 00344 uint32_t size = 0; 00345 size += ros::serialization::serializationLength(header); 00346 size += ros::serialization::serializationLength(wheeldropCaster); 00347 size += ros::serialization::serializationLength(wheeldropLeft); 00348 size += ros::serialization::serializationLength(wheeldropRight); 00349 size += ros::serialization::serializationLength(bumpLeft); 00350 size += ros::serialization::serializationLength(bumpRight); 00351 size += ros::serialization::serializationLength(wall); 00352 size += ros::serialization::serializationLength(cliffLeft); 00353 size += ros::serialization::serializationLength(cliffFronLeft); 00354 size += ros::serialization::serializationLength(cliffFrontRight); 00355 size += ros::serialization::serializationLength(cliffRight); 00356 size += ros::serialization::serializationLength(virtualWall); 00357 size += ros::serialization::serializationLength(infraredByte); 00358 size += ros::serialization::serializationLength(advance); 00359 size += ros::serialization::serializationLength(play); 00360 size += ros::serialization::serializationLength(distance); 00361 size += ros::serialization::serializationLength(angle); 00362 size += ros::serialization::serializationLength(chargingState); 00363 size += ros::serialization::serializationLength(voltage); 00364 size += ros::serialization::serializationLength(current); 00365 size += ros::serialization::serializationLength(batteryTemperature); 00366 size += ros::serialization::serializationLength(batteryCharge); 00367 size += ros::serialization::serializationLength(batteryCapacity); 00368 size += ros::serialization::serializationLength(wallSignal); 00369 size += ros::serialization::serializationLength(cliffLeftSignal); 00370 size += ros::serialization::serializationLength(cliffFrontLeftSignal); 00371 size += ros::serialization::serializationLength(cliffFrontRightSignal); 00372 size += ros::serialization::serializationLength(cliffRightSignal); 00373 size += ros::serialization::serializationLength(homeBase); 00374 size += ros::serialization::serializationLength(internalCharger); 00375 size += ros::serialization::serializationLength(songNumber); 00376 size += ros::serialization::serializationLength(songPlaying); 00377 return size; 00378 } 00379 00380 typedef boost::shared_ptr< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > Ptr; 00381 typedef boost::shared_ptr< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> const> ConstPtr; 00382 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00383 }; // struct SensorPacket 00384 typedef ::irobot_create_2_1::SensorPacket_<std::allocator<void> > SensorPacket; 00385 00386 typedef boost::shared_ptr< ::irobot_create_2_1::SensorPacket> SensorPacketPtr; 00387 typedef boost::shared_ptr< ::irobot_create_2_1::SensorPacket const> SensorPacketConstPtr; 00388 00389 00390 template<typename ContainerAllocator> 00391 std::ostream& operator<<(std::ostream& s, const ::irobot_create_2_1::SensorPacket_<ContainerAllocator> & v) 00392 { 00393 ros::message_operations::Printer< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> >::stream(s, "", v); 00394 return s;} 00395 00396 } // namespace irobot_create_2_1 00397 00398 namespace ros 00399 { 00400 namespace message_traits 00401 { 00402 template<class ContainerAllocator> struct IsMessage< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > : public TrueType {}; 00403 template<class ContainerAllocator> struct IsMessage< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> const> : public TrueType {}; 00404 template<class ContainerAllocator> 00405 struct MD5Sum< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > { 00406 static const char* value() 00407 { 00408 return "56f92e8d70d283e7e15aa47855e73ea7"; 00409 } 00410 00411 static const char* value(const ::irobot_create_2_1::SensorPacket_<ContainerAllocator> &) { return value(); } 00412 static const uint64_t static_value1 = 0x56f92e8d70d283e7ULL; 00413 static const uint64_t static_value2 = 0xe15aa47855e73ea7ULL; 00414 }; 00415 00416 template<class ContainerAllocator> 00417 struct DataType< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > { 00418 static const char* value() 00419 { 00420 return "irobot_create_2_1/SensorPacket"; 00421 } 00422 00423 static const char* value(const ::irobot_create_2_1::SensorPacket_<ContainerAllocator> &) { return value(); } 00424 }; 00425 00426 template<class ContainerAllocator> 00427 struct Definition< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > { 00428 static const char* value() 00429 { 00430 return "Header header\n\ 00431 bool wheeldropCaster\n\ 00432 bool wheeldropLeft\n\ 00433 bool wheeldropRight\n\ 00434 bool bumpLeft\n\ 00435 bool bumpRight\n\ 00436 bool wall\n\ 00437 bool cliffLeft\n\ 00438 bool cliffFronLeft\n\ 00439 bool cliffFrontRight\n\ 00440 bool cliffRight\n\ 00441 bool virtualWall\n\ 00442 uint8 infraredByte\n\ 00443 bool advance\n\ 00444 bool play\n\ 00445 int16 distance\n\ 00446 int16 angle\n\ 00447 uint8 chargingState\n\ 00448 uint16 voltage\n\ 00449 int16 current\n\ 00450 int8 batteryTemperature\n\ 00451 uint16 batteryCharge\n\ 00452 uint16 batteryCapacity\n\ 00453 uint16 wallSignal\n\ 00454 uint16 cliffLeftSignal\n\ 00455 uint16 cliffFrontLeftSignal\n\ 00456 uint16 cliffFrontRightSignal\n\ 00457 uint16 cliffRightSignal\n\ 00458 bool homeBase\n\ 00459 bool internalCharger\n\ 00460 uint8 songNumber\n\ 00461 uint8 songPlaying\n\ 00462 \n\ 00463 ================================================================================\n\ 00464 MSG: std_msgs/Header\n\ 00465 # Standard metadata for higher-level stamped data types.\n\ 00466 # This is generally used to communicate timestamped data \n\ 00467 # in a particular coordinate frame.\n\ 00468 # \n\ 00469 # sequence ID: consecutively increasing ID \n\ 00470 uint32 seq\n\ 00471 #Two-integer timestamp that is expressed as:\n\ 00472 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00473 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00474 # time-handling sugar is provided by the client library\n\ 00475 time stamp\n\ 00476 #Frame this data is associated with\n\ 00477 # 0: no frame\n\ 00478 # 1: global frame\n\ 00479 string frame_id\n\ 00480 \n\ 00481 "; 00482 } 00483 00484 static const char* value(const ::irobot_create_2_1::SensorPacket_<ContainerAllocator> &) { return value(); } 00485 }; 00486 00487 template<class ContainerAllocator> struct HasHeader< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > : public TrueType {}; 00488 template<class ContainerAllocator> struct HasHeader< const ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > : public TrueType {}; 00489 } // namespace message_traits 00490 } // namespace ros 00491 00492 namespace ros 00493 { 00494 namespace serialization 00495 { 00496 00497 template<class ContainerAllocator> struct Serializer< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > 00498 { 00499 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00500 { 00501 stream.next(m.header); 00502 stream.next(m.wheeldropCaster); 00503 stream.next(m.wheeldropLeft); 00504 stream.next(m.wheeldropRight); 00505 stream.next(m.bumpLeft); 00506 stream.next(m.bumpRight); 00507 stream.next(m.wall); 00508 stream.next(m.cliffLeft); 00509 stream.next(m.cliffFronLeft); 00510 stream.next(m.cliffFrontRight); 00511 stream.next(m.cliffRight); 00512 stream.next(m.virtualWall); 00513 stream.next(m.infraredByte); 00514 stream.next(m.advance); 00515 stream.next(m.play); 00516 stream.next(m.distance); 00517 stream.next(m.angle); 00518 stream.next(m.chargingState); 00519 stream.next(m.voltage); 00520 stream.next(m.current); 00521 stream.next(m.batteryTemperature); 00522 stream.next(m.batteryCharge); 00523 stream.next(m.batteryCapacity); 00524 stream.next(m.wallSignal); 00525 stream.next(m.cliffLeftSignal); 00526 stream.next(m.cliffFrontLeftSignal); 00527 stream.next(m.cliffFrontRightSignal); 00528 stream.next(m.cliffRightSignal); 00529 stream.next(m.homeBase); 00530 stream.next(m.internalCharger); 00531 stream.next(m.songNumber); 00532 stream.next(m.songPlaying); 00533 } 00534 00535 ROS_DECLARE_ALLINONE_SERIALIZER; 00536 }; // struct SensorPacket_ 00537 } // namespace serialization 00538 } // namespace ros 00539 00540 namespace ros 00541 { 00542 namespace message_operations 00543 { 00544 00545 template<class ContainerAllocator> 00546 struct Printer< ::irobot_create_2_1::SensorPacket_<ContainerAllocator> > 00547 { 00548 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::irobot_create_2_1::SensorPacket_<ContainerAllocator> & v) 00549 { 00550 s << indent << "header: "; 00551 s << std::endl; 00552 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00553 s << indent << "wheeldropCaster: "; 00554 Printer<uint8_t>::stream(s, indent + " ", v.wheeldropCaster); 00555 s << indent << "wheeldropLeft: "; 00556 Printer<uint8_t>::stream(s, indent + " ", v.wheeldropLeft); 00557 s << indent << "wheeldropRight: "; 00558 Printer<uint8_t>::stream(s, indent + " ", v.wheeldropRight); 00559 s << indent << "bumpLeft: "; 00560 Printer<uint8_t>::stream(s, indent + " ", v.bumpLeft); 00561 s << indent << "bumpRight: "; 00562 Printer<uint8_t>::stream(s, indent + " ", v.bumpRight); 00563 s << indent << "wall: "; 00564 Printer<uint8_t>::stream(s, indent + " ", v.wall); 00565 s << indent << "cliffLeft: "; 00566 Printer<uint8_t>::stream(s, indent + " ", v.cliffLeft); 00567 s << indent << "cliffFronLeft: "; 00568 Printer<uint8_t>::stream(s, indent + " ", v.cliffFronLeft); 00569 s << indent << "cliffFrontRight: "; 00570 Printer<uint8_t>::stream(s, indent + " ", v.cliffFrontRight); 00571 s << indent << "cliffRight: "; 00572 Printer<uint8_t>::stream(s, indent + " ", v.cliffRight); 00573 s << indent << "virtualWall: "; 00574 Printer<uint8_t>::stream(s, indent + " ", v.virtualWall); 00575 s << indent << "infraredByte: "; 00576 Printer<uint8_t>::stream(s, indent + " ", v.infraredByte); 00577 s << indent << "advance: "; 00578 Printer<uint8_t>::stream(s, indent + " ", v.advance); 00579 s << indent << "play: "; 00580 Printer<uint8_t>::stream(s, indent + " ", v.play); 00581 s << indent << "distance: "; 00582 Printer<int16_t>::stream(s, indent + " ", v.distance); 00583 s << indent << "angle: "; 00584 Printer<int16_t>::stream(s, indent + " ", v.angle); 00585 s << indent << "chargingState: "; 00586 Printer<uint8_t>::stream(s, indent + " ", v.chargingState); 00587 s << indent << "voltage: "; 00588 Printer<uint16_t>::stream(s, indent + " ", v.voltage); 00589 s << indent << "current: "; 00590 Printer<int16_t>::stream(s, indent + " ", v.current); 00591 s << indent << "batteryTemperature: "; 00592 Printer<int8_t>::stream(s, indent + " ", v.batteryTemperature); 00593 s << indent << "batteryCharge: "; 00594 Printer<uint16_t>::stream(s, indent + " ", v.batteryCharge); 00595 s << indent << "batteryCapacity: "; 00596 Printer<uint16_t>::stream(s, indent + " ", v.batteryCapacity); 00597 s << indent << "wallSignal: "; 00598 Printer<uint16_t>::stream(s, indent + " ", v.wallSignal); 00599 s << indent << "cliffLeftSignal: "; 00600 Printer<uint16_t>::stream(s, indent + " ", v.cliffLeftSignal); 00601 s << indent << "cliffFrontLeftSignal: "; 00602 Printer<uint16_t>::stream(s, indent + " ", v.cliffFrontLeftSignal); 00603 s << indent << "cliffFrontRightSignal: "; 00604 Printer<uint16_t>::stream(s, indent + " ", v.cliffFrontRightSignal); 00605 s << indent << "cliffRightSignal: "; 00606 Printer<uint16_t>::stream(s, indent + " ", v.cliffRightSignal); 00607 s << indent << "homeBase: "; 00608 Printer<uint8_t>::stream(s, indent + " ", v.homeBase); 00609 s << indent << "internalCharger: "; 00610 Printer<uint8_t>::stream(s, indent + " ", v.internalCharger); 00611 s << indent << "songNumber: "; 00612 Printer<uint8_t>::stream(s, indent + " ", v.songNumber); 00613 s << indent << "songPlaying: "; 00614 Printer<uint8_t>::stream(s, indent + " ", v.songPlaying); 00615 } 00616 }; 00617 00618 00619 } // namespace message_operations 00620 } // namespace ros 00621 00622 #endif // IROBOT_CREATE_2_1_MESSAGE_SENSORPACKET_H 00623