00001
00002
00003 package ros.pkg.sensor_msgs.msg;
00004
00005 import java.nio.ByteBuffer;
00006
00007 public class LaserScan extends ros.communication.Message {
00008
00009 public ros.pkg.std_msgs.msg.Header header = new ros.pkg.std_msgs.msg.Header();
00010 public float angle_min;
00011 public float angle_max;
00012 public float angle_increment;
00013 public float time_increment;
00014 public float scan_time;
00015 public float range_min;
00016 public float range_max;
00017 public float[] ranges = new float[0];
00018 public float[] intensities = new float[0];
00019
00020 public LaserScan() {
00021 }
00022
00023 public static java.lang.String __s_getDataType() { return "sensor_msgs/LaserScan"; }
00024 public java.lang.String getDataType() { return __s_getDataType(); }
00025 public static java.lang.String __s_getMD5Sum() { return "90c7ef2dc6895d81024acba2ac42f369"; }
00026 public java.lang.String getMD5Sum() { return __s_getMD5Sum(); }
00027 public static java.lang.String __s_getMessageDefinition() { return "# Single scan from a planar laser range-finder\n" +
00028 "#\n" +
00029 "# If you have another ranging device with different behavior (e.g. a sonar\n" +
00030 "# array), please find or create a different message, since applications\n" +
00031 "# will make fairly laser-specific assumptions about this data\n" +
00032 "\n" +
00033 "Header header # timestamp in the header is the acquisition time of \n" +
00034 " # the first ray in the scan.\n" +
00035 " #\n" +
00036 " # in frame frame_id, angles are measured around \n" +
00037 " # the positive Z axis (counterclockwise, if Z is up)\n" +
00038 " # with zero angle being forward along the x axis\n" +
00039 " \n" +
00040 "float32 angle_min # start angle of the scan [rad]\n" +
00041 "float32 angle_max # end angle of the scan [rad]\n" +
00042 "float32 angle_increment # angular distance between measurements [rad]\n" +
00043 "\n" +
00044 "float32 time_increment # time between measurements [seconds] - if your scanner\n" +
00045 " # is moving, this will be used in interpolating position\n" +
00046 " # of 3d points\n" +
00047 "float32 scan_time # time between scans [seconds]\n" +
00048 "\n" +
00049 "float32 range_min # minimum range value [m]\n" +
00050 "float32 range_max # maximum range value [m]\n" +
00051 "\n" +
00052 "float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)\n" +
00053 "float32[] intensities # intensity data [device-specific units]. If your\n" +
00054 " # device does not provide intensities, please leave\n" +
00055 " # the array empty.\n" +
00056 "\n" +
00057 "================================================================================\n" +
00058 "MSG: std_msgs/Header\n" +
00059 "# Standard metadata for higher-level stamped data types.\n" +
00060 "# This is generally used to communicate timestamped data \n" +
00061 "# in a particular coordinate frame.\n" +
00062 "# \n" +
00063 "# sequence ID: consecutively increasing ID \n" +
00064 "uint32 seq\n" +
00065 "#Two-integer timestamp that is expressed as:\n" +
00066 "# * stamp.secs: seconds (stamp_secs) since epoch\n" +
00067 "# * stamp.nsecs: nanoseconds since stamp_secs\n" +
00068 "# time-handling sugar is provided by the client library\n" +
00069 "time stamp\n" +
00070 "#Frame this data is associated with\n" +
00071 "# 0: no frame\n" +
00072 "# 1: global frame\n" +
00073 "string frame_id\n" +
00074 "\n" +
00075 ""; }
00076 public java.lang.String getMessageDefinition() { return __s_getMessageDefinition(); }
00077
00078 public LaserScan clone() {
00079 LaserScan c = new LaserScan();
00080 c.deserialize(serialize(0));
00081 return c;
00082 }
00083
00084 public void setTo(ros.communication.Message m) {
00085 deserialize(m.serialize(0));
00086 }
00087
00088 public int serializationLength() {
00089 int __l = 0;
00090 __l += header.serializationLength();
00091 __l += 4;
00092 __l += 4;
00093 __l += 4;
00094 __l += 4;
00095 __l += 4;
00096 __l += 4;
00097 __l += 4;
00098 __l += 4 + ranges.length * 4;
00099 __l += 4 + intensities.length * 4;
00100 return __l;
00101 }
00102
00103 public void serialize(ByteBuffer bb, int seq) {
00104 header.serialize(bb, seq);
00105 bb.putFloat(angle_min);
00106 bb.putFloat(angle_max);
00107 bb.putFloat(angle_increment);
00108 bb.putFloat(time_increment);
00109 bb.putFloat(scan_time);
00110 bb.putFloat(range_min);
00111 bb.putFloat(range_max);
00112 bb.putInt(ranges.length);
00113 for(float val : ranges) {
00114 bb.putFloat(val);
00115 }
00116 bb.putInt(intensities.length);
00117 for(float val : intensities) {
00118 bb.putFloat(val);
00119 }
00120 }
00121
00122 public void deserialize(ByteBuffer bb) {
00123 header.deserialize(bb);
00124 angle_min = bb.getFloat();
00125 angle_max = bb.getFloat();
00126 angle_increment = bb.getFloat();
00127 time_increment = bb.getFloat();
00128 scan_time = bb.getFloat();
00129 range_min = bb.getFloat();
00130 range_max = bb.getFloat();
00131
00132 int __ranges_len = bb.getInt();
00133 ranges = new float[__ranges_len];
00134 for(int __i=0; __i<__ranges_len; __i++) {
00135 ranges[__i] = bb.getFloat();
00136 }
00137
00138 int __intensities_len = bb.getInt();
00139 intensities = new float[__intensities_len];
00140 for(int __i=0; __i<__intensities_len; __i++) {
00141 intensities[__i] = bb.getFloat();
00142 }
00143 }
00144
00145 @SuppressWarnings("all")
00146 public boolean equals(Object o) {
00147 if(!(o instanceof LaserScan))
00148 return false;
00149 LaserScan other = (LaserScan) o;
00150 return
00151 header.equals(other.header) &&
00152 angle_min == other.angle_min &&
00153 angle_max == other.angle_max &&
00154 angle_increment == other.angle_increment &&
00155 time_increment == other.time_increment &&
00156 scan_time == other.scan_time &&
00157 range_min == other.range_min &&
00158 range_max == other.range_max &&
00159 java.util.Arrays.equals(ranges, other.ranges) &&
00160 java.util.Arrays.equals(intensities, other.intensities) &&
00161 true;
00162 }
00163
00164 @SuppressWarnings("all")
00165 public int hashCode() {
00166 final int prime = 31;
00167 int result = 1;
00168 long tmp;
00169 result = prime * result + (this.header == null ? 0 : this.header.hashCode());
00170 result = prime * result + Float.floatToIntBits(this.angle_min);
00171 result = prime * result + Float.floatToIntBits(this.angle_max);
00172 result = prime * result + Float.floatToIntBits(this.angle_increment);
00173 result = prime * result + Float.floatToIntBits(this.time_increment);
00174 result = prime * result + Float.floatToIntBits(this.scan_time);
00175 result = prime * result + Float.floatToIntBits(this.range_min);
00176 result = prime * result + Float.floatToIntBits(this.range_max);
00177 result = prime * result + java.util.Arrays.hashCode(this.ranges);
00178 result = prime * result + java.util.Arrays.hashCode(this.intensities);
00179 return result;
00180 }
00181 }
00182