00001
00002 #ifndef NASA_R2_COMMON_MSGS_MESSAGE_SYSTEMSTATUS_H
00003 #define NASA_R2_COMMON_MSGS_MESSAGE_SYSTEMSTATUS_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 "nasa_r2_common_msgs/SystemCore.h"
00019
00020 namespace nasa_r2_common_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct SystemStatus_ {
00024 typedef SystemStatus_<ContainerAllocator> Type;
00025
00026 SystemStatus_()
00027 : header()
00028 , name()
00029 , coreStats()
00030 , coreTemps()
00031 , oneMinuteLoad(0.0)
00032 , fiveMinuteLoad(0.0)
00033 , fifteenMinuteLoad(0.0)
00034 , uptime()
00035 , totalMemory(0)
00036 , usedMemory(0)
00037 , freeMemory(0)
00038 {
00039 }
00040
00041 SystemStatus_(const ContainerAllocator& _alloc)
00042 : header(_alloc)
00043 , name(_alloc)
00044 , coreStats(_alloc)
00045 , coreTemps(_alloc)
00046 , oneMinuteLoad(0.0)
00047 , fiveMinuteLoad(0.0)
00048 , fifteenMinuteLoad(0.0)
00049 , uptime()
00050 , totalMemory(0)
00051 , usedMemory(0)
00052 , freeMemory(0)
00053 {
00054 }
00055
00056 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00057 ::std_msgs::Header_<ContainerAllocator> header;
00058
00059 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _name_type;
00060 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > name;
00061
00062 typedef std::vector< ::nasa_r2_common_msgs::SystemCore_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::nasa_r2_common_msgs::SystemCore_<ContainerAllocator> >::other > _coreStats_type;
00063 std::vector< ::nasa_r2_common_msgs::SystemCore_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::nasa_r2_common_msgs::SystemCore_<ContainerAllocator> >::other > coreStats;
00064
00065 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _coreTemps_type;
00066 std::vector<double, typename ContainerAllocator::template rebind<double>::other > coreTemps;
00067
00068 typedef double _oneMinuteLoad_type;
00069 double oneMinuteLoad;
00070
00071 typedef double _fiveMinuteLoad_type;
00072 double fiveMinuteLoad;
00073
00074 typedef double _fifteenMinuteLoad_type;
00075 double fifteenMinuteLoad;
00076
00077 typedef ros::Duration _uptime_type;
00078 ros::Duration uptime;
00079
00080 typedef uint32_t _totalMemory_type;
00081 uint32_t totalMemory;
00082
00083 typedef uint32_t _usedMemory_type;
00084 uint32_t usedMemory;
00085
00086 typedef uint32_t _freeMemory_type;
00087 uint32_t freeMemory;
00088
00089
00090 typedef boost::shared_ptr< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> > Ptr;
00091 typedef boost::shared_ptr< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> const> ConstPtr;
00092 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00093 };
00094 typedef ::nasa_r2_common_msgs::SystemStatus_<std::allocator<void> > SystemStatus;
00095
00096 typedef boost::shared_ptr< ::nasa_r2_common_msgs::SystemStatus> SystemStatusPtr;
00097 typedef boost::shared_ptr< ::nasa_r2_common_msgs::SystemStatus const> SystemStatusConstPtr;
00098
00099
00100 template<typename ContainerAllocator>
00101 std::ostream& operator<<(std::ostream& s, const ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> & v)
00102 {
00103 ros::message_operations::Printer< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> >::stream(s, "", v);
00104 return s;}
00105
00106 }
00107
00108 namespace ros
00109 {
00110 namespace message_traits
00111 {
00112 template<class ContainerAllocator> struct IsMessage< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> > : public TrueType {};
00113 template<class ContainerAllocator> struct IsMessage< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> const> : public TrueType {};
00114 template<class ContainerAllocator>
00115 struct MD5Sum< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> > {
00116 static const char* value()
00117 {
00118 return "4896af13a56b5d046a8dac4145b244f0";
00119 }
00120
00121 static const char* value(const ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> &) { return value(); }
00122 static const uint64_t static_value1 = 0x4896af13a56b5d04ULL;
00123 static const uint64_t static_value2 = 0x6a8dac4145b244f0ULL;
00124 };
00125
00126 template<class ContainerAllocator>
00127 struct DataType< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> > {
00128 static const char* value()
00129 {
00130 return "nasa_r2_common_msgs/SystemStatus";
00131 }
00132
00133 static const char* value(const ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> &) { return value(); }
00134 };
00135
00136 template<class ContainerAllocator>
00137 struct Definition< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> > {
00138 static const char* value()
00139 {
00140 return "Header header\n\
00141 string name\n\
00142 SystemCore[] coreStats\n\
00143 float64[] coreTemps\n\
00144 float64 oneMinuteLoad\n\
00145 float64 fiveMinuteLoad\n\
00146 float64 fifteenMinuteLoad\n\
00147 duration uptime\n\
00148 uint32 totalMemory\n\
00149 uint32 usedMemory\n\
00150 uint32 freeMemory\n\
00151 ================================================================================\n\
00152 MSG: std_msgs/Header\n\
00153 # Standard metadata for higher-level stamped data types.\n\
00154 # This is generally used to communicate timestamped data \n\
00155 # in a particular coordinate frame.\n\
00156 # \n\
00157 # sequence ID: consecutively increasing ID \n\
00158 uint32 seq\n\
00159 #Two-integer timestamp that is expressed as:\n\
00160 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00161 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00162 # time-handling sugar is provided by the client library\n\
00163 time stamp\n\
00164 #Frame this data is associated with\n\
00165 # 0: no frame\n\
00166 # 1: global frame\n\
00167 string frame_id\n\
00168 \n\
00169 ================================================================================\n\
00170 MSG: nasa_r2_common_msgs/SystemCore\n\
00171 string id\n\
00172 float64 speed\n\
00173 float64 load\n\
00174 bool failure\n\
00175 ";
00176 }
00177
00178 static const char* value(const ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> &) { return value(); }
00179 };
00180
00181 template<class ContainerAllocator> struct HasHeader< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> > : public TrueType {};
00182 template<class ContainerAllocator> struct HasHeader< const ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> > : public TrueType {};
00183 }
00184 }
00185
00186 namespace ros
00187 {
00188 namespace serialization
00189 {
00190
00191 template<class ContainerAllocator> struct Serializer< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> >
00192 {
00193 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00194 {
00195 stream.next(m.header);
00196 stream.next(m.name);
00197 stream.next(m.coreStats);
00198 stream.next(m.coreTemps);
00199 stream.next(m.oneMinuteLoad);
00200 stream.next(m.fiveMinuteLoad);
00201 stream.next(m.fifteenMinuteLoad);
00202 stream.next(m.uptime);
00203 stream.next(m.totalMemory);
00204 stream.next(m.usedMemory);
00205 stream.next(m.freeMemory);
00206 }
00207
00208 ROS_DECLARE_ALLINONE_SERIALIZER;
00209 };
00210 }
00211 }
00212
00213 namespace ros
00214 {
00215 namespace message_operations
00216 {
00217
00218 template<class ContainerAllocator>
00219 struct Printer< ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> >
00220 {
00221 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::nasa_r2_common_msgs::SystemStatus_<ContainerAllocator> & v)
00222 {
00223 s << indent << "header: ";
00224 s << std::endl;
00225 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00226 s << indent << "name: ";
00227 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.name);
00228 s << indent << "coreStats[]" << std::endl;
00229 for (size_t i = 0; i < v.coreStats.size(); ++i)
00230 {
00231 s << indent << " coreStats[" << i << "]: ";
00232 s << std::endl;
00233 s << indent;
00234 Printer< ::nasa_r2_common_msgs::SystemCore_<ContainerAllocator> >::stream(s, indent + " ", v.coreStats[i]);
00235 }
00236 s << indent << "coreTemps[]" << std::endl;
00237 for (size_t i = 0; i < v.coreTemps.size(); ++i)
00238 {
00239 s << indent << " coreTemps[" << i << "]: ";
00240 Printer<double>::stream(s, indent + " ", v.coreTemps[i]);
00241 }
00242 s << indent << "oneMinuteLoad: ";
00243 Printer<double>::stream(s, indent + " ", v.oneMinuteLoad);
00244 s << indent << "fiveMinuteLoad: ";
00245 Printer<double>::stream(s, indent + " ", v.fiveMinuteLoad);
00246 s << indent << "fifteenMinuteLoad: ";
00247 Printer<double>::stream(s, indent + " ", v.fifteenMinuteLoad);
00248 s << indent << "uptime: ";
00249 Printer<ros::Duration>::stream(s, indent + " ", v.uptime);
00250 s << indent << "totalMemory: ";
00251 Printer<uint32_t>::stream(s, indent + " ", v.totalMemory);
00252 s << indent << "usedMemory: ";
00253 Printer<uint32_t>::stream(s, indent + " ", v.usedMemory);
00254 s << indent << "freeMemory: ";
00255 Printer<uint32_t>::stream(s, indent + " ", v.freeMemory);
00256 }
00257 };
00258
00259
00260 }
00261 }
00262
00263 #endif // NASA_R2_COMMON_MSGS_MESSAGE_SYSTEMSTATUS_H
00264