00001 
00002 
00003 package ros.pkg.test_rosjava.msg;
00004 
00005 import java.nio.ByteBuffer;
00006 
00007 public class TestDataTypes extends ros.communication.Message {
00008 
00009   public short byte_;
00010   public char char_;
00011   public short uint8_;
00012   public byte int8_;
00013   public int uint16_;
00014   public short int16_;
00015   public long uint32_;
00016   public int int32_;
00017   public long uint64_;
00018   public long int64_;
00019   public float float32_;
00020   public double float64_;
00021   public java.lang.String string_ = new java.lang.String();
00022   public ros.communication.Time time_ = new ros.communication.Time();
00023   public ros.communication.Duration duration_ = new ros.communication.Duration();
00024   public short[] byte_v = new short[0];
00025   public short[] byte_f = new short[2];
00026   public double[] float64_v = new double[0];
00027   public double[] float64_f = new double[2];
00028   public java.util.ArrayList<java.lang.String> string_v = new java.util.ArrayList<java.lang.String>();
00029   public java.lang.String[] string_f = new java.lang.String[2];
00030   public java.util.ArrayList<ros.communication.Time> time_v = new java.util.ArrayList<ros.communication.Time>();
00031   public ros.communication.Time[] time_f = new ros.communication.Time[2];
00032   public ros.pkg.std_msgs.msg.Byte Byte_ = new ros.pkg.std_msgs.msg.Byte();
00033   public java.util.ArrayList<ros.pkg.std_msgs.msg.Byte> Byte_v = new java.util.ArrayList<ros.pkg.std_msgs.msg.Byte>();
00034   public ros.pkg.std_msgs.msg.ByteMultiArray ByteMultiArray_ = new ros.pkg.std_msgs.msg.ByteMultiArray();
00035   public java.util.ArrayList<ros.pkg.std_msgs.msg.ByteMultiArray> ByteMultiArray_v = new java.util.ArrayList<ros.pkg.std_msgs.msg.ByteMultiArray>();
00036 
00037   public TestDataTypes() {
00038 
00039     for(int __i=0; __i<2; __i++) {
00040       string_f[__i] = new java.lang.String();
00041     }
00042 
00043     for(int __i=0; __i<2; __i++) {
00044       time_f[__i] = new ros.communication.Time();
00045     }
00046   }
00047 
00048   public static java.lang.String __s_getDataType() { return "test_rosjava/TestDataTypes"; }
00049   public java.lang.String getDataType() { return __s_getDataType(); }
00050   public static java.lang.String __s_getMD5Sum() { return "25bc379e8ef2913896f76e9ef8bedbdc"; }
00051   public java.lang.String getMD5Sum() { return __s_getMD5Sum(); }
00052   public static java.lang.String __s_getMessageDefinition() { return "# Test all primitive types\n" +
00053 "byte     byte_\n" +
00054 "char     char_\n" +
00055 "uint8    uint8_\n" +
00056 "int8     int8_\n" +
00057 "uint16   uint16_\n" +
00058 "int16    int16_\n" +
00059 "uint32   uint32_\n" +
00060 "int32    int32_\n" +
00061 "uint64   uint64_\n" +
00062 "int64    int64_\n" +
00063 "float32  float32_\n" +
00064 "float64  float64_\n" +
00065 "string   string_\n" +
00066 "time     time_\n" +
00067 "duration duration_\n" +
00068 "\n" +
00069 "# Test a smattering of array types\n" +
00070 "byte[]     byte_v\n" +
00071 "byte[2]    byte_f\n" +
00072 "float64[]  float64_v\n" +
00073 "float64[2] float64_f\n" +
00074 "string[]   string_v\n" +
00075 "string[2]  string_f\n" +
00076 "time[]     time_v\n" +
00077 "time[2]    time_f\n" +
00078 "\n" +
00079 "# Test submsgs, including both fixed and var length\n" +
00080 "std_msgs/Byte    Byte_\n" +
00081 "std_msgs/Byte[]  Byte_v\n" +
00082 "\n" +
00083 "std_msgs/ByteMultiArray    ByteMultiArray_\n" +
00084 "std_msgs/ByteMultiArray[]  ByteMultiArray_v\n" +
00085 "\n" +
00086 "# Unfortunately, can't test these because roscpp message generation\n" +
00087 "# is broken.  Hopefully rosjava works correctly ...\n" +
00088 "# TODO: put these back in.\n" +
00089 "\n" +
00090 "# std_msgs/Byte[2] Byte_f\n" +
00091 "# std_msgs/ByteMultiArray[2] ByteMultiArray_f\n" +
00092 "\n" +
00093 "================================================================================\n" +
00094 "MSG: std_msgs/Byte\n" +
00095 "byte data\n" +
00096 "\n" +
00097 "================================================================================\n" +
00098 "MSG: std_msgs/ByteMultiArray\n" +
00099 "# Please look at the MultiArrayLayout message definition for\n" +
00100 "# documentation on all multiarrays.\n" +
00101 "\n" +
00102 "MultiArrayLayout  layout        # specification of data layout\n" +
00103 "byte[]            data          # array of data\n" +
00104 "\n" +
00105 "\n" +
00106 "================================================================================\n" +
00107 "MSG: std_msgs/MultiArrayLayout\n" +
00108 "# The multiarray declares a generic multi-dimensional array of a\n" +
00109 "# particular data type.  Dimensions are ordered from outer most\n" +
00110 "# to inner most.\n" +
00111 "\n" +
00112 "MultiArrayDimension[] dim # Array of dimension properties\n" +
00113 "uint32 data_offset        # padding bytes at front of data\n" +
00114 "\n" +
00115 "# Accessors should ALWAYS be written in terms of dimension stride\n" +
00116 "# and specified outer-most dimension first.\n" +
00117 "# \n" +
00118 "# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n" +
00119 "#\n" +
00120 "# A standard, 3-channel 640x480 image with interleaved color channels\n" +
00121 "# would be specified as:\n" +
00122 "#\n" +
00123 "# dim[0].label  = \"height\"\n" +
00124 "# dim[0].size   = 480\n" +
00125 "# dim[0].stride = 3*640*480 = 921600  (note dim[0] stride is just size of image)\n" +
00126 "# dim[1].label  = \"width\"\n" +
00127 "# dim[1].size   = 640\n" +
00128 "# dim[1].stride = 3*640 = 1920\n" +
00129 "# dim[2].label  = \"channel\"\n" +
00130 "# dim[2].size   = 3\n" +
00131 "# dim[2].stride = 3\n" +
00132 "#\n" +
00133 "# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n" +
00134 "================================================================================\n" +
00135 "MSG: std_msgs/MultiArrayDimension\n" +
00136 "string label   # label of given dimension\n" +
00137 "uint32 size    # size of given dimension (in type units)\n" +
00138 "uint32 stride  # stride of given dimension\n" +
00139 ""; }
00140   public java.lang.String getMessageDefinition() { return __s_getMessageDefinition(); }
00141 
00142   public TestDataTypes clone() {
00143     TestDataTypes c = new TestDataTypes();
00144     c.deserialize(serialize(0));
00145     return c;
00146   }
00147 
00148   public void setTo(ros.communication.Message m) {
00149     deserialize(m.serialize(0));
00150   }
00151 
00152   public int serializationLength() {
00153     int __l = 0;
00154     __l += 1; 
00155     __l += 1; 
00156     __l += 1; 
00157     __l += 1; 
00158     __l += 2; 
00159     __l += 2; 
00160     __l += 4; 
00161     __l += 4; 
00162     __l += 8; 
00163     __l += 8; 
00164     __l += 4; 
00165     __l += 8; 
00166     __l += 4 + string_.length();
00167     __l += 8; 
00168     __l += 8; 
00169     __l += 4 + byte_v.length * 1; 
00170     __l += 2; 
00171     __l += 4 + float64_v.length * 8; 
00172     __l += 16; 
00173     __l += 4;
00174     for(java.lang.String val : string_v) {
00175       __l += 4 + val.length();
00176     }
00177 
00178     for(java.lang.String val : string_f) {
00179       __l += 4 + val.length();
00180     }
00181     __l += 4 + time_v.size() * 8; 
00182     __l += 16; 
00183     __l += Byte_.serializationLength();
00184     __l += 4;
00185     for(ros.pkg.std_msgs.msg.Byte val : Byte_v) {
00186       __l += val.serializationLength();
00187     }
00188     __l += ByteMultiArray_.serializationLength();
00189     __l += 4;
00190     for(ros.pkg.std_msgs.msg.ByteMultiArray val : ByteMultiArray_v) {
00191       __l += val.serializationLength();
00192     }
00193     return __l;
00194   }
00195 
00196   public void serialize(ByteBuffer bb, int seq) {
00197     bb.put((byte)byte_);
00198     bb.put((byte)char_);
00199     bb.put((byte)uint8_);
00200     bb.put(int8_);
00201     bb.putShort((short)uint16_);
00202     bb.putShort(int16_);
00203     bb.putInt((int)uint32_);
00204     bb.putInt(int32_);
00205     bb.putLong(uint64_);
00206     bb.putLong(int64_);
00207     bb.putFloat(float32_);
00208     bb.putDouble(float64_);
00209     Serialization.writeString(bb, string_);
00210     Serialization.writeTime(bb, time_);
00211     Serialization.writeDuration(bb, duration_);
00212     bb.putInt(byte_v.length);
00213     for(short val : byte_v) {
00214       bb.put((byte)val);
00215     }
00216 
00217     for(short val : byte_f) {
00218       bb.put((byte)val);
00219     }
00220     bb.putInt(float64_v.length);
00221     for(double val : float64_v) {
00222       bb.putDouble(val);
00223     }
00224 
00225     for(double val : float64_f) {
00226       bb.putDouble(val);
00227     }
00228     bb.putInt(string_v.size());
00229     for(java.lang.String val : string_v) {
00230       Serialization.writeString(bb, val);
00231     }
00232 
00233     for(java.lang.String val : string_f) {
00234       Serialization.writeString(bb, val);
00235     }
00236     bb.putInt(time_v.size());
00237     for(ros.communication.Time val : time_v) {
00238       Serialization.writeTime(bb, val);
00239     }
00240 
00241     for(ros.communication.Time val : time_f) {
00242       Serialization.writeTime(bb, val);
00243     }
00244     Byte_.serialize(bb, seq);
00245     bb.putInt(Byte_v.size());
00246     for(ros.pkg.std_msgs.msg.Byte val : Byte_v) {
00247       val.serialize(bb, seq);
00248     }
00249     ByteMultiArray_.serialize(bb, seq);
00250     bb.putInt(ByteMultiArray_v.size());
00251     for(ros.pkg.std_msgs.msg.ByteMultiArray val : ByteMultiArray_v) {
00252       val.serialize(bb, seq);
00253     }
00254   }
00255 
00256   public void deserialize(ByteBuffer bb) {
00257     byte_ = (short)(bb.get() & 0xff);
00258     char_ = (char)(bb.get() & 0xff);
00259     uint8_ = (short)(bb.get() & 0xff);
00260     int8_ = bb.get();
00261     uint16_ = (int)(bb.getShort() & 0xffff);
00262     int16_ = bb.getShort();
00263     uint32_ = (long)(bb.getInt() & 0xffffffff);
00264     int32_ = bb.getInt();
00265     uint64_ = bb.getLong();
00266     int64_ = bb.getLong();
00267     float32_ = bb.getFloat();
00268     float64_ = bb.getDouble();
00269     string_ = Serialization.readString(bb);
00270     time_ = Serialization.readTime(bb);
00271     duration_ = Serialization.readDuration(bb);
00272 
00273     int __byte_v_len = bb.getInt();
00274     byte_v = new short[__byte_v_len];
00275     for(int __i=0; __i<__byte_v_len; __i++) {
00276       byte_v[__i] = (short)(bb.get() & 0xff);
00277     }
00278 
00279     int __byte_f_len = byte_f.length;;
00280     byte_f = new short[__byte_f_len];
00281     for(int __i=0; __i<__byte_f_len; __i++) {
00282       byte_f[__i] = (short)(bb.get() & 0xff);
00283     }
00284 
00285     int __float64_v_len = bb.getInt();
00286     float64_v = new double[__float64_v_len];
00287     for(int __i=0; __i<__float64_v_len; __i++) {
00288       float64_v[__i] = bb.getDouble();
00289     }
00290 
00291     int __float64_f_len = float64_f.length;;
00292     float64_f = new double[__float64_f_len];
00293     for(int __i=0; __i<__float64_f_len; __i++) {
00294       float64_f[__i] = bb.getDouble();
00295     }
00296 
00297     int __string_v_len = bb.getInt();
00298     string_v = new java.util.ArrayList<java.lang.String>(__string_v_len);
00299     for(int __i=0; __i<__string_v_len; __i++) {
00300       string_v.add(Serialization.readString(bb));
00301     }
00302 
00303     int __string_f_len = string_f.length;;
00304     string_f = new java.lang.String[__string_f_len];
00305     for(int __i=0; __i<__string_f_len; __i++) {
00306       string_f[__i] = Serialization.readString(bb);
00307     }
00308 
00309     int __time_v_len = bb.getInt();
00310     time_v = new java.util.ArrayList<ros.communication.Time>(__time_v_len);
00311     for(int __i=0; __i<__time_v_len; __i++) {
00312       time_v.add(Serialization.readTime(bb));
00313     }
00314 
00315     int __time_f_len = time_f.length;;
00316     time_f = new ros.communication.Time[__time_f_len];
00317     for(int __i=0; __i<__time_f_len; __i++) {
00318       time_f[__i] = Serialization.readTime(bb);
00319     }
00320     Byte_.deserialize(bb);
00321 
00322     int __Byte_v_len = bb.getInt();
00323     Byte_v = new java.util.ArrayList<ros.pkg.std_msgs.msg.Byte>(__Byte_v_len);
00324     for(int __i=0; __i<__Byte_v_len; __i++) {
00325       ros.pkg.std_msgs.msg.Byte __tmp = new ros.pkg.std_msgs.msg.Byte();
00326       __tmp.deserialize(bb);
00327       Byte_v.add(__tmp);;
00328     }
00329     ByteMultiArray_.deserialize(bb);
00330 
00331     int __ByteMultiArray_v_len = bb.getInt();
00332     ByteMultiArray_v = new java.util.ArrayList<ros.pkg.std_msgs.msg.ByteMultiArray>(__ByteMultiArray_v_len);
00333     for(int __i=0; __i<__ByteMultiArray_v_len; __i++) {
00334       ros.pkg.std_msgs.msg.ByteMultiArray __tmp = new ros.pkg.std_msgs.msg.ByteMultiArray();
00335       __tmp.deserialize(bb);
00336       ByteMultiArray_v.add(__tmp);;
00337     }
00338   }
00339 
00340   @SuppressWarnings("all")
00341   public boolean equals(Object o) {
00342     if(!(o instanceof TestDataTypes))
00343       return false;
00344     TestDataTypes other = (TestDataTypes) o;
00345     return
00346       byte_ == other.byte_ &&
00347       char_ == other.char_ &&
00348       uint8_ == other.uint8_ &&
00349       int8_ == other.int8_ &&
00350       uint16_ == other.uint16_ &&
00351       int16_ == other.int16_ &&
00352       uint32_ == other.uint32_ &&
00353       int32_ == other.int32_ &&
00354       uint64_ == other.uint64_ &&
00355       int64_ == other.int64_ &&
00356       float32_ == other.float32_ &&
00357       float64_ == other.float64_ &&
00358       string_.equals(other.string_) &&
00359       time_.equals(other.time_) &&
00360       duration_.equals(other.duration_) &&
00361       java.util.Arrays.equals(byte_v, other.byte_v) &&
00362       java.util.Arrays.equals(byte_f, other.byte_f) &&
00363       java.util.Arrays.equals(float64_v, other.float64_v) &&
00364       java.util.Arrays.equals(float64_f, other.float64_f) &&
00365       string_v.equals(other.string_v) &&
00366       java.util.Arrays.equals(string_f, other.string_f) &&
00367       time_v.equals(other.time_v) &&
00368       java.util.Arrays.equals(time_f, other.time_f) &&
00369       Byte_.equals(other.Byte_) &&
00370       Byte_v.equals(other.Byte_v) &&
00371       ByteMultiArray_.equals(other.ByteMultiArray_) &&
00372       ByteMultiArray_v.equals(other.ByteMultiArray_v) &&
00373       true;
00374   }
00375 
00376   @SuppressWarnings("all")
00377   public int hashCode() {
00378     final int prime = 31;
00379     int result = 1;
00380     long tmp;
00381     result = prime * result + this.byte_;
00382     result = prime * result + this.char_;
00383     result = prime * result + this.uint8_;
00384     result = prime * result + this.int8_;
00385     result = prime * result + this.uint16_;
00386     result = prime * result + this.int16_;
00387     result = prime * result + (int)(this.uint32_ ^ (this.uint32_ >>> 32));
00388     result = prime * result + this.int32_;
00389     result = prime * result + (int)(this.uint64_ ^ (this.uint64_ >>> 32));
00390     result = prime * result + (int)(this.int64_ ^ (this.int64_ >>> 32));
00391     result = prime * result + Float.floatToIntBits(this.float32_);
00392     result = prime * result + (int)((tmp = Double.doubleToLongBits(this.float64_)) ^ (tmp >>> 32));
00393     result = prime * result + (this.string_ == null ? 0 : this.string_.hashCode());
00394     result = prime * result + (this.time_ == null ? 0 : this.time_.hashCode());
00395     result = prime * result + (this.duration_ == null ? 0 : this.duration_.hashCode());
00396     result = prime * result + java.util.Arrays.hashCode(this.byte_v);
00397     result = prime * result + java.util.Arrays.hashCode(this.byte_f);
00398     result = prime * result + java.util.Arrays.hashCode(this.float64_v);
00399     result = prime * result + java.util.Arrays.hashCode(this.float64_f);
00400     result = prime * result + (this.string_v == null ? 0 : this.string_v.hashCode());
00401     result = prime * result + java.util.Arrays.hashCode(this.string_f);
00402     result = prime * result + (this.time_v == null ? 0 : this.time_v.hashCode());
00403     result = prime * result + java.util.Arrays.hashCode(this.time_f);
00404     result = prime * result + (this.Byte_ == null ? 0 : this.Byte_.hashCode());
00405     result = prime * result + (this.Byte_v == null ? 0 : this.Byte_v.hashCode());
00406     result = prime * result + (this.ByteMultiArray_ == null ? 0 : this.ByteMultiArray_.hashCode());
00407     result = prime * result + (this.ByteMultiArray_v == null ? 0 : this.ByteMultiArray_v.hashCode());
00408     return result;
00409   }
00410 } 
00411