PowerBoardState.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/PowerBoardState.msg */
00002 #ifndef PR2_MSGS_MESSAGE_POWERBOARDSTATE_H
00003 #define PR2_MSGS_MESSAGE_POWERBOARDSTATE_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 
00019 namespace pr2_msgs
00020 {
00021 template <class ContainerAllocator>
00022 struct PowerBoardState_ {
00023   typedef PowerBoardState_<ContainerAllocator> Type;
00024 
00025   PowerBoardState_()
00026   : header()
00027   , name()
00028   , serial_num(0)
00029   , input_voltage(0.0)
00030   , master_state(0)
00031   , circuit_state()
00032   , circuit_voltage()
00033   , run_stop(false)
00034   , wireless_stop(false)
00035   {
00036     circuit_state.assign(0);
00037     circuit_voltage.assign(0.0);
00038   }
00039 
00040   PowerBoardState_(const ContainerAllocator& _alloc)
00041   : header(_alloc)
00042   , name(_alloc)
00043   , serial_num(0)
00044   , input_voltage(0.0)
00045   , master_state(0)
00046   , circuit_state()
00047   , circuit_voltage()
00048   , run_stop(false)
00049   , wireless_stop(false)
00050   {
00051     circuit_state.assign(0);
00052     circuit_voltage.assign(0.0);
00053   }
00054 
00055   typedef  ::std_msgs::Header_<ContainerAllocator>  _header_type;
00056    ::std_msgs::Header_<ContainerAllocator>  header;
00057 
00058   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _name_type;
00059   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  name;
00060 
00061   typedef uint32_t _serial_num_type;
00062   uint32_t serial_num;
00063 
00064   typedef double _input_voltage_type;
00065   double input_voltage;
00066 
00067   typedef int8_t _master_state_type;
00068   int8_t master_state;
00069 
00070   typedef boost::array<int8_t, 3>  _circuit_state_type;
00071   boost::array<int8_t, 3>  circuit_state;
00072 
00073   typedef boost::array<double, 3>  _circuit_voltage_type;
00074   boost::array<double, 3>  circuit_voltage;
00075 
00076   typedef uint8_t _run_stop_type;
00077   uint8_t run_stop;
00078 
00079   typedef uint8_t _wireless_stop_type;
00080   uint8_t wireless_stop;
00081 
00082   enum { STATE_NOPOWER = 0 };
00083   enum { STATE_STANDBY = 1 };
00084   enum { STATE_PUMPING = 2 };
00085   enum { STATE_ON = 3 };
00086   enum { STATE_ENABLED = 3 };
00087   enum { STATE_DISABLED = 4 };
00088   enum { MASTER_NOPOWER = 0 };
00089   enum { MASTER_STANDBY = 1 };
00090   enum { MASTER_ON = 2 };
00091   enum { MASTER_OFF = 3 };
00092   enum { MASTER_SHUTDOWN = 4 };
00093 
00094   typedef boost::shared_ptr< ::pr2_msgs::PowerBoardState_<ContainerAllocator> > Ptr;
00095   typedef boost::shared_ptr< ::pr2_msgs::PowerBoardState_<ContainerAllocator>  const> ConstPtr;
00096   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00097 }; // struct PowerBoardState
00098 typedef  ::pr2_msgs::PowerBoardState_<std::allocator<void> > PowerBoardState;
00099 
00100 typedef boost::shared_ptr< ::pr2_msgs::PowerBoardState> PowerBoardStatePtr;
00101 typedef boost::shared_ptr< ::pr2_msgs::PowerBoardState const> PowerBoardStateConstPtr;
00102 
00103 
00104 template<typename ContainerAllocator>
00105 std::ostream& operator<<(std::ostream& s, const  ::pr2_msgs::PowerBoardState_<ContainerAllocator> & v)
00106 {
00107   ros::message_operations::Printer< ::pr2_msgs::PowerBoardState_<ContainerAllocator> >::stream(s, "", v);
00108   return s;}
00109 
00110 } // namespace pr2_msgs
00111 
00112 namespace ros
00113 {
00114 namespace message_traits
00115 {
00116 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::PowerBoardState_<ContainerAllocator> > : public TrueType {};
00117 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::PowerBoardState_<ContainerAllocator>  const> : public TrueType {};
00118 template<class ContainerAllocator>
00119 struct MD5Sum< ::pr2_msgs::PowerBoardState_<ContainerAllocator> > {
00120   static const char* value() 
00121   {
00122     return "08899b671e6a1a449e7ce0000da8ae7b";
00123   }
00124 
00125   static const char* value(const  ::pr2_msgs::PowerBoardState_<ContainerAllocator> &) { return value(); } 
00126   static const uint64_t static_value1 = 0x08899b671e6a1a44ULL;
00127   static const uint64_t static_value2 = 0x9e7ce0000da8ae7bULL;
00128 };
00129 
00130 template<class ContainerAllocator>
00131 struct DataType< ::pr2_msgs::PowerBoardState_<ContainerAllocator> > {
00132   static const char* value() 
00133   {
00134     return "pr2_msgs/PowerBoardState";
00135   }
00136 
00137   static const char* value(const  ::pr2_msgs::PowerBoardState_<ContainerAllocator> &) { return value(); } 
00138 };
00139 
00140 template<class ContainerAllocator>
00141 struct Definition< ::pr2_msgs::PowerBoardState_<ContainerAllocator> > {
00142   static const char* value() 
00143   {
00144     return "# This message communicates the state of the PR2's power board.\n\
00145 int8 STATE_NOPOWER=0\n\
00146 int8 STATE_STANDBY=1\n\
00147 int8 STATE_PUMPING=2\n\
00148 int8 STATE_ON=3\n\
00149 int8 STATE_ENABLED=3  # Preferred over STATE_ON, keeping STATE_ON for backcompat\n\
00150 int8 STATE_DISABLED=4\n\
00151 \n\
00152 int8 MASTER_NOPOWER=0\n\
00153 int8 MASTER_STANDBY=1\n\
00154 int8 MASTER_ON=2\n\
00155 int8 MASTER_OFF=3\n\
00156 int8 MASTER_SHUTDOWN=4\n\
00157 \n\
00158 Header header\n\
00159 string name # Name with serial number\n\
00160 uint32 serial_num # Serial number for this board's message\n\
00161 float64 input_voltage # Input voltage to power board\n\
00162 \n\
00163 # Master States:\n\
00164 #  MASTER_NOPOWER, MASTER_STANDBY, MASTER_ON, MASTER_OFF, MASTER_SHUTDOWN \n\
00165 int8 master_state  # The master state machine's state in the powerboard\n\
00166 \n\
00167 # Circuit States:\n\
00168 #  STATE_NOPOWER, STATE_STANDBY, STATE_PUMPING, STATE_ON, STATE_DISABLED\n\
00169 int8[3] circuit_state # One of the above states\n\
00170 float64[3] circuit_voltage  # Output voltage of each circuit\n\
00171 \n\
00172 # True if robot should be enabled\n\
00173 bool run_stop           #Note - if the wireless run-stop is hit, this will be unobservable\n\
00174 bool wireless_stop \n\
00175 \n\
00176 ================================================================================\n\
00177 MSG: std_msgs/Header\n\
00178 # Standard metadata for higher-level stamped data types.\n\
00179 # This is generally used to communicate timestamped data \n\
00180 # in a particular coordinate frame.\n\
00181 # \n\
00182 # sequence ID: consecutively increasing ID \n\
00183 uint32 seq\n\
00184 #Two-integer timestamp that is expressed as:\n\
00185 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00186 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00187 # time-handling sugar is provided by the client library\n\
00188 time stamp\n\
00189 #Frame this data is associated with\n\
00190 # 0: no frame\n\
00191 # 1: global frame\n\
00192 string frame_id\n\
00193 \n\
00194 ";
00195   }
00196 
00197   static const char* value(const  ::pr2_msgs::PowerBoardState_<ContainerAllocator> &) { return value(); } 
00198 };
00199 
00200 template<class ContainerAllocator> struct HasHeader< ::pr2_msgs::PowerBoardState_<ContainerAllocator> > : public TrueType {};
00201 template<class ContainerAllocator> struct HasHeader< const ::pr2_msgs::PowerBoardState_<ContainerAllocator> > : public TrueType {};
00202 } // namespace message_traits
00203 } // namespace ros
00204 
00205 namespace ros
00206 {
00207 namespace serialization
00208 {
00209 
00210 template<class ContainerAllocator> struct Serializer< ::pr2_msgs::PowerBoardState_<ContainerAllocator> >
00211 {
00212   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00213   {
00214     stream.next(m.header);
00215     stream.next(m.name);
00216     stream.next(m.serial_num);
00217     stream.next(m.input_voltage);
00218     stream.next(m.master_state);
00219     stream.next(m.circuit_state);
00220     stream.next(m.circuit_voltage);
00221     stream.next(m.run_stop);
00222     stream.next(m.wireless_stop);
00223   }
00224 
00225   ROS_DECLARE_ALLINONE_SERIALIZER;
00226 }; // struct PowerBoardState_
00227 } // namespace serialization
00228 } // namespace ros
00229 
00230 namespace ros
00231 {
00232 namespace message_operations
00233 {
00234 
00235 template<class ContainerAllocator>
00236 struct Printer< ::pr2_msgs::PowerBoardState_<ContainerAllocator> >
00237 {
00238   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::pr2_msgs::PowerBoardState_<ContainerAllocator> & v) 
00239   {
00240     s << indent << "header: ";
00241 s << std::endl;
00242     Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + "  ", v.header);
00243     s << indent << "name: ";
00244     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.name);
00245     s << indent << "serial_num: ";
00246     Printer<uint32_t>::stream(s, indent + "  ", v.serial_num);
00247     s << indent << "input_voltage: ";
00248     Printer<double>::stream(s, indent + "  ", v.input_voltage);
00249     s << indent << "master_state: ";
00250     Printer<int8_t>::stream(s, indent + "  ", v.master_state);
00251     s << indent << "circuit_state[]" << std::endl;
00252     for (size_t i = 0; i < v.circuit_state.size(); ++i)
00253     {
00254       s << indent << "  circuit_state[" << i << "]: ";
00255       Printer<int8_t>::stream(s, indent + "  ", v.circuit_state[i]);
00256     }
00257     s << indent << "circuit_voltage[]" << std::endl;
00258     for (size_t i = 0; i < v.circuit_voltage.size(); ++i)
00259     {
00260       s << indent << "  circuit_voltage[" << i << "]: ";
00261       Printer<double>::stream(s, indent + "  ", v.circuit_voltage[i]);
00262     }
00263     s << indent << "run_stop: ";
00264     Printer<uint8_t>::stream(s, indent + "  ", v.run_stop);
00265     s << indent << "wireless_stop: ";
00266     Printer<uint8_t>::stream(s, indent + "  ", v.wireless_stop);
00267   }
00268 };
00269 
00270 
00271 } // namespace message_operations
00272 } // namespace ros
00273 
00274 #endif // PR2_MSGS_MESSAGE_POWERBOARDSTATE_H
00275 


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