00001
00002 #ifndef PR2_MSGS_MESSAGE_BATTERYSERVER2_H
00003 #define PR2_MSGS_MESSAGE_BATTERYSERVER2_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 "pr2_msgs/BatteryState2.h"
00015
00016 namespace pr2_msgs
00017 {
00018 template <class ContainerAllocator>
00019 struct BatteryServer2_ : public ros::Message
00020 {
00021 typedef BatteryServer2_<ContainerAllocator> Type;
00022
00023 BatteryServer2_()
00024 : header()
00025 , id(0)
00026 , last_system_update()
00027 , time_left()
00028 , average_charge(0)
00029 , message()
00030 , last_controller_update()
00031 , battery()
00032 {
00033 }
00034
00035 BatteryServer2_(const ContainerAllocator& _alloc)
00036 : header(_alloc)
00037 , id(0)
00038 , last_system_update()
00039 , time_left()
00040 , average_charge(0)
00041 , message(_alloc)
00042 , last_controller_update()
00043 , battery(_alloc)
00044 {
00045 }
00046
00047 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00048 ::std_msgs::Header_<ContainerAllocator> header;
00049
00050 typedef int32_t _id_type;
00051 int32_t id;
00052
00053 typedef ros::Time _last_system_update_type;
00054 ros::Time last_system_update;
00055
00056 typedef ros::Duration _time_left_type;
00057 ros::Duration time_left;
00058
00059 typedef int32_t _average_charge_type;
00060 int32_t average_charge;
00061
00062 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _message_type;
00063 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > message;
00064
00065 typedef ros::Time _last_controller_update_type;
00066 ros::Time last_controller_update;
00067
00068 typedef std::vector< ::pr2_msgs::BatteryState2_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_msgs::BatteryState2_<ContainerAllocator> >::other > _battery_type;
00069 std::vector< ::pr2_msgs::BatteryState2_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_msgs::BatteryState2_<ContainerAllocator> >::other > battery;
00070
00071 enum { MAX_BAT_COUNT = 4 };
00072 enum { MAX_BAT_REG = 48 };
00073
00074 ROS_DEPRECATED uint32_t get_battery_size() const { return (uint32_t)battery.size(); }
00075 ROS_DEPRECATED void set_battery_size(uint32_t size) { battery.resize((size_t)size); }
00076 ROS_DEPRECATED void get_battery_vec(std::vector< ::pr2_msgs::BatteryState2_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_msgs::BatteryState2_<ContainerAllocator> >::other > & vec) const { vec = this->battery; }
00077 ROS_DEPRECATED void set_battery_vec(const std::vector< ::pr2_msgs::BatteryState2_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pr2_msgs::BatteryState2_<ContainerAllocator> >::other > & vec) { this->battery = vec; }
00078 private:
00079 static const char* __s_getDataType_() { return "pr2_msgs/BatteryServer2"; }
00080 public:
00081 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00082
00083 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00084
00085 private:
00086 static const char* __s_getMD5Sum_() { return "5f2cec7d06c312d756189db96c1f3819"; }
00087 public:
00088 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00089
00090 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00091
00092 private:
00093 static const char* __s_getMessageDefinition_() { return "# This message communicates the state of a battery server, which controls\n\
00094 # multiple batteries.\n\
00095 Header header\n\
00096 int32 MAX_BAT_COUNT=4\n\
00097 int32 MAX_BAT_REG=48\n\
00098 int32 id # unique ID for each battery server\n\
00099 # Battery System Stats\n\
00100 time last_system_update # last time the system stats where updated\n\
00101 duration time_left # in seconds (hardware resolution is 1 minute)\n\
00102 int32 average_charge # in percent\n\
00103 string message # message from the ocean server\n\
00104 time last_controller_update # last time a battery status flag was updated\n\
00105 # for each battery\n\
00106 pr2_msgs/BatteryState2[] battery\n\
00107 \n\
00108 ================================================================================\n\
00109 MSG: std_msgs/Header\n\
00110 # Standard metadata for higher-level stamped data types.\n\
00111 # This is generally used to communicate timestamped data \n\
00112 # in a particular coordinate frame.\n\
00113 # \n\
00114 # sequence ID: consecutively increasing ID \n\
00115 uint32 seq\n\
00116 #Two-integer timestamp that is expressed as:\n\
00117 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00118 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00119 # time-handling sugar is provided by the client library\n\
00120 time stamp\n\
00121 #Frame this data is associated with\n\
00122 # 0: no frame\n\
00123 # 1: global frame\n\
00124 string frame_id\n\
00125 \n\
00126 ================================================================================\n\
00127 MSG: pr2_msgs/BatteryState2\n\
00128 # This message communicates the state of a single battery.\n\
00129 # Battery Controller Flags, one per battery\n\
00130 bool present # is this pack present\n\
00131 bool charging # is this pack charging\n\
00132 bool discharging # is this pack discharging\n\
00133 bool power_present # is there an input voltage\n\
00134 bool power_no_good # is there a fault (No Good)\n\
00135 bool inhibited # is this pack disabled for some reason\n\
00136 # These registers are per battery\n\
00137 time last_battery_update # last time any battery update occurred\n\
00138 int16[48] battery_register # value of this register in the battery\n\
00139 bool[48] battery_update_flag # Has this register ever been updated\n\
00140 time[48] battery_register_update # last time this specific register was updated\n\
00141 \n\
00142 "; }
00143 public:
00144 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00145
00146 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00147
00148 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00149 {
00150 ros::serialization::OStream stream(write_ptr, 1000000000);
00151 ros::serialization::serialize(stream, header);
00152 ros::serialization::serialize(stream, id);
00153 ros::serialization::serialize(stream, last_system_update);
00154 ros::serialization::serialize(stream, time_left);
00155 ros::serialization::serialize(stream, average_charge);
00156 ros::serialization::serialize(stream, message);
00157 ros::serialization::serialize(stream, last_controller_update);
00158 ros::serialization::serialize(stream, battery);
00159 return stream.getData();
00160 }
00161
00162 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00163 {
00164 ros::serialization::IStream stream(read_ptr, 1000000000);
00165 ros::serialization::deserialize(stream, header);
00166 ros::serialization::deserialize(stream, id);
00167 ros::serialization::deserialize(stream, last_system_update);
00168 ros::serialization::deserialize(stream, time_left);
00169 ros::serialization::deserialize(stream, average_charge);
00170 ros::serialization::deserialize(stream, message);
00171 ros::serialization::deserialize(stream, last_controller_update);
00172 ros::serialization::deserialize(stream, battery);
00173 return stream.getData();
00174 }
00175
00176 ROS_DEPRECATED virtual uint32_t serializationLength() const
00177 {
00178 uint32_t size = 0;
00179 size += ros::serialization::serializationLength(header);
00180 size += ros::serialization::serializationLength(id);
00181 size += ros::serialization::serializationLength(last_system_update);
00182 size += ros::serialization::serializationLength(time_left);
00183 size += ros::serialization::serializationLength(average_charge);
00184 size += ros::serialization::serializationLength(message);
00185 size += ros::serialization::serializationLength(last_controller_update);
00186 size += ros::serialization::serializationLength(battery);
00187 return size;
00188 }
00189
00190 typedef boost::shared_ptr< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > Ptr;
00191 typedef boost::shared_ptr< ::pr2_msgs::BatteryServer2_<ContainerAllocator> const> ConstPtr;
00192 };
00193 typedef ::pr2_msgs::BatteryServer2_<std::allocator<void> > BatteryServer2;
00194
00195 typedef boost::shared_ptr< ::pr2_msgs::BatteryServer2> BatteryServer2Ptr;
00196 typedef boost::shared_ptr< ::pr2_msgs::BatteryServer2 const> BatteryServer2ConstPtr;
00197
00198
00199 template<typename ContainerAllocator>
00200 std::ostream& operator<<(std::ostream& s, const ::pr2_msgs::BatteryServer2_<ContainerAllocator> & v)
00201 {
00202 ros::message_operations::Printer< ::pr2_msgs::BatteryServer2_<ContainerAllocator> >::stream(s, "", v);
00203 return s;}
00204
00205 }
00206
00207 namespace ros
00208 {
00209 namespace message_traits
00210 {
00211 template<class ContainerAllocator>
00212 struct MD5Sum< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > {
00213 static const char* value()
00214 {
00215 return "5f2cec7d06c312d756189db96c1f3819";
00216 }
00217
00218 static const char* value(const ::pr2_msgs::BatteryServer2_<ContainerAllocator> &) { return value(); }
00219 static const uint64_t static_value1 = 0x5f2cec7d06c312d7ULL;
00220 static const uint64_t static_value2 = 0x56189db96c1f3819ULL;
00221 };
00222
00223 template<class ContainerAllocator>
00224 struct DataType< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > {
00225 static const char* value()
00226 {
00227 return "pr2_msgs/BatteryServer2";
00228 }
00229
00230 static const char* value(const ::pr2_msgs::BatteryServer2_<ContainerAllocator> &) { return value(); }
00231 };
00232
00233 template<class ContainerAllocator>
00234 struct Definition< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > {
00235 static const char* value()
00236 {
00237 return "# This message communicates the state of a battery server, which controls\n\
00238 # multiple batteries.\n\
00239 Header header\n\
00240 int32 MAX_BAT_COUNT=4\n\
00241 int32 MAX_BAT_REG=48\n\
00242 int32 id # unique ID for each battery server\n\
00243 # Battery System Stats\n\
00244 time last_system_update # last time the system stats where updated\n\
00245 duration time_left # in seconds (hardware resolution is 1 minute)\n\
00246 int32 average_charge # in percent\n\
00247 string message # message from the ocean server\n\
00248 time last_controller_update # last time a battery status flag was updated\n\
00249 # for each battery\n\
00250 pr2_msgs/BatteryState2[] battery\n\
00251 \n\
00252 ================================================================================\n\
00253 MSG: std_msgs/Header\n\
00254 # Standard metadata for higher-level stamped data types.\n\
00255 # This is generally used to communicate timestamped data \n\
00256 # in a particular coordinate frame.\n\
00257 # \n\
00258 # sequence ID: consecutively increasing ID \n\
00259 uint32 seq\n\
00260 #Two-integer timestamp that is expressed as:\n\
00261 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00262 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00263 # time-handling sugar is provided by the client library\n\
00264 time stamp\n\
00265 #Frame this data is associated with\n\
00266 # 0: no frame\n\
00267 # 1: global frame\n\
00268 string frame_id\n\
00269 \n\
00270 ================================================================================\n\
00271 MSG: pr2_msgs/BatteryState2\n\
00272 # This message communicates the state of a single battery.\n\
00273 # Battery Controller Flags, one per battery\n\
00274 bool present # is this pack present\n\
00275 bool charging # is this pack charging\n\
00276 bool discharging # is this pack discharging\n\
00277 bool power_present # is there an input voltage\n\
00278 bool power_no_good # is there a fault (No Good)\n\
00279 bool inhibited # is this pack disabled for some reason\n\
00280 # These registers are per battery\n\
00281 time last_battery_update # last time any battery update occurred\n\
00282 int16[48] battery_register # value of this register in the battery\n\
00283 bool[48] battery_update_flag # Has this register ever been updated\n\
00284 time[48] battery_register_update # last time this specific register was updated\n\
00285 \n\
00286 ";
00287 }
00288
00289 static const char* value(const ::pr2_msgs::BatteryServer2_<ContainerAllocator> &) { return value(); }
00290 };
00291
00292 template<class ContainerAllocator> struct HasHeader< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > : public TrueType {};
00293 template<class ContainerAllocator> struct HasHeader< const ::pr2_msgs::BatteryServer2_<ContainerAllocator> > : public TrueType {};
00294 }
00295 }
00296
00297 namespace ros
00298 {
00299 namespace serialization
00300 {
00301
00302 template<class ContainerAllocator> struct Serializer< ::pr2_msgs::BatteryServer2_<ContainerAllocator> >
00303 {
00304 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00305 {
00306 stream.next(m.header);
00307 stream.next(m.id);
00308 stream.next(m.last_system_update);
00309 stream.next(m.time_left);
00310 stream.next(m.average_charge);
00311 stream.next(m.message);
00312 stream.next(m.last_controller_update);
00313 stream.next(m.battery);
00314 }
00315
00316 ROS_DECLARE_ALLINONE_SERIALIZER;
00317 };
00318 }
00319 }
00320
00321 namespace ros
00322 {
00323 namespace message_operations
00324 {
00325
00326 template<class ContainerAllocator>
00327 struct Printer< ::pr2_msgs::BatteryServer2_<ContainerAllocator> >
00328 {
00329 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_msgs::BatteryServer2_<ContainerAllocator> & v)
00330 {
00331 s << indent << "header: ";
00332 s << std::endl;
00333 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00334 s << indent << "id: ";
00335 Printer<int32_t>::stream(s, indent + " ", v.id);
00336 s << indent << "last_system_update: ";
00337 Printer<ros::Time>::stream(s, indent + " ", v.last_system_update);
00338 s << indent << "time_left: ";
00339 Printer<ros::Duration>::stream(s, indent + " ", v.time_left);
00340 s << indent << "average_charge: ";
00341 Printer<int32_t>::stream(s, indent + " ", v.average_charge);
00342 s << indent << "message: ";
00343 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.message);
00344 s << indent << "last_controller_update: ";
00345 Printer<ros::Time>::stream(s, indent + " ", v.last_controller_update);
00346 s << indent << "battery[]" << std::endl;
00347 for (size_t i = 0; i < v.battery.size(); ++i)
00348 {
00349 s << indent << " battery[" << i << "]: ";
00350 s << std::endl;
00351 s << indent;
00352 Printer< ::pr2_msgs::BatteryState2_<ContainerAllocator> >::stream(s, indent + " ", v.battery[i]);
00353 }
00354 }
00355 };
00356
00357
00358 }
00359 }
00360
00361 #endif // PR2_MSGS_MESSAGE_BATTERYSERVER2_H
00362