BatteryServer2.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-pr2_common/doc_stacks/2014-01-06_11-32-47.864635/pr2_common/pr2_msgs/msg/BatteryServer2.msg */
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   typedef boost::shared_ptr< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > Ptr;
00078   typedef boost::shared_ptr< ::pr2_msgs::BatteryServer2_<ContainerAllocator>  const> ConstPtr;
00079   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00080 }; // struct BatteryServer2
00081 typedef  ::pr2_msgs::BatteryServer2_<std::allocator<void> > BatteryServer2;
00082 
00083 typedef boost::shared_ptr< ::pr2_msgs::BatteryServer2> BatteryServer2Ptr;
00084 typedef boost::shared_ptr< ::pr2_msgs::BatteryServer2 const> BatteryServer2ConstPtr;
00085 
00086 
00087 template<typename ContainerAllocator>
00088 std::ostream& operator<<(std::ostream& s, const  ::pr2_msgs::BatteryServer2_<ContainerAllocator> & v)
00089 {
00090   ros::message_operations::Printer< ::pr2_msgs::BatteryServer2_<ContainerAllocator> >::stream(s, "", v);
00091   return s;}
00092 
00093 } // namespace pr2_msgs
00094 
00095 namespace ros
00096 {
00097 namespace message_traits
00098 {
00099 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > : public TrueType {};
00100 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::BatteryServer2_<ContainerAllocator>  const> : public TrueType {};
00101 template<class ContainerAllocator>
00102 struct MD5Sum< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > {
00103   static const char* value() 
00104   {
00105     return "5f2cec7d06c312d756189db96c1f3819";
00106   }
00107 
00108   static const char* value(const  ::pr2_msgs::BatteryServer2_<ContainerAllocator> &) { return value(); } 
00109   static const uint64_t static_value1 = 0x5f2cec7d06c312d7ULL;
00110   static const uint64_t static_value2 = 0x56189db96c1f3819ULL;
00111 };
00112 
00113 template<class ContainerAllocator>
00114 struct DataType< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > {
00115   static const char* value() 
00116   {
00117     return "pr2_msgs/BatteryServer2";
00118   }
00119 
00120   static const char* value(const  ::pr2_msgs::BatteryServer2_<ContainerAllocator> &) { return value(); } 
00121 };
00122 
00123 template<class ContainerAllocator>
00124 struct Definition< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > {
00125   static const char* value() 
00126   {
00127     return "# This message communicates the state of a battery server, which controls\n\
00128 # multiple batteries.\n\
00129 Header header\n\
00130 int32 MAX_BAT_COUNT=4\n\
00131 int32 MAX_BAT_REG=48\n\
00132 int32 id  # unique ID for each battery server\n\
00133 # Battery System Stats\n\
00134 time last_system_update  # last time the system stats where updated\n\
00135 duration time_left       # in seconds (hardware resolution is 1 minute)\n\
00136 int32 average_charge     # in percent\n\
00137 string message           # message from the ocean server\n\
00138 time last_controller_update # last time a battery status flag was updated\n\
00139 # for each battery\n\
00140 pr2_msgs/BatteryState2[] battery\n\
00141 \n\
00142 ================================================================================\n\
00143 MSG: std_msgs/Header\n\
00144 # Standard metadata for higher-level stamped data types.\n\
00145 # This is generally used to communicate timestamped data \n\
00146 # in a particular coordinate frame.\n\
00147 # \n\
00148 # sequence ID: consecutively increasing ID \n\
00149 uint32 seq\n\
00150 #Two-integer timestamp that is expressed as:\n\
00151 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00152 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00153 # time-handling sugar is provided by the client library\n\
00154 time stamp\n\
00155 #Frame this data is associated with\n\
00156 # 0: no frame\n\
00157 # 1: global frame\n\
00158 string frame_id\n\
00159 \n\
00160 ================================================================================\n\
00161 MSG: pr2_msgs/BatteryState2\n\
00162 # This message communicates the state of a single battery.\n\
00163 # Battery Controller Flags, one per battery\n\
00164 bool present       # is this pack present\n\
00165 bool charging      # is this pack charging\n\
00166 bool discharging   # is this pack discharging\n\
00167 bool power_present # is there an input voltage\n\
00168 bool power_no_good # is there a fault (No Good)\n\
00169 bool inhibited     # is this pack disabled for some reason\n\
00170 # These registers are per battery\n\
00171 time      last_battery_update     # last time any battery update occurred\n\
00172 int16[48] battery_register        # value of this register in the battery\n\
00173 bool[48]  battery_update_flag     # Has this register ever been updated\n\
00174 time[48]  battery_register_update # last time this specific register was updated\n\
00175 \n\
00176 ";
00177   }
00178 
00179   static const char* value(const  ::pr2_msgs::BatteryServer2_<ContainerAllocator> &) { return value(); } 
00180 };
00181 
00182 template<class ContainerAllocator> struct HasHeader< ::pr2_msgs::BatteryServer2_<ContainerAllocator> > : public TrueType {};
00183 template<class ContainerAllocator> struct HasHeader< const ::pr2_msgs::BatteryServer2_<ContainerAllocator> > : public TrueType {};
00184 } // namespace message_traits
00185 } // namespace ros
00186 
00187 namespace ros
00188 {
00189 namespace serialization
00190 {
00191 
00192 template<class ContainerAllocator> struct Serializer< ::pr2_msgs::BatteryServer2_<ContainerAllocator> >
00193 {
00194   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00195   {
00196     stream.next(m.header);
00197     stream.next(m.id);
00198     stream.next(m.last_system_update);
00199     stream.next(m.time_left);
00200     stream.next(m.average_charge);
00201     stream.next(m.message);
00202     stream.next(m.last_controller_update);
00203     stream.next(m.battery);
00204   }
00205 
00206   ROS_DECLARE_ALLINONE_SERIALIZER;
00207 }; // struct BatteryServer2_
00208 } // namespace serialization
00209 } // namespace ros
00210 
00211 namespace ros
00212 {
00213 namespace message_operations
00214 {
00215 
00216 template<class ContainerAllocator>
00217 struct Printer< ::pr2_msgs::BatteryServer2_<ContainerAllocator> >
00218 {
00219   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::pr2_msgs::BatteryServer2_<ContainerAllocator> & v) 
00220   {
00221     s << indent << "header: ";
00222 s << std::endl;
00223     Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + "  ", v.header);
00224     s << indent << "id: ";
00225     Printer<int32_t>::stream(s, indent + "  ", v.id);
00226     s << indent << "last_system_update: ";
00227     Printer<ros::Time>::stream(s, indent + "  ", v.last_system_update);
00228     s << indent << "time_left: ";
00229     Printer<ros::Duration>::stream(s, indent + "  ", v.time_left);
00230     s << indent << "average_charge: ";
00231     Printer<int32_t>::stream(s, indent + "  ", v.average_charge);
00232     s << indent << "message: ";
00233     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.message);
00234     s << indent << "last_controller_update: ";
00235     Printer<ros::Time>::stream(s, indent + "  ", v.last_controller_update);
00236     s << indent << "battery[]" << std::endl;
00237     for (size_t i = 0; i < v.battery.size(); ++i)
00238     {
00239       s << indent << "  battery[" << i << "]: ";
00240       s << std::endl;
00241       s << indent;
00242       Printer< ::pr2_msgs::BatteryState2_<ContainerAllocator> >::stream(s, indent + "    ", v.battery[i]);
00243     }
00244   }
00245 };
00246 
00247 
00248 } // namespace message_operations
00249 } // namespace ros
00250 
00251 #endif // PR2_MSGS_MESSAGE_BATTERYSERVER2_H
00252 


pr2_msgs
Author(s): Eric Berger and many others
autogenerated on Mon Jan 6 2014 11:34:07