00001
00002
00003 package ros.pkg.mapping_msgs.msg;
00004
00005 import java.nio.ByteBuffer;
00006
00007 public class CollisionObject extends ros.communication.Message {
00008
00009 public ros.pkg.std_msgs.msg.Header header = new ros.pkg.std_msgs.msg.Header();
00010 public java.lang.String id = new java.lang.String();
00011 public ros.pkg.mapping_msgs.msg.CollisionObjectOperation operation = new ros.pkg.mapping_msgs.msg.CollisionObjectOperation();
00012 public java.util.ArrayList<ros.pkg.geometric_shapes_msgs.msg.Shape> shapes = new java.util.ArrayList<ros.pkg.geometric_shapes_msgs.msg.Shape>();
00013 public java.util.ArrayList<ros.pkg.geometry_msgs.msg.Pose> poses = new java.util.ArrayList<ros.pkg.geometry_msgs.msg.Pose>();
00014
00015 public CollisionObject() {
00016 }
00017
00018 public static java.lang.String __s_getDataType() { return "mapping_msgs/CollisionObject"; }
00019 public java.lang.String getDataType() { return __s_getDataType(); }
00020 public static java.lang.String __s_getMD5Sum() { return "c25d22faff81b340d88e28e270ae03f5"; }
00021 public java.lang.String getMD5Sum() { return __s_getMD5Sum(); }
00022 public static java.lang.String __s_getMessageDefinition() { return "# a header, used for interpreting the poses\n" +
00023 "Header header\n" +
00024 "\n" +
00025 "# the id of the object\n" +
00026 "string id\n" +
00027 "\n" +
00028 "#This contains what is to be done with the object\n" +
00029 "CollisionObjectOperation operation\n" +
00030 "\n" +
00031 "#the shapes associated with the object\n" +
00032 "geometric_shapes_msgs/Shape[] shapes\n" +
00033 "\n" +
00034 "#the poses associated with the shapes - will be transformed using the header\n" +
00035 "geometry_msgs/Pose[] poses\n" +
00036 "\n" +
00037 "================================================================================\n" +
00038 "MSG: std_msgs/Header\n" +
00039 "# Standard metadata for higher-level stamped data types.\n" +
00040 "# This is generally used to communicate timestamped data \n" +
00041 "# in a particular coordinate frame.\n" +
00042 "# \n" +
00043 "# sequence ID: consecutively increasing ID \n" +
00044 "uint32 seq\n" +
00045 "#Two-integer timestamp that is expressed as:\n" +
00046 "# * stamp.secs: seconds (stamp_secs) since epoch\n" +
00047 "# * stamp.nsecs: nanoseconds since stamp_secs\n" +
00048 "# time-handling sugar is provided by the client library\n" +
00049 "time stamp\n" +
00050 "#Frame this data is associated with\n" +
00051 "# 0: no frame\n" +
00052 "# 1: global frame\n" +
00053 "string frame_id\n" +
00054 "\n" +
00055 "================================================================================\n" +
00056 "MSG: mapping_msgs/CollisionObjectOperation\n" +
00057 "#Puts the object into the environment\n" +
00058 "#or updates the object if already added\n" +
00059 "byte ADD=0\n" +
00060 "\n" +
00061 "#Removes the object from the environment entirely\n" +
00062 "byte REMOVE=1\n" +
00063 "\n" +
00064 "#Only valid within the context of a CollisionAttachedObject message\n" +
00065 "#Will be ignored if sent with an CollisionObject message\n" +
00066 "#Takes an attached object, detaches from the attached link\n" +
00067 "#But adds back in as regular object\n" +
00068 "byte DETACH_AND_ADD_AS_OBJECT=2\n" +
00069 "\n" +
00070 "#Only valid within the context of a CollisionAttachedObject message\n" +
00071 "#Will be ignored if sent with an CollisionObject message\n" +
00072 "#Takes current object in the environment and removes it as\n" +
00073 "#a regular object\n" +
00074 "byte ATTACH_AND_REMOVE_AS_OBJECT=3\n" +
00075 "\n" +
00076 "# Byte code for operation\n" +
00077 "byte operation\n" +
00078 "\n" +
00079 "================================================================================\n" +
00080 "MSG: geometric_shapes_msgs/Shape\n" +
00081 "byte SPHERE=0\n" +
00082 "byte BOX=1\n" +
00083 "byte CYLINDER=2\n" +
00084 "byte MESH=3\n" +
00085 "\n" +
00086 "byte type\n" +
00087 "\n" +
00088 "\n" +
00089 "#### define sphere, box, cylinder ####\n" +
00090 "# the origin of each shape is considered at the shape's center\n" +
00091 "\n" +
00092 "# for sphere\n" +
00093 "# radius := dimensions[0]\n" +
00094 "\n" +
00095 "# for cylinder\n" +
00096 "# radius := dimensions[0]\n" +
00097 "# length := dimensions[1]\n" +
00098 "# the length is along the Z axis\n" +
00099 "\n" +
00100 "# for box\n" +
00101 "# size_x := dimensions[0]\n" +
00102 "# size_y := dimensions[1]\n" +
00103 "# size_z := dimensions[2]\n" +
00104 "float64[] dimensions\n" +
00105 "\n" +
00106 "\n" +
00107 "#### define mesh ####\n" +
00108 "\n" +
00109 "# list of triangles; triangle k is defined by tre vertices located\n" +
00110 "# at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n" +
00111 "int32[] triangles\n" +
00112 "geometry_msgs/Point[] vertices\n" +
00113 "\n" +
00114 "================================================================================\n" +
00115 "MSG: geometry_msgs/Point\n" +
00116 "# This contains the position of a point in free space\n" +
00117 "float64 x\n" +
00118 "float64 y\n" +
00119 "float64 z\n" +
00120 "\n" +
00121 "================================================================================\n" +
00122 "MSG: geometry_msgs/Pose\n" +
00123 "# A representation of pose in free space, composed of postion and orientation. \n" +
00124 "Point position\n" +
00125 "Quaternion orientation\n" +
00126 "\n" +
00127 "================================================================================\n" +
00128 "MSG: geometry_msgs/Quaternion\n" +
00129 "# This represents an orientation in free space in quaternion form.\n" +
00130 "\n" +
00131 "float64 x\n" +
00132 "float64 y\n" +
00133 "float64 z\n" +
00134 "float64 w\n" +
00135 "\n" +
00136 ""; }
00137 public java.lang.String getMessageDefinition() { return __s_getMessageDefinition(); }
00138
00139 public CollisionObject clone() {
00140 CollisionObject c = new CollisionObject();
00141 c.deserialize(serialize(0));
00142 return c;
00143 }
00144
00145 public void setTo(ros.communication.Message m) {
00146 deserialize(m.serialize(0));
00147 }
00148
00149 public int serializationLength() {
00150 int __l = 0;
00151 __l += header.serializationLength();
00152 __l += 4 + id.length();
00153 __l += operation.serializationLength();
00154 __l += 4;
00155 for(ros.pkg.geometric_shapes_msgs.msg.Shape val : shapes) {
00156 __l += val.serializationLength();
00157 }
00158 __l += 4;
00159 for(ros.pkg.geometry_msgs.msg.Pose val : poses) {
00160 __l += val.serializationLength();
00161 }
00162 return __l;
00163 }
00164
00165 public void serialize(ByteBuffer bb, int seq) {
00166 header.serialize(bb, seq);
00167 Serialization.writeString(bb, id);
00168 operation.serialize(bb, seq);
00169 bb.putInt(shapes.size());
00170 for(ros.pkg.geometric_shapes_msgs.msg.Shape val : shapes) {
00171 val.serialize(bb, seq);
00172 }
00173 bb.putInt(poses.size());
00174 for(ros.pkg.geometry_msgs.msg.Pose val : poses) {
00175 val.serialize(bb, seq);
00176 }
00177 }
00178
00179 public void deserialize(ByteBuffer bb) {
00180 header.deserialize(bb);
00181 id = Serialization.readString(bb);
00182 operation.deserialize(bb);
00183
00184 int __shapes_len = bb.getInt();
00185 shapes = new java.util.ArrayList<ros.pkg.geometric_shapes_msgs.msg.Shape>(__shapes_len);
00186 for(int __i=0; __i<__shapes_len; __i++) {
00187 ros.pkg.geometric_shapes_msgs.msg.Shape __tmp = new ros.pkg.geometric_shapes_msgs.msg.Shape();
00188 __tmp.deserialize(bb);
00189 shapes.add(__tmp);;
00190 }
00191
00192 int __poses_len = bb.getInt();
00193 poses = new java.util.ArrayList<ros.pkg.geometry_msgs.msg.Pose>(__poses_len);
00194 for(int __i=0; __i<__poses_len; __i++) {
00195 ros.pkg.geometry_msgs.msg.Pose __tmp = new ros.pkg.geometry_msgs.msg.Pose();
00196 __tmp.deserialize(bb);
00197 poses.add(__tmp);;
00198 }
00199 }
00200
00201 @SuppressWarnings("all")
00202 public boolean equals(Object o) {
00203 if(!(o instanceof CollisionObject))
00204 return false;
00205 CollisionObject other = (CollisionObject) o;
00206 return
00207 header.equals(other.header) &&
00208 id.equals(other.id) &&
00209 operation.equals(other.operation) &&
00210 shapes.equals(other.shapes) &&
00211 poses.equals(other.poses) &&
00212 true;
00213 }
00214
00215 @SuppressWarnings("all")
00216 public int hashCode() {
00217 final int prime = 31;
00218 int result = 1;
00219 long tmp;
00220 result = prime * result + (this.header == null ? 0 : this.header.hashCode());
00221 result = prime * result + (this.id == null ? 0 : this.id.hashCode());
00222 result = prime * result + (this.operation == null ? 0 : this.operation.hashCode());
00223 result = prime * result + (this.shapes == null ? 0 : this.shapes.hashCode());
00224 result = prime * result + (this.poses == null ? 0 : this.poses.hashCode());
00225 return result;
00226 }
00227 }
00228