00001
00002
00003 package ros.pkg.mapping_msgs.msg;
00004
00005 import java.nio.ByteBuffer;
00006
00007 public class PolygonalMap extends ros.communication.Message {
00008
00009 public ros.pkg.std_msgs.msg.Header header = new ros.pkg.std_msgs.msg.Header();
00010 public java.util.ArrayList<ros.pkg.geometry_msgs.msg.Polygon> polygons = new java.util.ArrayList<ros.pkg.geometry_msgs.msg.Polygon>();
00011 public java.util.ArrayList<ros.pkg.sensor_msgs.msg.ChannelFloat32> chan = new java.util.ArrayList<ros.pkg.sensor_msgs.msg.ChannelFloat32>();
00012
00013 public PolygonalMap() {
00014 }
00015
00016 public static java.lang.String __s_getDataType() { return "mapping_msgs/PolygonalMap"; }
00017 public java.lang.String getDataType() { return __s_getDataType(); }
00018 public static java.lang.String __s_getMD5Sum() { return "3ef041ea9abaaa9dac3e5aec60c68a99"; }
00019 public java.lang.String getMD5Sum() { return __s_getMD5Sum(); }
00020 public static java.lang.String __s_getMessageDefinition() { return "Header header\n" +
00021 "geometry_msgs/Polygon[] polygons\n" +
00022 "sensor_msgs/ChannelFloat32[] chan\n" +
00023 "\n" +
00024 "================================================================================\n" +
00025 "MSG: std_msgs/Header\n" +
00026 "# Standard metadata for higher-level stamped data types.\n" +
00027 "# This is generally used to communicate timestamped data \n" +
00028 "# in a particular coordinate frame.\n" +
00029 "# \n" +
00030 "# sequence ID: consecutively increasing ID \n" +
00031 "uint32 seq\n" +
00032 "#Two-integer timestamp that is expressed as:\n" +
00033 "# * stamp.secs: seconds (stamp_secs) since epoch\n" +
00034 "# * stamp.nsecs: nanoseconds since stamp_secs\n" +
00035 "# time-handling sugar is provided by the client library\n" +
00036 "time stamp\n" +
00037 "#Frame this data is associated with\n" +
00038 "# 0: no frame\n" +
00039 "# 1: global frame\n" +
00040 "string frame_id\n" +
00041 "\n" +
00042 "================================================================================\n" +
00043 "MSG: geometry_msgs/Polygon\n" +
00044 "#A specification of a polygon where the first and last points are assumed to be connected\n" +
00045 "geometry_msgs/Point32[] points\n" +
00046 "\n" +
00047 "================================================================================\n" +
00048 "MSG: geometry_msgs/Point32\n" +
00049 "# This contains the position of a point in free space(with 32 bits of precision).\n" +
00050 "# It is recommeded to use Point wherever possible instead of Point32. \n" +
00051 "# \n" +
00052 "# This recommendation is to promote interoperability. \n" +
00053 "#\n" +
00054 "# This message is designed to take up less space when sending\n" +
00055 "# lots of points at once, as in the case of a PointCloud. \n" +
00056 "\n" +
00057 "float32 x\n" +
00058 "float32 y\n" +
00059 "float32 z\n" +
00060 "================================================================================\n" +
00061 "MSG: sensor_msgs/ChannelFloat32\n" +
00062 "# This message is used by the PointCloud message to hold optional data\n" +
00063 "# associated with each point in the cloud. The length of the values\n" +
00064 "# array should be the same as the length of the points array in the\n" +
00065 "# PointCloud, and each value should be associated with the corresponding\n" +
00066 "# point.\n" +
00067 "\n" +
00068 "# Channel names in existing practice include:\n" +
00069 "# \"u\", \"v\" - row and column (respectively) in the left stereo image.\n" +
00070 "# This is opposite to usual conventions but remains for\n" +
00071 "# historical reasons. The newer PointCloud2 message has no\n" +
00072 "# such problem.\n" +
00073 "# \"rgb\" - For point clouds produced by color stereo cameras. uint8\n" +
00074 "# (R,G,B) values packed into the least significant 24 bits,\n" +
00075 "# in order.\n" +
00076 "# \"intensity\" - laser or pixel intensity.\n" +
00077 "# \"distance\"\n" +
00078 "\n" +
00079 "# The channel name should give semantics of the channel (e.g.\n" +
00080 "# \"intensity\" instead of \"value\").\n" +
00081 "string name\n" +
00082 "\n" +
00083 "# The values array should be 1-1 with the elements of the associated\n" +
00084 "# PointCloud.\n" +
00085 "float32[] values\n" +
00086 "\n" +
00087 ""; }
00088 public java.lang.String getMessageDefinition() { return __s_getMessageDefinition(); }
00089
00090 public PolygonalMap clone() {
00091 PolygonalMap c = new PolygonalMap();
00092 c.deserialize(serialize(0));
00093 return c;
00094 }
00095
00096 public void setTo(ros.communication.Message m) {
00097 deserialize(m.serialize(0));
00098 }
00099
00100 public int serializationLength() {
00101 int __l = 0;
00102 __l += header.serializationLength();
00103 __l += 4;
00104 for(ros.pkg.geometry_msgs.msg.Polygon val : polygons) {
00105 __l += val.serializationLength();
00106 }
00107 __l += 4;
00108 for(ros.pkg.sensor_msgs.msg.ChannelFloat32 val : chan) {
00109 __l += val.serializationLength();
00110 }
00111 return __l;
00112 }
00113
00114 public void serialize(ByteBuffer bb, int seq) {
00115 header.serialize(bb, seq);
00116 bb.putInt(polygons.size());
00117 for(ros.pkg.geometry_msgs.msg.Polygon val : polygons) {
00118 val.serialize(bb, seq);
00119 }
00120 bb.putInt(chan.size());
00121 for(ros.pkg.sensor_msgs.msg.ChannelFloat32 val : chan) {
00122 val.serialize(bb, seq);
00123 }
00124 }
00125
00126 public void deserialize(ByteBuffer bb) {
00127 header.deserialize(bb);
00128
00129 int __polygons_len = bb.getInt();
00130 polygons = new java.util.ArrayList<ros.pkg.geometry_msgs.msg.Polygon>(__polygons_len);
00131 for(int __i=0; __i<__polygons_len; __i++) {
00132 ros.pkg.geometry_msgs.msg.Polygon __tmp = new ros.pkg.geometry_msgs.msg.Polygon();
00133 __tmp.deserialize(bb);
00134 polygons.add(__tmp);;
00135 }
00136
00137 int __chan_len = bb.getInt();
00138 chan = new java.util.ArrayList<ros.pkg.sensor_msgs.msg.ChannelFloat32>(__chan_len);
00139 for(int __i=0; __i<__chan_len; __i++) {
00140 ros.pkg.sensor_msgs.msg.ChannelFloat32 __tmp = new ros.pkg.sensor_msgs.msg.ChannelFloat32();
00141 __tmp.deserialize(bb);
00142 chan.add(__tmp);;
00143 }
00144 }
00145
00146 @SuppressWarnings("all")
00147 public boolean equals(Object o) {
00148 if(!(o instanceof PolygonalMap))
00149 return false;
00150 PolygonalMap other = (PolygonalMap) o;
00151 return
00152 header.equals(other.header) &&
00153 polygons.equals(other.polygons) &&
00154 chan.equals(other.chan) &&
00155 true;
00156 }
00157
00158 @SuppressWarnings("all")
00159 public int hashCode() {
00160 final int prime = 31;
00161 int result = 1;
00162 long tmp;
00163 result = prime * result + (this.header == null ? 0 : this.header.hashCode());
00164 result = prime * result + (this.polygons == null ? 0 : this.polygons.hashCode());
00165 result = prime * result + (this.chan == null ? 0 : this.chan.hashCode());
00166 return result;
00167 }
00168 }
00169