00001
00002
00003 package ros.pkg.sensor_msgs.msg;
00004
00005 import java.nio.ByteBuffer;
00006
00007 public class Range extends ros.communication.Message {
00008 static public final short ULTRASOUND = 0;
00009 static public final short INFRARED = 1;
00010
00011 public ros.pkg.std_msgs.msg.Header header = new ros.pkg.std_msgs.msg.Header();
00012 public short radiation_type;
00013 public float field_of_view;
00014 public float min_range;
00015 public float max_range;
00016 public float range;
00017
00018 public Range() {
00019 }
00020
00021 public static java.lang.String __s_getDataType() { return "sensor_msgs/Range"; }
00022 public java.lang.String getDataType() { return __s_getDataType(); }
00023 public static java.lang.String __s_getMD5Sum() { return "c005c34273dc426c67a020a87bc24148"; }
00024 public java.lang.String getMD5Sum() { return __s_getMD5Sum(); }
00025 public static java.lang.String __s_getMessageDefinition() { return "# Single range reading from an active ranger that emits energy and reports\n" +
00026 "# one range reading that is valid along an arc at the distance measured. \n" +
00027 "# This message is not appropriate for fixed-range obstacle detectors, \n" +
00028 "# such as the Sharp GP2D15. This message is also not appropriate for laser \n" +
00029 "# scanners. See the LaserScan message if you are working with a laser scanner.\n" +
00030 "\n" +
00031 "Header header # timestamp in the header is the time the ranger\n" +
00032 " # returned the distance reading\n" +
00033 "\n" +
00034 "# Radiation type enums\n" +
00035 "# If you want a value added to this list, send an email to the ros-users list\n" +
00036 "uint8 ULTRASOUND=0\n" +
00037 "uint8 INFRARED=1\n" +
00038 "\n" +
00039 "uint8 radiation_type # the type of radiation used by the sensor\n" +
00040 " # (sound, IR, etc) [enum]\n" +
00041 "\n" +
00042 "float32 field_of_view # the size of the arc that the distance reading is\n" +
00043 " # valid for [rad]\n" +
00044 " # the object causing the range reading may have\n" +
00045 " # been anywhere within -field_of_view/2 and\n" +
00046 " # field_of_view/2 at the measured range. \n" +
00047 " # 0 angle corresponds to the x-axis of the sensor.\n" +
00048 "\n" +
00049 "float32 min_range # minimum range value [m]\n" +
00050 "float32 max_range # maximum range value [m]\n" +
00051 "\n" +
00052 "float32 range # range data [m]\n" +
00053 " # (Note: values < range_min or > range_max\n" +
00054 " # should be discarded)\n" +
00055 "\n" +
00056 "================================================================================\n" +
00057 "MSG: std_msgs/Header\n" +
00058 "# Standard metadata for higher-level stamped data types.\n" +
00059 "# This is generally used to communicate timestamped data \n" +
00060 "# in a particular coordinate frame.\n" +
00061 "# \n" +
00062 "# sequence ID: consecutively increasing ID \n" +
00063 "uint32 seq\n" +
00064 "#Two-integer timestamp that is expressed as:\n" +
00065 "# * stamp.secs: seconds (stamp_secs) since epoch\n" +
00066 "# * stamp.nsecs: nanoseconds since stamp_secs\n" +
00067 "# time-handling sugar is provided by the client library\n" +
00068 "time stamp\n" +
00069 "#Frame this data is associated with\n" +
00070 "# 0: no frame\n" +
00071 "# 1: global frame\n" +
00072 "string frame_id\n" +
00073 "\n" +
00074 ""; }
00075 public java.lang.String getMessageDefinition() { return __s_getMessageDefinition(); }
00076
00077 public Range clone() {
00078 Range c = new Range();
00079 c.deserialize(serialize(0));
00080 return c;
00081 }
00082
00083 public void setTo(ros.communication.Message m) {
00084 deserialize(m.serialize(0));
00085 }
00086
00087 public int serializationLength() {
00088 int __l = 0;
00089 __l += header.serializationLength();
00090 __l += 1;
00091 __l += 4;
00092 __l += 4;
00093 __l += 4;
00094 __l += 4;
00095 return __l;
00096 }
00097
00098 public void serialize(ByteBuffer bb, int seq) {
00099 header.serialize(bb, seq);
00100 bb.put((byte)radiation_type);
00101 bb.putFloat(field_of_view);
00102 bb.putFloat(min_range);
00103 bb.putFloat(max_range);
00104 bb.putFloat(range);
00105 }
00106
00107 public void deserialize(ByteBuffer bb) {
00108 header.deserialize(bb);
00109 radiation_type = (short)(bb.get() & 0xff);
00110 field_of_view = bb.getFloat();
00111 min_range = bb.getFloat();
00112 max_range = bb.getFloat();
00113 range = bb.getFloat();
00114 }
00115
00116 @SuppressWarnings("all")
00117 public boolean equals(Object o) {
00118 if(!(o instanceof Range))
00119 return false;
00120 Range other = (Range) o;
00121 return
00122 header.equals(other.header) &&
00123 radiation_type == other.radiation_type &&
00124 field_of_view == other.field_of_view &&
00125 min_range == other.min_range &&
00126 max_range == other.max_range &&
00127 range == other.range &&
00128 true;
00129 }
00130
00131 @SuppressWarnings("all")
00132 public int hashCode() {
00133 final int prime = 31;
00134 int result = 1;
00135 long tmp;
00136 result = prime * result + (this.header == null ? 0 : this.header.hashCode());
00137 result = prime * result + this.radiation_type;
00138 result = prime * result + Float.floatToIntBits(this.field_of_view);
00139 result = prime * result + Float.floatToIntBits(this.min_range);
00140 result = prime * result + Float.floatToIntBits(this.max_range);
00141 result = prime * result + Float.floatToIntBits(this.range);
00142 return result;
00143 }
00144 }
00145