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