$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_common/doc_stacks/2013-03-01_16-36-22.045406/pr2_common/pr2_msgs/msg/DashboardState.msg */ 00002 #ifndef PR2_MSGS_MESSAGE_DASHBOARDSTATE_H 00003 #define PR2_MSGS_MESSAGE_DASHBOARDSTATE_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/Bool.h" 00018 #include "pr2_msgs/PowerBoardState.h" 00019 #include "pr2_msgs/PowerState.h" 00020 #include "pr2_msgs/AccessPoint.h" 00021 00022 namespace pr2_msgs 00023 { 00024 template <class ContainerAllocator> 00025 struct DashboardState_ { 00026 typedef DashboardState_<ContainerAllocator> Type; 00027 00028 DashboardState_() 00029 : motors_halted() 00030 , motors_halted_valid(false) 00031 , power_board_state() 00032 , power_board_state_valid(false) 00033 , power_state() 00034 , power_state_valid(false) 00035 , access_point() 00036 , access_point_valid(false) 00037 { 00038 } 00039 00040 DashboardState_(const ContainerAllocator& _alloc) 00041 : motors_halted(_alloc) 00042 , motors_halted_valid(false) 00043 , power_board_state(_alloc) 00044 , power_board_state_valid(false) 00045 , power_state(_alloc) 00046 , power_state_valid(false) 00047 , access_point(_alloc) 00048 , access_point_valid(false) 00049 { 00050 } 00051 00052 typedef ::std_msgs::Bool_<ContainerAllocator> _motors_halted_type; 00053 ::std_msgs::Bool_<ContainerAllocator> motors_halted; 00054 00055 typedef uint8_t _motors_halted_valid_type; 00056 uint8_t motors_halted_valid; 00057 00058 typedef ::pr2_msgs::PowerBoardState_<ContainerAllocator> _power_board_state_type; 00059 ::pr2_msgs::PowerBoardState_<ContainerAllocator> power_board_state; 00060 00061 typedef uint8_t _power_board_state_valid_type; 00062 uint8_t power_board_state_valid; 00063 00064 typedef ::pr2_msgs::PowerState_<ContainerAllocator> _power_state_type; 00065 ::pr2_msgs::PowerState_<ContainerAllocator> power_state; 00066 00067 typedef uint8_t _power_state_valid_type; 00068 uint8_t power_state_valid; 00069 00070 typedef ::pr2_msgs::AccessPoint_<ContainerAllocator> _access_point_type; 00071 ::pr2_msgs::AccessPoint_<ContainerAllocator> access_point; 00072 00073 typedef uint8_t _access_point_valid_type; 00074 uint8_t access_point_valid; 00075 00076 00077 private: 00078 static const char* __s_getDataType_() { return "pr2_msgs/DashboardState"; } 00079 public: 00080 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00081 00082 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00083 00084 private: 00085 static const char* __s_getMD5Sum_() { return "db0cd0d535d75e0f6257b20c403e87f5"; } 00086 public: 00087 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00088 00089 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00090 00091 private: 00092 static const char* __s_getMessageDefinition_() { return "# This message communicates state information that might be used by a\n\ 00093 # dashboard application.\n\ 00094 std_msgs/Bool motors_halted\n\ 00095 bool motors_halted_valid\n\ 00096 \n\ 00097 pr2_msgs/PowerBoardState power_board_state\n\ 00098 bool power_board_state_valid\n\ 00099 \n\ 00100 pr2_msgs/PowerState power_state\n\ 00101 bool power_state_valid\n\ 00102 \n\ 00103 pr2_msgs/AccessPoint access_point\n\ 00104 bool access_point_valid\n\ 00105 \n\ 00106 ================================================================================\n\ 00107 MSG: std_msgs/Bool\n\ 00108 bool data\n\ 00109 ================================================================================\n\ 00110 MSG: pr2_msgs/PowerBoardState\n\ 00111 # This message communicates the state of the PR2's power board.\n\ 00112 int8 STATE_NOPOWER=0\n\ 00113 int8 STATE_STANDBY=1\n\ 00114 int8 STATE_PUMPING=2\n\ 00115 int8 STATE_ON=3\n\ 00116 int8 STATE_ENABLED=3 # Preferred over STATE_ON, keeping STATE_ON for backcompat\n\ 00117 int8 STATE_DISABLED=4\n\ 00118 \n\ 00119 int8 MASTER_NOPOWER=0\n\ 00120 int8 MASTER_STANDBY=1\n\ 00121 int8 MASTER_ON=2\n\ 00122 int8 MASTER_OFF=3\n\ 00123 int8 MASTER_SHUTDOWN=4\n\ 00124 \n\ 00125 Header header\n\ 00126 string name # Name with serial number\n\ 00127 uint32 serial_num # Serial number for this board's message\n\ 00128 float64 input_voltage # Input voltage to power board\n\ 00129 \n\ 00130 # Master States:\n\ 00131 # MASTER_NOPOWER, MASTER_STANDBY, MASTER_ON, MASTER_OFF, MASTER_SHUTDOWN \n\ 00132 int8 master_state # The master state machine's state in the powerboard\n\ 00133 \n\ 00134 # Circuit States:\n\ 00135 # STATE_NOPOWER, STATE_STANDBY, STATE_PUMPING, STATE_ON, STATE_DISABLED\n\ 00136 int8[3] circuit_state # One of the above states\n\ 00137 float64[3] circuit_voltage # Output voltage of each circuit\n\ 00138 \n\ 00139 # True if robot should be enabled\n\ 00140 bool run_stop #Note - if the wireless run-stop is hit, this will be unobservable\n\ 00141 bool wireless_stop \n\ 00142 \n\ 00143 ================================================================================\n\ 00144 MSG: std_msgs/Header\n\ 00145 # Standard metadata for higher-level stamped data types.\n\ 00146 # This is generally used to communicate timestamped data \n\ 00147 # in a particular coordinate frame.\n\ 00148 # \n\ 00149 # sequence ID: consecutively increasing ID \n\ 00150 uint32 seq\n\ 00151 #Two-integer timestamp that is expressed as:\n\ 00152 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00153 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00154 # time-handling sugar is provided by the client library\n\ 00155 time stamp\n\ 00156 #Frame this data is associated with\n\ 00157 # 0: no frame\n\ 00158 # 1: global frame\n\ 00159 string frame_id\n\ 00160 \n\ 00161 ================================================================================\n\ 00162 MSG: pr2_msgs/PowerState\n\ 00163 # This message communicates the state of the PR2's power system.\n\ 00164 Header header\n\ 00165 float64 power_consumption ## Watts\n\ 00166 duration time_remaining ## estimated time to empty or full\n\ 00167 string prediction_method ## how time_remaining is being calculated\n\ 00168 int8 relative_capacity ## percent of capacity\n\ 00169 int8 AC_present ## number of packs detecting AC power, > 0 means plugged in\n\ 00170 \n\ 00171 ================================================================================\n\ 00172 MSG: pr2_msgs/AccessPoint\n\ 00173 # This message communicates the state of the PR2's wifi access point.\n\ 00174 Header header\n\ 00175 string essid\n\ 00176 string macaddr\n\ 00177 int32 signal\n\ 00178 int32 noise\n\ 00179 int32 snr\n\ 00180 int32 channel\n\ 00181 string rate\n\ 00182 string tx_power\n\ 00183 int32 quality\n\ 00184 \n\ 00185 "; } 00186 public: 00187 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00188 00189 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00190 00191 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00192 { 00193 ros::serialization::OStream stream(write_ptr, 1000000000); 00194 ros::serialization::serialize(stream, motors_halted); 00195 ros::serialization::serialize(stream, motors_halted_valid); 00196 ros::serialization::serialize(stream, power_board_state); 00197 ros::serialization::serialize(stream, power_board_state_valid); 00198 ros::serialization::serialize(stream, power_state); 00199 ros::serialization::serialize(stream, power_state_valid); 00200 ros::serialization::serialize(stream, access_point); 00201 ros::serialization::serialize(stream, access_point_valid); 00202 return stream.getData(); 00203 } 00204 00205 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00206 { 00207 ros::serialization::IStream stream(read_ptr, 1000000000); 00208 ros::serialization::deserialize(stream, motors_halted); 00209 ros::serialization::deserialize(stream, motors_halted_valid); 00210 ros::serialization::deserialize(stream, power_board_state); 00211 ros::serialization::deserialize(stream, power_board_state_valid); 00212 ros::serialization::deserialize(stream, power_state); 00213 ros::serialization::deserialize(stream, power_state_valid); 00214 ros::serialization::deserialize(stream, access_point); 00215 ros::serialization::deserialize(stream, access_point_valid); 00216 return stream.getData(); 00217 } 00218 00219 ROS_DEPRECATED virtual uint32_t serializationLength() const 00220 { 00221 uint32_t size = 0; 00222 size += ros::serialization::serializationLength(motors_halted); 00223 size += ros::serialization::serializationLength(motors_halted_valid); 00224 size += ros::serialization::serializationLength(power_board_state); 00225 size += ros::serialization::serializationLength(power_board_state_valid); 00226 size += ros::serialization::serializationLength(power_state); 00227 size += ros::serialization::serializationLength(power_state_valid); 00228 size += ros::serialization::serializationLength(access_point); 00229 size += ros::serialization::serializationLength(access_point_valid); 00230 return size; 00231 } 00232 00233 typedef boost::shared_ptr< ::pr2_msgs::DashboardState_<ContainerAllocator> > Ptr; 00234 typedef boost::shared_ptr< ::pr2_msgs::DashboardState_<ContainerAllocator> const> ConstPtr; 00235 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00236 }; // struct DashboardState 00237 typedef ::pr2_msgs::DashboardState_<std::allocator<void> > DashboardState; 00238 00239 typedef boost::shared_ptr< ::pr2_msgs::DashboardState> DashboardStatePtr; 00240 typedef boost::shared_ptr< ::pr2_msgs::DashboardState const> DashboardStateConstPtr; 00241 00242 00243 template<typename ContainerAllocator> 00244 std::ostream& operator<<(std::ostream& s, const ::pr2_msgs::DashboardState_<ContainerAllocator> & v) 00245 { 00246 ros::message_operations::Printer< ::pr2_msgs::DashboardState_<ContainerAllocator> >::stream(s, "", v); 00247 return s;} 00248 00249 } // namespace pr2_msgs 00250 00251 namespace ros 00252 { 00253 namespace message_traits 00254 { 00255 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::DashboardState_<ContainerAllocator> > : public TrueType {}; 00256 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::DashboardState_<ContainerAllocator> const> : public TrueType {}; 00257 template<class ContainerAllocator> 00258 struct MD5Sum< ::pr2_msgs::DashboardState_<ContainerAllocator> > { 00259 static const char* value() 00260 { 00261 return "db0cd0d535d75e0f6257b20c403e87f5"; 00262 } 00263 00264 static const char* value(const ::pr2_msgs::DashboardState_<ContainerAllocator> &) { return value(); } 00265 static const uint64_t static_value1 = 0xdb0cd0d535d75e0fULL; 00266 static const uint64_t static_value2 = 0x6257b20c403e87f5ULL; 00267 }; 00268 00269 template<class ContainerAllocator> 00270 struct DataType< ::pr2_msgs::DashboardState_<ContainerAllocator> > { 00271 static const char* value() 00272 { 00273 return "pr2_msgs/DashboardState"; 00274 } 00275 00276 static const char* value(const ::pr2_msgs::DashboardState_<ContainerAllocator> &) { return value(); } 00277 }; 00278 00279 template<class ContainerAllocator> 00280 struct Definition< ::pr2_msgs::DashboardState_<ContainerAllocator> > { 00281 static const char* value() 00282 { 00283 return "# This message communicates state information that might be used by a\n\ 00284 # dashboard application.\n\ 00285 std_msgs/Bool motors_halted\n\ 00286 bool motors_halted_valid\n\ 00287 \n\ 00288 pr2_msgs/PowerBoardState power_board_state\n\ 00289 bool power_board_state_valid\n\ 00290 \n\ 00291 pr2_msgs/PowerState power_state\n\ 00292 bool power_state_valid\n\ 00293 \n\ 00294 pr2_msgs/AccessPoint access_point\n\ 00295 bool access_point_valid\n\ 00296 \n\ 00297 ================================================================================\n\ 00298 MSG: std_msgs/Bool\n\ 00299 bool data\n\ 00300 ================================================================================\n\ 00301 MSG: pr2_msgs/PowerBoardState\n\ 00302 # This message communicates the state of the PR2's power board.\n\ 00303 int8 STATE_NOPOWER=0\n\ 00304 int8 STATE_STANDBY=1\n\ 00305 int8 STATE_PUMPING=2\n\ 00306 int8 STATE_ON=3\n\ 00307 int8 STATE_ENABLED=3 # Preferred over STATE_ON, keeping STATE_ON for backcompat\n\ 00308 int8 STATE_DISABLED=4\n\ 00309 \n\ 00310 int8 MASTER_NOPOWER=0\n\ 00311 int8 MASTER_STANDBY=1\n\ 00312 int8 MASTER_ON=2\n\ 00313 int8 MASTER_OFF=3\n\ 00314 int8 MASTER_SHUTDOWN=4\n\ 00315 \n\ 00316 Header header\n\ 00317 string name # Name with serial number\n\ 00318 uint32 serial_num # Serial number for this board's message\n\ 00319 float64 input_voltage # Input voltage to power board\n\ 00320 \n\ 00321 # Master States:\n\ 00322 # MASTER_NOPOWER, MASTER_STANDBY, MASTER_ON, MASTER_OFF, MASTER_SHUTDOWN \n\ 00323 int8 master_state # The master state machine's state in the powerboard\n\ 00324 \n\ 00325 # Circuit States:\n\ 00326 # STATE_NOPOWER, STATE_STANDBY, STATE_PUMPING, STATE_ON, STATE_DISABLED\n\ 00327 int8[3] circuit_state # One of the above states\n\ 00328 float64[3] circuit_voltage # Output voltage of each circuit\n\ 00329 \n\ 00330 # True if robot should be enabled\n\ 00331 bool run_stop #Note - if the wireless run-stop is hit, this will be unobservable\n\ 00332 bool wireless_stop \n\ 00333 \n\ 00334 ================================================================================\n\ 00335 MSG: std_msgs/Header\n\ 00336 # Standard metadata for higher-level stamped data types.\n\ 00337 # This is generally used to communicate timestamped data \n\ 00338 # in a particular coordinate frame.\n\ 00339 # \n\ 00340 # sequence ID: consecutively increasing ID \n\ 00341 uint32 seq\n\ 00342 #Two-integer timestamp that is expressed as:\n\ 00343 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00344 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00345 # time-handling sugar is provided by the client library\n\ 00346 time stamp\n\ 00347 #Frame this data is associated with\n\ 00348 # 0: no frame\n\ 00349 # 1: global frame\n\ 00350 string frame_id\n\ 00351 \n\ 00352 ================================================================================\n\ 00353 MSG: pr2_msgs/PowerState\n\ 00354 # This message communicates the state of the PR2's power system.\n\ 00355 Header header\n\ 00356 float64 power_consumption ## Watts\n\ 00357 duration time_remaining ## estimated time to empty or full\n\ 00358 string prediction_method ## how time_remaining is being calculated\n\ 00359 int8 relative_capacity ## percent of capacity\n\ 00360 int8 AC_present ## number of packs detecting AC power, > 0 means plugged in\n\ 00361 \n\ 00362 ================================================================================\n\ 00363 MSG: pr2_msgs/AccessPoint\n\ 00364 # This message communicates the state of the PR2's wifi access point.\n\ 00365 Header header\n\ 00366 string essid\n\ 00367 string macaddr\n\ 00368 int32 signal\n\ 00369 int32 noise\n\ 00370 int32 snr\n\ 00371 int32 channel\n\ 00372 string rate\n\ 00373 string tx_power\n\ 00374 int32 quality\n\ 00375 \n\ 00376 "; 00377 } 00378 00379 static const char* value(const ::pr2_msgs::DashboardState_<ContainerAllocator> &) { return value(); } 00380 }; 00381 00382 } // namespace message_traits 00383 } // namespace ros 00384 00385 namespace ros 00386 { 00387 namespace serialization 00388 { 00389 00390 template<class ContainerAllocator> struct Serializer< ::pr2_msgs::DashboardState_<ContainerAllocator> > 00391 { 00392 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00393 { 00394 stream.next(m.motors_halted); 00395 stream.next(m.motors_halted_valid); 00396 stream.next(m.power_board_state); 00397 stream.next(m.power_board_state_valid); 00398 stream.next(m.power_state); 00399 stream.next(m.power_state_valid); 00400 stream.next(m.access_point); 00401 stream.next(m.access_point_valid); 00402 } 00403 00404 ROS_DECLARE_ALLINONE_SERIALIZER; 00405 }; // struct DashboardState_ 00406 } // namespace serialization 00407 } // namespace ros 00408 00409 namespace ros 00410 { 00411 namespace message_operations 00412 { 00413 00414 template<class ContainerAllocator> 00415 struct Printer< ::pr2_msgs::DashboardState_<ContainerAllocator> > 00416 { 00417 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_msgs::DashboardState_<ContainerAllocator> & v) 00418 { 00419 s << indent << "motors_halted: "; 00420 s << std::endl; 00421 Printer< ::std_msgs::Bool_<ContainerAllocator> >::stream(s, indent + " ", v.motors_halted); 00422 s << indent << "motors_halted_valid: "; 00423 Printer<uint8_t>::stream(s, indent + " ", v.motors_halted_valid); 00424 s << indent << "power_board_state: "; 00425 s << std::endl; 00426 Printer< ::pr2_msgs::PowerBoardState_<ContainerAllocator> >::stream(s, indent + " ", v.power_board_state); 00427 s << indent << "power_board_state_valid: "; 00428 Printer<uint8_t>::stream(s, indent + " ", v.power_board_state_valid); 00429 s << indent << "power_state: "; 00430 s << std::endl; 00431 Printer< ::pr2_msgs::PowerState_<ContainerAllocator> >::stream(s, indent + " ", v.power_state); 00432 s << indent << "power_state_valid: "; 00433 Printer<uint8_t>::stream(s, indent + " ", v.power_state_valid); 00434 s << indent << "access_point: "; 00435 s << std::endl; 00436 Printer< ::pr2_msgs::AccessPoint_<ContainerAllocator> >::stream(s, indent + " ", v.access_point); 00437 s << indent << "access_point_valid: "; 00438 Printer<uint8_t>::stream(s, indent + " ", v.access_point_valid); 00439 } 00440 }; 00441 00442 00443 } // namespace message_operations 00444 } // namespace ros 00445 00446 #endif // PR2_MSGS_MESSAGE_DASHBOARDSTATE_H 00447