Go to the documentation of this file.00001
00002 #ifndef NASA_R2_COMMON_MSGS_MESSAGE_JOINTSTATUSARRAY_H
00003 #define NASA_R2_COMMON_MSGS_MESSAGE_JOINTSTATUSARRAY_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/JointStatus.h"
00019
00020 namespace nasa_r2_common_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct JointStatusArray_ {
00024 typedef JointStatusArray_<ContainerAllocator> Type;
00025
00026 JointStatusArray_()
00027 : header()
00028 , status()
00029 {
00030 }
00031
00032 JointStatusArray_(const ContainerAllocator& _alloc)
00033 : header(_alloc)
00034 , status(_alloc)
00035 {
00036 }
00037
00038 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00039 ::std_msgs::Header_<ContainerAllocator> header;
00040
00041 typedef std::vector< ::nasa_r2_common_msgs::JointStatus_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::nasa_r2_common_msgs::JointStatus_<ContainerAllocator> >::other > _status_type;
00042 std::vector< ::nasa_r2_common_msgs::JointStatus_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::nasa_r2_common_msgs::JointStatus_<ContainerAllocator> >::other > status;
00043
00044
00045 typedef boost::shared_ptr< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> > Ptr;
00046 typedef boost::shared_ptr< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> const> ConstPtr;
00047 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00048 };
00049 typedef ::nasa_r2_common_msgs::JointStatusArray_<std::allocator<void> > JointStatusArray;
00050
00051 typedef boost::shared_ptr< ::nasa_r2_common_msgs::JointStatusArray> JointStatusArrayPtr;
00052 typedef boost::shared_ptr< ::nasa_r2_common_msgs::JointStatusArray const> JointStatusArrayConstPtr;
00053
00054
00055 template<typename ContainerAllocator>
00056 std::ostream& operator<<(std::ostream& s, const ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> & v)
00057 {
00058 ros::message_operations::Printer< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> >::stream(s, "", v);
00059 return s;}
00060
00061 }
00062
00063 namespace ros
00064 {
00065 namespace message_traits
00066 {
00067 template<class ContainerAllocator> struct IsMessage< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> > : public TrueType {};
00068 template<class ContainerAllocator> struct IsMessage< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> const> : public TrueType {};
00069 template<class ContainerAllocator>
00070 struct MD5Sum< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> > {
00071 static const char* value()
00072 {
00073 return "db132c4fff9528f41c0236d435100eda";
00074 }
00075
00076 static const char* value(const ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> &) { return value(); }
00077 static const uint64_t static_value1 = 0xdb132c4fff9528f4ULL;
00078 static const uint64_t static_value2 = 0x1c0236d435100edaULL;
00079 };
00080
00081 template<class ContainerAllocator>
00082 struct DataType< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> > {
00083 static const char* value()
00084 {
00085 return "nasa_r2_common_msgs/JointStatusArray";
00086 }
00087
00088 static const char* value(const ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> &) { return value(); }
00089 };
00090
00091 template<class ContainerAllocator>
00092 struct Definition< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> > {
00093 static const char* value()
00094 {
00095 return "Header header\n\
00096 JointStatus[] status\n\
00097 \n\
00098 ================================================================================\n\
00099 MSG: std_msgs/Header\n\
00100 # Standard metadata for higher-level stamped data types.\n\
00101 # This is generally used to communicate timestamped data \n\
00102 # in a particular coordinate frame.\n\
00103 # \n\
00104 # sequence ID: consecutively increasing ID \n\
00105 uint32 seq\n\
00106 #Two-integer timestamp that is expressed as:\n\
00107 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00108 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00109 # time-handling sugar is provided by the client library\n\
00110 time stamp\n\
00111 #Frame this data is associated with\n\
00112 # 0: no frame\n\
00113 # 1: global frame\n\
00114 string frame_id\n\
00115 \n\
00116 ================================================================================\n\
00117 MSG: nasa_r2_common_msgs/JointStatus\n\
00118 string publisher\n\
00119 string joint\n\
00120 uint32 registerValue\n\
00121 bool coeffsLoaded\n\
00122 bool bridgeEnabled\n\
00123 bool motorEnabled\n\
00124 bool brakeReleased\n\
00125 bool motorPowerDetected\n\
00126 bool embeddedMotCom\n\
00127 bool jointFaulted\n\
00128 \n\
00129 ";
00130 }
00131
00132 static const char* value(const ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> &) { return value(); }
00133 };
00134
00135 template<class ContainerAllocator> struct HasHeader< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> > : public TrueType {};
00136 template<class ContainerAllocator> struct HasHeader< const ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> > : public TrueType {};
00137 }
00138 }
00139
00140 namespace ros
00141 {
00142 namespace serialization
00143 {
00144
00145 template<class ContainerAllocator> struct Serializer< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> >
00146 {
00147 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00148 {
00149 stream.next(m.header);
00150 stream.next(m.status);
00151 }
00152
00153 ROS_DECLARE_ALLINONE_SERIALIZER;
00154 };
00155 }
00156 }
00157
00158 namespace ros
00159 {
00160 namespace message_operations
00161 {
00162
00163 template<class ContainerAllocator>
00164 struct Printer< ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> >
00165 {
00166 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::nasa_r2_common_msgs::JointStatusArray_<ContainerAllocator> & v)
00167 {
00168 s << indent << "header: ";
00169 s << std::endl;
00170 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00171 s << indent << "status[]" << std::endl;
00172 for (size_t i = 0; i < v.status.size(); ++i)
00173 {
00174 s << indent << " status[" << i << "]: ";
00175 s << std::endl;
00176 s << indent;
00177 Printer< ::nasa_r2_common_msgs::JointStatus_<ContainerAllocator> >::stream(s, indent + " ", v.status[i]);
00178 }
00179 }
00180 };
00181
00182
00183 }
00184 }
00185
00186 #endif // NASA_R2_COMMON_MSGS_MESSAGE_JOINTSTATUSARRAY_H
00187