00001
00002
00003 package ros.pkg.geometric_shapes_msgs.msg;
00004
00005 import java.nio.ByteBuffer;
00006
00007 public class Shape extends ros.communication.Message {
00008 static public final short SPHERE = 0;
00009 static public final short BOX = 1;
00010 static public final short CYLINDER = 2;
00011 static public final short MESH = 3;
00012
00013 public short type;
00014 public double[] dimensions = new double[0];
00015 public int[] triangles = new int[0];
00016 public java.util.ArrayList<ros.pkg.geometry_msgs.msg.Point> vertices = new java.util.ArrayList<ros.pkg.geometry_msgs.msg.Point>();
00017
00018 public Shape() {
00019 }
00020
00021 public static java.lang.String __s_getDataType() { return "geometric_shapes_msgs/Shape"; }
00022 public java.lang.String getDataType() { return __s_getDataType(); }
00023 public static java.lang.String __s_getMD5Sum() { return "59935940044147de75e7523b5d37c4d7"; }
00024 public java.lang.String getMD5Sum() { return __s_getMD5Sum(); }
00025 public static java.lang.String __s_getMessageDefinition() { return "byte SPHERE=0\n" +
00026 "byte BOX=1\n" +
00027 "byte CYLINDER=2\n" +
00028 "byte MESH=3\n" +
00029 "\n" +
00030 "byte type\n" +
00031 "\n" +
00032 "\n" +
00033 "#### define sphere, box, cylinder ####\n" +
00034 "# the origin of each shape is considered at the shape's center\n" +
00035 "\n" +
00036 "# for sphere\n" +
00037 "# radius := dimensions[0]\n" +
00038 "\n" +
00039 "# for cylinder\n" +
00040 "# radius := dimensions[0]\n" +
00041 "# length := dimensions[1]\n" +
00042 "# the length is along the Z axis\n" +
00043 "\n" +
00044 "# for box\n" +
00045 "# size_x := dimensions[0]\n" +
00046 "# size_y := dimensions[1]\n" +
00047 "# size_z := dimensions[2]\n" +
00048 "float64[] dimensions\n" +
00049 "\n" +
00050 "\n" +
00051 "#### define mesh ####\n" +
00052 "\n" +
00053 "# list of triangles; triangle k is defined by tre vertices located\n" +
00054 "# at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n" +
00055 "int32[] triangles\n" +
00056 "geometry_msgs/Point[] vertices\n" +
00057 "\n" +
00058 "================================================================================\n" +
00059 "MSG: geometry_msgs/Point\n" +
00060 "# This contains the position of a point in free space\n" +
00061 "float64 x\n" +
00062 "float64 y\n" +
00063 "float64 z\n" +
00064 "\n" +
00065 ""; }
00066 public java.lang.String getMessageDefinition() { return __s_getMessageDefinition(); }
00067
00068 public Shape clone() {
00069 Shape c = new Shape();
00070 c.deserialize(serialize(0));
00071 return c;
00072 }
00073
00074 public void setTo(ros.communication.Message m) {
00075 deserialize(m.serialize(0));
00076 }
00077
00078 public int serializationLength() {
00079 int __l = 0;
00080 __l += 1;
00081 __l += 4 + dimensions.length * 8;
00082 __l += 4 + triangles.length * 4;
00083 __l += 4;
00084 for(ros.pkg.geometry_msgs.msg.Point val : vertices) {
00085 __l += val.serializationLength();
00086 }
00087 return __l;
00088 }
00089
00090 public void serialize(ByteBuffer bb, int seq) {
00091 bb.put((byte)type);
00092 bb.putInt(dimensions.length);
00093 for(double val : dimensions) {
00094 bb.putDouble(val);
00095 }
00096 bb.putInt(triangles.length);
00097 for(int val : triangles) {
00098 bb.putInt(val);
00099 }
00100 bb.putInt(vertices.size());
00101 for(ros.pkg.geometry_msgs.msg.Point val : vertices) {
00102 val.serialize(bb, seq);
00103 }
00104 }
00105
00106 public void deserialize(ByteBuffer bb) {
00107 type = (short)(bb.get() & 0xff);
00108
00109 int __dimensions_len = bb.getInt();
00110 dimensions = new double[__dimensions_len];
00111 for(int __i=0; __i<__dimensions_len; __i++) {
00112 dimensions[__i] = bb.getDouble();
00113 }
00114
00115 int __triangles_len = bb.getInt();
00116 triangles = new int[__triangles_len];
00117 for(int __i=0; __i<__triangles_len; __i++) {
00118 triangles[__i] = bb.getInt();
00119 }
00120
00121 int __vertices_len = bb.getInt();
00122 vertices = new java.util.ArrayList<ros.pkg.geometry_msgs.msg.Point>(__vertices_len);
00123 for(int __i=0; __i<__vertices_len; __i++) {
00124 ros.pkg.geometry_msgs.msg.Point __tmp = new ros.pkg.geometry_msgs.msg.Point();
00125 __tmp.deserialize(bb);
00126 vertices.add(__tmp);;
00127 }
00128 }
00129
00130 @SuppressWarnings("all")
00131 public boolean equals(Object o) {
00132 if(!(o instanceof Shape))
00133 return false;
00134 Shape other = (Shape) o;
00135 return
00136 type == other.type &&
00137 java.util.Arrays.equals(dimensions, other.dimensions) &&
00138 java.util.Arrays.equals(triangles, other.triangles) &&
00139 vertices.equals(other.vertices) &&
00140 true;
00141 }
00142
00143 @SuppressWarnings("all")
00144 public int hashCode() {
00145 final int prime = 31;
00146 int result = 1;
00147 long tmp;
00148 result = prime * result + this.type;
00149 result = prime * result + java.util.Arrays.hashCode(this.dimensions);
00150 result = prime * result + java.util.Arrays.hashCode(this.triangles);
00151 result = prime * result + (this.vertices == null ? 0 : this.vertices.hashCode());
00152 return result;
00153 }
00154 }
00155