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