00001
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 typedef boost::shared_ptr< ::pr2_msgs::DashboardState_<ContainerAllocator> > Ptr;
00078 typedef boost::shared_ptr< ::pr2_msgs::DashboardState_<ContainerAllocator> const> ConstPtr;
00079 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00080 };
00081 typedef ::pr2_msgs::DashboardState_<std::allocator<void> > DashboardState;
00082
00083 typedef boost::shared_ptr< ::pr2_msgs::DashboardState> DashboardStatePtr;
00084 typedef boost::shared_ptr< ::pr2_msgs::DashboardState const> DashboardStateConstPtr;
00085
00086
00087 template<typename ContainerAllocator>
00088 std::ostream& operator<<(std::ostream& s, const ::pr2_msgs::DashboardState_<ContainerAllocator> & v)
00089 {
00090 ros::message_operations::Printer< ::pr2_msgs::DashboardState_<ContainerAllocator> >::stream(s, "", v);
00091 return s;}
00092
00093 }
00094
00095 namespace ros
00096 {
00097 namespace message_traits
00098 {
00099 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::DashboardState_<ContainerAllocator> > : public TrueType {};
00100 template<class ContainerAllocator> struct IsMessage< ::pr2_msgs::DashboardState_<ContainerAllocator> const> : public TrueType {};
00101 template<class ContainerAllocator>
00102 struct MD5Sum< ::pr2_msgs::DashboardState_<ContainerAllocator> > {
00103 static const char* value()
00104 {
00105 return "db0cd0d535d75e0f6257b20c403e87f5";
00106 }
00107
00108 static const char* value(const ::pr2_msgs::DashboardState_<ContainerAllocator> &) { return value(); }
00109 static const uint64_t static_value1 = 0xdb0cd0d535d75e0fULL;
00110 static const uint64_t static_value2 = 0x6257b20c403e87f5ULL;
00111 };
00112
00113 template<class ContainerAllocator>
00114 struct DataType< ::pr2_msgs::DashboardState_<ContainerAllocator> > {
00115 static const char* value()
00116 {
00117 return "pr2_msgs/DashboardState";
00118 }
00119
00120 static const char* value(const ::pr2_msgs::DashboardState_<ContainerAllocator> &) { return value(); }
00121 };
00122
00123 template<class ContainerAllocator>
00124 struct Definition< ::pr2_msgs::DashboardState_<ContainerAllocator> > {
00125 static const char* value()
00126 {
00127 return "# This message communicates state information that might be used by a\n\
00128 # dashboard application.\n\
00129 std_msgs/Bool motors_halted\n\
00130 bool motors_halted_valid\n\
00131 \n\
00132 pr2_msgs/PowerBoardState power_board_state\n\
00133 bool power_board_state_valid\n\
00134 \n\
00135 pr2_msgs/PowerState power_state\n\
00136 bool power_state_valid\n\
00137 \n\
00138 pr2_msgs/AccessPoint access_point\n\
00139 bool access_point_valid\n\
00140 \n\
00141 ================================================================================\n\
00142 MSG: std_msgs/Bool\n\
00143 bool data\n\
00144 ================================================================================\n\
00145 MSG: pr2_msgs/PowerBoardState\n\
00146 # This message communicates the state of the PR2's power board.\n\
00147 int8 STATE_NOPOWER=0\n\
00148 int8 STATE_STANDBY=1\n\
00149 int8 STATE_PUMPING=2\n\
00150 int8 STATE_ON=3\n\
00151 int8 STATE_ENABLED=3 # Preferred over STATE_ON, keeping STATE_ON for backcompat\n\
00152 int8 STATE_DISABLED=4\n\
00153 \n\
00154 int8 MASTER_NOPOWER=0\n\
00155 int8 MASTER_STANDBY=1\n\
00156 int8 MASTER_ON=2\n\
00157 int8 MASTER_OFF=3\n\
00158 int8 MASTER_SHUTDOWN=4\n\
00159 \n\
00160 Header header\n\
00161 string name # Name with serial number\n\
00162 uint32 serial_num # Serial number for this board's message\n\
00163 float64 input_voltage # Input voltage to power board\n\
00164 \n\
00165 # Master States:\n\
00166 # MASTER_NOPOWER, MASTER_STANDBY, MASTER_ON, MASTER_OFF, MASTER_SHUTDOWN \n\
00167 int8 master_state # The master state machine's state in the powerboard\n\
00168 \n\
00169 # Circuit States:\n\
00170 # STATE_NOPOWER, STATE_STANDBY, STATE_PUMPING, STATE_ON, STATE_DISABLED\n\
00171 int8[3] circuit_state # One of the above states\n\
00172 float64[3] circuit_voltage # Output voltage of each circuit\n\
00173 \n\
00174 # True if robot should be enabled\n\
00175 bool run_stop #Note - if the wireless run-stop is hit, this will be unobservable\n\
00176 bool wireless_stop \n\
00177 \n\
00178 ================================================================================\n\
00179 MSG: std_msgs/Header\n\
00180 # Standard metadata for higher-level stamped data types.\n\
00181 # This is generally used to communicate timestamped data \n\
00182 # in a particular coordinate frame.\n\
00183 # \n\
00184 # sequence ID: consecutively increasing ID \n\
00185 uint32 seq\n\
00186 #Two-integer timestamp that is expressed as:\n\
00187 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00188 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00189 # time-handling sugar is provided by the client library\n\
00190 time stamp\n\
00191 #Frame this data is associated with\n\
00192 # 0: no frame\n\
00193 # 1: global frame\n\
00194 string frame_id\n\
00195 \n\
00196 ================================================================================\n\
00197 MSG: pr2_msgs/PowerState\n\
00198 # This message communicates the state of the PR2's power system.\n\
00199 Header header\n\
00200 float64 power_consumption ## Watts\n\
00201 duration time_remaining ## estimated time to empty or full\n\
00202 string prediction_method ## how time_remaining is being calculated\n\
00203 int8 relative_capacity ## percent of capacity\n\
00204 int8 AC_present ## number of packs detecting AC power, > 0 means plugged in\n\
00205 \n\
00206 ================================================================================\n\
00207 MSG: pr2_msgs/AccessPoint\n\
00208 # This message communicates the state of the PR2's wifi access point.\n\
00209 Header header\n\
00210 string essid\n\
00211 string macaddr\n\
00212 int32 signal\n\
00213 int32 noise\n\
00214 int32 snr\n\
00215 int32 channel\n\
00216 string rate\n\
00217 string tx_power\n\
00218 int32 quality\n\
00219 \n\
00220 ";
00221 }
00222
00223 static const char* value(const ::pr2_msgs::DashboardState_<ContainerAllocator> &) { return value(); }
00224 };
00225
00226 }
00227 }
00228
00229 namespace ros
00230 {
00231 namespace serialization
00232 {
00233
00234 template<class ContainerAllocator> struct Serializer< ::pr2_msgs::DashboardState_<ContainerAllocator> >
00235 {
00236 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00237 {
00238 stream.next(m.motors_halted);
00239 stream.next(m.motors_halted_valid);
00240 stream.next(m.power_board_state);
00241 stream.next(m.power_board_state_valid);
00242 stream.next(m.power_state);
00243 stream.next(m.power_state_valid);
00244 stream.next(m.access_point);
00245 stream.next(m.access_point_valid);
00246 }
00247
00248 ROS_DECLARE_ALLINONE_SERIALIZER;
00249 };
00250 }
00251 }
00252
00253 namespace ros
00254 {
00255 namespace message_operations
00256 {
00257
00258 template<class ContainerAllocator>
00259 struct Printer< ::pr2_msgs::DashboardState_<ContainerAllocator> >
00260 {
00261 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pr2_msgs::DashboardState_<ContainerAllocator> & v)
00262 {
00263 s << indent << "motors_halted: ";
00264 s << std::endl;
00265 Printer< ::std_msgs::Bool_<ContainerAllocator> >::stream(s, indent + " ", v.motors_halted);
00266 s << indent << "motors_halted_valid: ";
00267 Printer<uint8_t>::stream(s, indent + " ", v.motors_halted_valid);
00268 s << indent << "power_board_state: ";
00269 s << std::endl;
00270 Printer< ::pr2_msgs::PowerBoardState_<ContainerAllocator> >::stream(s, indent + " ", v.power_board_state);
00271 s << indent << "power_board_state_valid: ";
00272 Printer<uint8_t>::stream(s, indent + " ", v.power_board_state_valid);
00273 s << indent << "power_state: ";
00274 s << std::endl;
00275 Printer< ::pr2_msgs::PowerState_<ContainerAllocator> >::stream(s, indent + " ", v.power_state);
00276 s << indent << "power_state_valid: ";
00277 Printer<uint8_t>::stream(s, indent + " ", v.power_state_valid);
00278 s << indent << "access_point: ";
00279 s << std::endl;
00280 Printer< ::pr2_msgs::AccessPoint_<ContainerAllocator> >::stream(s, indent + " ", v.access_point);
00281 s << indent << "access_point_valid: ";
00282 Printer<uint8_t>::stream(s, indent + " ", v.access_point_valid);
00283 }
00284 };
00285
00286
00287 }
00288 }
00289
00290 #endif // PR2_MSGS_MESSAGE_DASHBOARDSTATE_H
00291