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