TestDataTypes.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-client_rosjava_jni/doc_stacks/2014-01-02_11-05-27.429326/client_rosjava_jni/test_rosjava_jni/msg/TestDataTypes.msg */
00002 #ifndef TEST_ROSJAVA_JNI_MESSAGE_TESTDATATYPES_H
00003 #define TEST_ROSJAVA_JNI_MESSAGE_TESTDATATYPES_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/Byte.h"
00018 #include "std_msgs/Byte.h"
00019 #include "std_msgs/ByteMultiArray.h"
00020 #include "std_msgs/ByteMultiArray.h"
00021 
00022 namespace test_rosjava_jni
00023 {
00024 template <class ContainerAllocator>
00025 struct TestDataTypes_ {
00026   typedef TestDataTypes_<ContainerAllocator> Type;
00027 
00028   TestDataTypes_()
00029   : byte_(0)
00030   , char_(0)
00031   , uint8_(0)
00032   , int8_(0)
00033   , uint16_(0)
00034   , int16_(0)
00035   , uint32_(0)
00036   , int32_(0)
00037   , uint64_(0)
00038   , int64_(0)
00039   , float32_(0.0)
00040   , float64_(0.0)
00041   , string_()
00042   , time_()
00043   , duration_()
00044   , byte_v()
00045   , byte_f()
00046   , float64_v()
00047   , float64_f()
00048   , string_v()
00049   , string_f()
00050   , time_v()
00051   , time_f()
00052   , Byte_()
00053   , Byte_v()
00054   , ByteMultiArray_()
00055   , ByteMultiArray_v()
00056   {
00057     byte_f.assign(0);
00058     float64_f.assign(0.0);
00059   }
00060 
00061   TestDataTypes_(const ContainerAllocator& _alloc)
00062   : byte_(0)
00063   , char_(0)
00064   , uint8_(0)
00065   , int8_(0)
00066   , uint16_(0)
00067   , int16_(0)
00068   , uint32_(0)
00069   , int32_(0)
00070   , uint64_(0)
00071   , int64_(0)
00072   , float32_(0.0)
00073   , float64_(0.0)
00074   , string_(_alloc)
00075   , time_()
00076   , duration_()
00077   , byte_v(_alloc)
00078   , byte_f()
00079   , float64_v(_alloc)
00080   , float64_f()
00081   , string_v(_alloc)
00082   , string_f()
00083   , time_v(_alloc)
00084   , time_f()
00085   , Byte_(_alloc)
00086   , Byte_v(_alloc)
00087   , ByteMultiArray_(_alloc)
00088   , ByteMultiArray_v(_alloc)
00089   {
00090     byte_f.assign(0);
00091     float64_f.assign(0.0);
00092     string_f.assign(std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > (_alloc));
00093   }
00094 
00095   typedef int8_t _byte__type;
00096   int8_t byte_;
00097 
00098   typedef uint8_t _char__type;
00099   uint8_t char_;
00100 
00101   typedef uint8_t _uint8__type;
00102   uint8_t uint8_;
00103 
00104   typedef int8_t _int8__type;
00105   int8_t int8_;
00106 
00107   typedef uint16_t _uint16__type;
00108   uint16_t uint16_;
00109 
00110   typedef int16_t _int16__type;
00111   int16_t int16_;
00112 
00113   typedef uint32_t _uint32__type;
00114   uint32_t uint32_;
00115 
00116   typedef int32_t _int32__type;
00117   int32_t int32_;
00118 
00119   typedef uint64_t _uint64__type;
00120   uint64_t uint64_;
00121 
00122   typedef int64_t _int64__type;
00123   int64_t int64_;
00124 
00125   typedef float _float32__type;
00126   float float32_;
00127 
00128   typedef double _float64__type;
00129   double float64_;
00130 
00131   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _string__type;
00132   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  string_;
00133 
00134   typedef ros::Time _time__type;
00135   ros::Time time_;
00136 
00137   typedef ros::Duration _duration__type;
00138   ros::Duration duration_;
00139 
00140   typedef std::vector<int8_t, typename ContainerAllocator::template rebind<int8_t>::other >  _byte_v_type;
00141   std::vector<int8_t, typename ContainerAllocator::template rebind<int8_t>::other >  byte_v;
00142 
00143   typedef boost::array<int8_t, 2>  _byte_f_type;
00144   boost::array<int8_t, 2>  byte_f;
00145 
00146   typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other >  _float64_v_type;
00147   std::vector<double, typename ContainerAllocator::template rebind<double>::other >  float64_v;
00148 
00149   typedef boost::array<double, 2>  _float64_f_type;
00150   boost::array<double, 2>  float64_f;
00151 
00152   typedef std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other >  _string_v_type;
00153   std::vector<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , typename ContainerAllocator::template rebind<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::other >  string_v;
00154 
00155   typedef boost::array<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , 2>  _string_f_type;
00156   boost::array<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > , 2>  string_f;
00157 
00158   typedef std::vector<ros::Time, typename ContainerAllocator::template rebind<ros::Time>::other >  _time_v_type;
00159   std::vector<ros::Time, typename ContainerAllocator::template rebind<ros::Time>::other >  time_v;
00160 
00161   typedef boost::array<ros::Time, 2>  _time_f_type;
00162   boost::array<ros::Time, 2>  time_f;
00163 
00164   typedef  ::std_msgs::Byte_<ContainerAllocator>  _Byte__type;
00165    ::std_msgs::Byte_<ContainerAllocator>  Byte_;
00166 
00167   typedef std::vector< ::std_msgs::Byte_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::Byte_<ContainerAllocator> >::other >  _Byte_v_type;
00168   std::vector< ::std_msgs::Byte_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::Byte_<ContainerAllocator> >::other >  Byte_v;
00169 
00170   typedef  ::std_msgs::ByteMultiArray_<ContainerAllocator>  _ByteMultiArray__type;
00171    ::std_msgs::ByteMultiArray_<ContainerAllocator>  ByteMultiArray_;
00172 
00173   typedef std::vector< ::std_msgs::ByteMultiArray_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ByteMultiArray_<ContainerAllocator> >::other >  _ByteMultiArray_v_type;
00174   std::vector< ::std_msgs::ByteMultiArray_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::std_msgs::ByteMultiArray_<ContainerAllocator> >::other >  ByteMultiArray_v;
00175 
00176 
00177   typedef boost::shared_ptr< ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> > Ptr;
00178   typedef boost::shared_ptr< ::test_rosjava_jni::TestDataTypes_<ContainerAllocator>  const> ConstPtr;
00179   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00180 }; // struct TestDataTypes
00181 typedef  ::test_rosjava_jni::TestDataTypes_<std::allocator<void> > TestDataTypes;
00182 
00183 typedef boost::shared_ptr< ::test_rosjava_jni::TestDataTypes> TestDataTypesPtr;
00184 typedef boost::shared_ptr< ::test_rosjava_jni::TestDataTypes const> TestDataTypesConstPtr;
00185 
00186 
00187 template<typename ContainerAllocator>
00188 std::ostream& operator<<(std::ostream& s, const  ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> & v)
00189 {
00190   ros::message_operations::Printer< ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> >::stream(s, "", v);
00191   return s;}
00192 
00193 } // namespace test_rosjava_jni
00194 
00195 namespace ros
00196 {
00197 namespace message_traits
00198 {
00199 template<class ContainerAllocator> struct IsMessage< ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> > : public TrueType {};
00200 template<class ContainerAllocator> struct IsMessage< ::test_rosjava_jni::TestDataTypes_<ContainerAllocator>  const> : public TrueType {};
00201 template<class ContainerAllocator>
00202 struct MD5Sum< ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> > {
00203   static const char* value() 
00204   {
00205     return "25bc379e8ef2913896f76e9ef8bedbdc";
00206   }
00207 
00208   static const char* value(const  ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> &) { return value(); } 
00209   static const uint64_t static_value1 = 0x25bc379e8ef29138ULL;
00210   static const uint64_t static_value2 = 0x96f76e9ef8bedbdcULL;
00211 };
00212 
00213 template<class ContainerAllocator>
00214 struct DataType< ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> > {
00215   static const char* value() 
00216   {
00217     return "test_rosjava_jni/TestDataTypes";
00218   }
00219 
00220   static const char* value(const  ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> &) { return value(); } 
00221 };
00222 
00223 template<class ContainerAllocator>
00224 struct Definition< ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> > {
00225   static const char* value() 
00226   {
00227     return "# Test all primitive types\n\
00228 byte     byte_\n\
00229 char     char_\n\
00230 uint8    uint8_\n\
00231 int8     int8_\n\
00232 uint16   uint16_\n\
00233 int16    int16_\n\
00234 uint32   uint32_\n\
00235 int32    int32_\n\
00236 uint64   uint64_\n\
00237 int64    int64_\n\
00238 float32  float32_\n\
00239 float64  float64_\n\
00240 string   string_\n\
00241 time     time_\n\
00242 duration duration_\n\
00243 \n\
00244 # Test a smattering of array types\n\
00245 byte[]     byte_v\n\
00246 byte[2]    byte_f\n\
00247 float64[]  float64_v\n\
00248 float64[2] float64_f\n\
00249 string[]   string_v\n\
00250 string[2]  string_f\n\
00251 time[]     time_v\n\
00252 time[2]    time_f\n\
00253 \n\
00254 # Test submsgs, including both fixed and var length\n\
00255 std_msgs/Byte    Byte_\n\
00256 std_msgs/Byte[]  Byte_v\n\
00257 \n\
00258 std_msgs/ByteMultiArray    ByteMultiArray_\n\
00259 std_msgs/ByteMultiArray[]  ByteMultiArray_v\n\
00260 \n\
00261 # Unfortunately, can't test these because roscpp message generation\n\
00262 # is broken.  Hopefully rosjava works correctly ...\n\
00263 # TODO: put these back in.\n\
00264 \n\
00265 # std_msgs/Byte[2] Byte_f\n\
00266 # std_msgs/ByteMultiArray[2] ByteMultiArray_f\n\
00267 \n\
00268 ================================================================================\n\
00269 MSG: std_msgs/Byte\n\
00270 byte data\n\
00271 \n\
00272 ================================================================================\n\
00273 MSG: std_msgs/ByteMultiArray\n\
00274 # Please look at the MultiArrayLayout message definition for\n\
00275 # documentation on all multiarrays.\n\
00276 \n\
00277 MultiArrayLayout  layout        # specification of data layout\n\
00278 byte[]            data          # array of data\n\
00279 \n\
00280 \n\
00281 ================================================================================\n\
00282 MSG: std_msgs/MultiArrayLayout\n\
00283 # The multiarray declares a generic multi-dimensional array of a\n\
00284 # particular data type.  Dimensions are ordered from outer most\n\
00285 # to inner most.\n\
00286 \n\
00287 MultiArrayDimension[] dim # Array of dimension properties\n\
00288 uint32 data_offset        # padding bytes at front of data\n\
00289 \n\
00290 # Accessors should ALWAYS be written in terms of dimension stride\n\
00291 # and specified outer-most dimension first.\n\
00292 # \n\
00293 # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\
00294 #\n\
00295 # A standard, 3-channel 640x480 image with interleaved color channels\n\
00296 # would be specified as:\n\
00297 #\n\
00298 # dim[0].label  = \"height\"\n\
00299 # dim[0].size   = 480\n\
00300 # dim[0].stride = 3*640*480 = 921600  (note dim[0] stride is just size of image)\n\
00301 # dim[1].label  = \"width\"\n\
00302 # dim[1].size   = 640\n\
00303 # dim[1].stride = 3*640 = 1920\n\
00304 # dim[2].label  = \"channel\"\n\
00305 # dim[2].size   = 3\n\
00306 # dim[2].stride = 3\n\
00307 #\n\
00308 # multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\
00309 ================================================================================\n\
00310 MSG: std_msgs/MultiArrayDimension\n\
00311 string label   # label of given dimension\n\
00312 uint32 size    # size of given dimension (in type units)\n\
00313 uint32 stride  # stride of given dimension\n\
00314 ";
00315   }
00316 
00317   static const char* value(const  ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> &) { return value(); } 
00318 };
00319 
00320 } // namespace message_traits
00321 } // namespace ros
00322 
00323 namespace ros
00324 {
00325 namespace serialization
00326 {
00327 
00328 template<class ContainerAllocator> struct Serializer< ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> >
00329 {
00330   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00331   {
00332     stream.next(m.byte_);
00333     stream.next(m.char_);
00334     stream.next(m.uint8_);
00335     stream.next(m.int8_);
00336     stream.next(m.uint16_);
00337     stream.next(m.int16_);
00338     stream.next(m.uint32_);
00339     stream.next(m.int32_);
00340     stream.next(m.uint64_);
00341     stream.next(m.int64_);
00342     stream.next(m.float32_);
00343     stream.next(m.float64_);
00344     stream.next(m.string_);
00345     stream.next(m.time_);
00346     stream.next(m.duration_);
00347     stream.next(m.byte_v);
00348     stream.next(m.byte_f);
00349     stream.next(m.float64_v);
00350     stream.next(m.float64_f);
00351     stream.next(m.string_v);
00352     stream.next(m.string_f);
00353     stream.next(m.time_v);
00354     stream.next(m.time_f);
00355     stream.next(m.Byte_);
00356     stream.next(m.Byte_v);
00357     stream.next(m.ByteMultiArray_);
00358     stream.next(m.ByteMultiArray_v);
00359   }
00360 
00361   ROS_DECLARE_ALLINONE_SERIALIZER;
00362 }; // struct TestDataTypes_
00363 } // namespace serialization
00364 } // namespace ros
00365 
00366 namespace ros
00367 {
00368 namespace message_operations
00369 {
00370 
00371 template<class ContainerAllocator>
00372 struct Printer< ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> >
00373 {
00374   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::test_rosjava_jni::TestDataTypes_<ContainerAllocator> & v) 
00375   {
00376     s << indent << "byte_: ";
00377     Printer<int8_t>::stream(s, indent + "  ", v.byte_);
00378     s << indent << "char_: ";
00379     Printer<uint8_t>::stream(s, indent + "  ", v.char_);
00380     s << indent << "uint8_: ";
00381     Printer<uint8_t>::stream(s, indent + "  ", v.uint8_);
00382     s << indent << "int8_: ";
00383     Printer<int8_t>::stream(s, indent + "  ", v.int8_);
00384     s << indent << "uint16_: ";
00385     Printer<uint16_t>::stream(s, indent + "  ", v.uint16_);
00386     s << indent << "int16_: ";
00387     Printer<int16_t>::stream(s, indent + "  ", v.int16_);
00388     s << indent << "uint32_: ";
00389     Printer<uint32_t>::stream(s, indent + "  ", v.uint32_);
00390     s << indent << "int32_: ";
00391     Printer<int32_t>::stream(s, indent + "  ", v.int32_);
00392     s << indent << "uint64_: ";
00393     Printer<uint64_t>::stream(s, indent + "  ", v.uint64_);
00394     s << indent << "int64_: ";
00395     Printer<int64_t>::stream(s, indent + "  ", v.int64_);
00396     s << indent << "float32_: ";
00397     Printer<float>::stream(s, indent + "  ", v.float32_);
00398     s << indent << "float64_: ";
00399     Printer<double>::stream(s, indent + "  ", v.float64_);
00400     s << indent << "string_: ";
00401     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.string_);
00402     s << indent << "time_: ";
00403     Printer<ros::Time>::stream(s, indent + "  ", v.time_);
00404     s << indent << "duration_: ";
00405     Printer<ros::Duration>::stream(s, indent + "  ", v.duration_);
00406     s << indent << "byte_v[]" << std::endl;
00407     for (size_t i = 0; i < v.byte_v.size(); ++i)
00408     {
00409       s << indent << "  byte_v[" << i << "]: ";
00410       Printer<int8_t>::stream(s, indent + "  ", v.byte_v[i]);
00411     }
00412     s << indent << "byte_f[]" << std::endl;
00413     for (size_t i = 0; i < v.byte_f.size(); ++i)
00414     {
00415       s << indent << "  byte_f[" << i << "]: ";
00416       Printer<int8_t>::stream(s, indent + "  ", v.byte_f[i]);
00417     }
00418     s << indent << "float64_v[]" << std::endl;
00419     for (size_t i = 0; i < v.float64_v.size(); ++i)
00420     {
00421       s << indent << "  float64_v[" << i << "]: ";
00422       Printer<double>::stream(s, indent + "  ", v.float64_v[i]);
00423     }
00424     s << indent << "float64_f[]" << std::endl;
00425     for (size_t i = 0; i < v.float64_f.size(); ++i)
00426     {
00427       s << indent << "  float64_f[" << i << "]: ";
00428       Printer<double>::stream(s, indent + "  ", v.float64_f[i]);
00429     }
00430     s << indent << "string_v[]" << std::endl;
00431     for (size_t i = 0; i < v.string_v.size(); ++i)
00432     {
00433       s << indent << "  string_v[" << i << "]: ";
00434       Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.string_v[i]);
00435     }
00436     s << indent << "string_f[]" << std::endl;
00437     for (size_t i = 0; i < v.string_f.size(); ++i)
00438     {
00439       s << indent << "  string_f[" << i << "]: ";
00440       Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.string_f[i]);
00441     }
00442     s << indent << "time_v[]" << std::endl;
00443     for (size_t i = 0; i < v.time_v.size(); ++i)
00444     {
00445       s << indent << "  time_v[" << i << "]: ";
00446       Printer<ros::Time>::stream(s, indent + "  ", v.time_v[i]);
00447     }
00448     s << indent << "time_f[]" << std::endl;
00449     for (size_t i = 0; i < v.time_f.size(); ++i)
00450     {
00451       s << indent << "  time_f[" << i << "]: ";
00452       Printer<ros::Time>::stream(s, indent + "  ", v.time_f[i]);
00453     }
00454     s << indent << "Byte_: ";
00455 s << std::endl;
00456     Printer< ::std_msgs::Byte_<ContainerAllocator> >::stream(s, indent + "  ", v.Byte_);
00457     s << indent << "Byte_v[]" << std::endl;
00458     for (size_t i = 0; i < v.Byte_v.size(); ++i)
00459     {
00460       s << indent << "  Byte_v[" << i << "]: ";
00461       s << std::endl;
00462       s << indent;
00463       Printer< ::std_msgs::Byte_<ContainerAllocator> >::stream(s, indent + "    ", v.Byte_v[i]);
00464     }
00465     s << indent << "ByteMultiArray_: ";
00466 s << std::endl;
00467     Printer< ::std_msgs::ByteMultiArray_<ContainerAllocator> >::stream(s, indent + "  ", v.ByteMultiArray_);
00468     s << indent << "ByteMultiArray_v[]" << std::endl;
00469     for (size_t i = 0; i < v.ByteMultiArray_v.size(); ++i)
00470     {
00471       s << indent << "  ByteMultiArray_v[" << i << "]: ";
00472       s << std::endl;
00473       s << indent;
00474       Printer< ::std_msgs::ByteMultiArray_<ContainerAllocator> >::stream(s, indent + "    ", v.ByteMultiArray_v[i]);
00475     }
00476   }
00477 };
00478 
00479 
00480 } // namespace message_operations
00481 } // namespace ros
00482 
00483 #endif // TEST_ROSJAVA_JNI_MESSAGE_TESTDATATYPES_H
00484 


test_rosjava_jni
Author(s): Jason Wolfe (jawolfe@willowgarage.com)
autogenerated on Thu Jan 2 2014 11:07:07