00001
00002 #ifndef PR2_MSGS_MESSAGE_BATTERYSTATE2_H
00003 #define PR2_MSGS_MESSAGE_BATTERYSTATE2_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
00018 namespace pr2_msgs
00019 {
00020 template <class ContainerAllocator>
00021 struct BatteryState2_ {
00022 typedef BatteryState2_<ContainerAllocator> Type;
00023
00024 BatteryState2_()
00025 : present(false)
00026 , charging(false)
00027 , discharging(false)
00028 , power_present(false)
00029 , power_no_good(false)
00030 , inhibited(false)
00031 , last_battery_update()
00032 , battery_register()
00033 , battery_update_flag()
00034 , battery_register_update()
00035 {
00036 battery_register.assign(0);
00037 battery_update_flag.assign(false);
00038 }
00039
00040 BatteryState2_(const ContainerAllocator& _alloc)
00041 : present(false)
00042 , charging(false)
00043 , discharging(false)
00044 , power_present(false)
00045 , power_no_good(false)
00046 , inhibited(false)
00047 , last_battery_update()
00048 , battery_register()
00049 , battery_update_flag()
00050 , battery_register_update()
00051 {
00052 battery_register.assign(0);
00053 battery_update_flag.assign(false);
00054 }
00055
00056 typedef uint8_t _present_type;
00057 uint8_t present;
00058
00059 typedef uint8_t _charging_type;
00060 uint8_t charging;
00061
00062 typedef uint8_t _discharging_type;
00063 uint8_t discharging;
00064
00065 typedef uint8_t _power_present_type;
00066 uint8_t power_present;
00067
00068 typedef uint8_t _power_no_good_type;
00069 uint8_t power_no_good;
00070
00071 typedef uint8_t _inhibited_type;
00072 uint8_t inhibited;
00073
00074 typedef ros::Time _last_battery_update_type;
00075 ros::Time last_battery_update;
00076
00077 typedef boost::array<int16_t, 48> _battery_register_type;
00078 boost::array<int16_t, 48> battery_register;
00079
00080 typedef boost::array<uint8_t, 48> _battery_update_flag_type;
00081 boost::array<uint8_t, 48> battery_update_flag;
00082
00083 typedef boost::array<ros::Time, 48> _battery_register_update_type;
00084 boost::array<ros::Time, 48> battery_register_update;
00085
00086
00087 ROS_DEPRECATED uint32_t get_battery_register_size() const { return (uint32_t)battery_register.size(); }
00088 ROS_DEPRECATED uint32_t get_battery_update_flag_size() const { return (uint32_t)battery_update_flag.size(); }
00089 ROS_DEPRECATED uint32_t get_battery_register_update_size() const { return (uint32_t)battery_register_update.size(); }
00090 private:
00091 static const char* __s_getDataType_() { return "pr2_msgs/BatteryState2"; }
00092 public:
00093 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00094
00095 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00096
00097 private:
00098 static const char* __s_getMD5Sum_() { return "91b4acb000aa990ac3006834f9a99669"; }
00099 public:
00100 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00101
00102 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00103
00104 private:
00105 static const char* __s_getMessageDefinition_() { return "# This message communicates the state of a single battery.\n\
00106 # Battery Controller Flags, one per battery\n\
00107 bool present # is this pack present\n\
00108 bool charging # is this pack charging\n\
00109 bool discharging # is this pack discharging\n\
00110 bool power_present # is there an input voltage\n\
00111 bool power_no_good # is there a fault (No Good)\n\
00112 bool inhibited # is this pack disabled for some reason\n\
00113 # These registers are per battery\n\
00114 time last_battery_update # last time any battery update occurred\n\
00115 int16[48] battery_register # value of this register in the battery\n\
00116 bool[48] battery_update_flag # Has this register ever been updated\n\
00117 time[48] battery_register_update # last time this specific register was updated\n\
00118 \n\
00119 "; }
00120 public:
00121 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00122
00123 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00124
00125 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00126 {
00127 ros::serialization::OStream stream(write_ptr, 1000000000);
00128 ros::serialization::serialize(stream, present);
00129 ros::serialization::serialize(stream, charging);
00130 ros::serialization::serialize(stream, discharging);
00131 ros::serialization::serialize(stream, power_present);
00132 ros::serialization::serialize(stream, power_no_good);
00133 ros::serialization::serialize(stream, inhibited);
00134 ros::serialization::serialize(stream, last_battery_update);
00135 ros::serialization::serialize(stream, battery_register);
00136 ros::serialization::serialize(stream, battery_update_flag);
00137 ros::serialization::serialize(stream, battery_register_update);
00138 return stream.getData();
00139 }
00140
00141 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00142 {
00143 ros::serialization::IStream stream(read_ptr, 1000000000);
00144 ros::serialization::deserialize(stream, present);
00145 ros::serialization::deserialize(stream, charging);
00146 ros::serialization::deserialize(stream, discharging);
00147 ros::serialization::deserialize(stream, power_present);
00148 ros::serialization::deserialize(stream, power_no_good);
00149 ros::serialization::deserialize(stream, inhibited);
00150 ros::serialization::deserialize(stream, last_battery_update);
00151 ros::serialization::deserialize(stream, battery_register);
00152 ros::serialization::deserialize(stream, battery_update_flag);
00153 ros::serialization::deserialize(stream, battery_register_update);
00154 return stream.getData();
00155 }
00156
00157 ROS_DEPRECATED virtual uint32_t serializationLength() const
00158 {
00159 uint32_t size = 0;
00160 size += ros::serialization::serializationLength(present);
00161 size += ros::serialization::serializationLength(charging);
00162 size += ros::serialization::serializationLength(discharging);
00163 size += ros::serialization::serializationLength(power_present);
00164 size += ros::serialization::serializationLength(power_no_good);
00165 size += ros::serialization::serializationLength(inhibited);
00166 size += ros::serialization::serializationLength(last_battery_update);
00167 size += ros::serialization::serializationLength(battery_register);
00168 size += ros::serialization::serializationLength(battery_update_flag);
00169 size += ros::serialization::serializationLength(battery_register_update);
00170 return size;
00171 }
00172
00173 typedef boost::shared_ptr< ::pr2_msgs::BatteryState2_<ContainerAllocator> > Ptr;
00174 typedef boost::shared_ptr< ::pr2_msgs::BatteryState2_<ContainerAllocator> const> ConstPtr;
00175 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00176 };
00177 typedef ::pr2_msgs::BatteryState2_<std::allocator<void> > BatteryState2;
00178
00179 typedef boost::shared_ptr< ::pr2_msgs::BatteryState2> BatteryState2Ptr;
00180 typedef boost::shared_ptr< ::pr2_msgs::BatteryState2 const> BatteryState2ConstPtr;
00181
00182
00183 template<typename ContainerAllocator>
00184 std::ostream& operator<<(std::ostream& s, const ::pr2_msgs::BatteryState2_<ContainerAllocator> & v)
00185 {
00186 ros::message_operations::Printer< ::pr2_msgs::BatteryState2_<ContainerAllocator> >::stream(s, "", v);
00187 return s;}
00188
00189 }
00190
00191 namespace ros
00192 {
00193 namespace message_traits
00194 {
00195 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::BatteryState2_<ContainerAllocator> > : public TrueType {};
00196 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::BatteryState2_<ContainerAllocator> const> : public TrueType {};
00197 template<class ContainerAllocator>
00198 struct MD5Sum< ::pr2_msgs::BatteryState2_<ContainerAllocator> > {
00199 static const char* value()
00200 {
00201 return "91b4acb000aa990ac3006834f9a99669";
00202 }
00203
00204 static const char* value(const ::pr2_msgs::BatteryState2_<ContainerAllocator> &) { return value(); }
00205 static const uint64_t static_value1 = 0x91b4acb000aa990aULL;
00206 static const uint64_t static_value2 = 0xc3006834f9a99669ULL;
00207 };
00208
00209 template<class ContainerAllocator>
00210 struct DataType< ::pr2_msgs::BatteryState2_<ContainerAllocator> > {
00211 static const char* value()
00212 {
00213 return "pr2_msgs/BatteryState2";
00214 }
00215
00216 static const char* value(const ::pr2_msgs::BatteryState2_<ContainerAllocator> &) { return value(); }
00217 };
00218
00219 template<class ContainerAllocator>
00220 struct Definition< ::pr2_msgs::BatteryState2_<ContainerAllocator> > {
00221 static const char* value()
00222 {
00223 return "# This message communicates the state of a single battery.\n\
00224 # Battery Controller Flags, one per battery\n\
00225 bool present # is this pack present\n\
00226 bool charging # is this pack charging\n\
00227 bool discharging # is this pack discharging\n\
00228 bool power_present # is there an input voltage\n\
00229 bool power_no_good # is there a fault (No Good)\n\
00230 bool inhibited # is this pack disabled for some reason\n\
00231 # These registers are per battery\n\
00232 time last_battery_update # last time any battery update occurred\n\
00233 int16[48] battery_register # value of this register in the battery\n\
00234 bool[48] battery_update_flag # Has this register ever been updated\n\
00235 time[48] battery_register_update # last time this specific register was updated\n\
00236 \n\
00237 ";
00238 }
00239
00240 static const char* value(const ::pr2_msgs::BatteryState2_<ContainerAllocator> &) { return value(); }
00241 };
00242
00243 template<class ContainerAllocator> struct IsFixedSize< ::pr2_msgs::BatteryState2_<ContainerAllocator> > : public TrueType {};
00244 }
00245 }
00246
00247 namespace ros
00248 {
00249 namespace serialization
00250 {
00251
00252 template<class ContainerAllocator> struct Serializer< ::pr2_msgs::BatteryState2_<ContainerAllocator> >
00253 {
00254 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00255 {
00256 stream.next(m.present);
00257 stream.next(m.charging);
00258 stream.next(m.discharging);
00259 stream.next(m.power_present);
00260 stream.next(m.power_no_good);
00261 stream.next(m.inhibited);
00262 stream.next(m.last_battery_update);
00263 stream.next(m.battery_register);
00264 stream.next(m.battery_update_flag);
00265 stream.next(m.battery_register_update);
00266 }
00267
00268 ROS_DECLARE_ALLINONE_SERIALIZER;
00269 };
00270 }
00271 }
00272
00273 namespace ros
00274 {
00275 namespace message_operations
00276 {
00277
00278 template<class ContainerAllocator>
00279 struct Printer< ::pr2_msgs::BatteryState2_<ContainerAllocator> >
00280 {
00281 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_msgs::BatteryState2_<ContainerAllocator> & v)
00282 {
00283 s << indent << "present: ";
00284 Printer<uint8_t>::stream(s, indent + " ", v.present);
00285 s << indent << "charging: ";
00286 Printer<uint8_t>::stream(s, indent + " ", v.charging);
00287 s << indent << "discharging: ";
00288 Printer<uint8_t>::stream(s, indent + " ", v.discharging);
00289 s << indent << "power_present: ";
00290 Printer<uint8_t>::stream(s, indent + " ", v.power_present);
00291 s << indent << "power_no_good: ";
00292 Printer<uint8_t>::stream(s, indent + " ", v.power_no_good);
00293 s << indent << "inhibited: ";
00294 Printer<uint8_t>::stream(s, indent + " ", v.inhibited);
00295 s << indent << "last_battery_update: ";
00296 Printer<ros::Time>::stream(s, indent + " ", v.last_battery_update);
00297 s << indent << "battery_register[]" << std::endl;
00298 for (size_t i = 0; i < v.battery_register.size(); ++i)
00299 {
00300 s << indent << " battery_register[" << i << "]: ";
00301 Printer<int16_t>::stream(s, indent + " ", v.battery_register[i]);
00302 }
00303 s << indent << "battery_update_flag[]" << std::endl;
00304 for (size_t i = 0; i < v.battery_update_flag.size(); ++i)
00305 {
00306 s << indent << " battery_update_flag[" << i << "]: ";
00307 Printer<uint8_t>::stream(s, indent + " ", v.battery_update_flag[i]);
00308 }
00309 s << indent << "battery_register_update[]" << std::endl;
00310 for (size_t i = 0; i < v.battery_register_update.size(); ++i)
00311 {
00312 s << indent << " battery_register_update[" << i << "]: ";
00313 Printer<ros::Time>::stream(s, indent + " ", v.battery_register_update[i]);
00314 }
00315 }
00316 };
00317
00318
00319 }
00320 }
00321
00322 #endif // PR2_MSGS_MESSAGE_BATTERYSTATE2_H
00323