00001
00002
00003 package ros.pkg.sensor_msgs.msg;
00004
00005 import java.nio.ByteBuffer;
00006
00007 public class NavSatFix extends ros.communication.Message {
00008 static public final short COVARIANCE_TYPE_UNKNOWN = 0;
00009 static public final short COVARIANCE_TYPE_APPROXIMATED = 1;
00010 static public final short COVARIANCE_TYPE_DIAGONAL_KNOWN = 2;
00011 static public final short COVARIANCE_TYPE_KNOWN = 3;
00012
00013 public ros.pkg.std_msgs.msg.Header header = new ros.pkg.std_msgs.msg.Header();
00014 public ros.pkg.sensor_msgs.msg.NavSatStatus status = new ros.pkg.sensor_msgs.msg.NavSatStatus();
00015 public double latitude;
00016 public double longitude;
00017 public double altitude;
00018 public double[] position_covariance = new double[9];
00019 public short position_covariance_type;
00020
00021 public NavSatFix() {
00022 }
00023
00024 public static java.lang.String __s_getDataType() { return "sensor_msgs/NavSatFix"; }
00025 public java.lang.String getDataType() { return __s_getDataType(); }
00026 public static java.lang.String __s_getMD5Sum() { return "2d3a8cd499b9b4a0249fb98fd05cfa48"; }
00027 public java.lang.String getMD5Sum() { return __s_getMD5Sum(); }
00028 public static java.lang.String __s_getMessageDefinition() { return "# Navigation Satellite fix for any Global Navigation Satellite System\n" +
00029 "#\n" +
00030 "# Specified using the WGS 84 reference ellipsoid\n" +
00031 "\n" +
00032 "# Header specifies ROS time and frame of reference for this fix.\n" +
00033 "Header header\n" +
00034 "\n" +
00035 "# satellite fix status information\n" +
00036 "sensor_msgs/NavSatStatus status\n" +
00037 "\n" +
00038 "# Latitude [degrees]. Positive is north of equator; negative is south.\n" +
00039 "float64 latitude\n" +
00040 "\n" +
00041 "# Longitude [degrees]. Positive is east of prime meridian; negative is west.\n" +
00042 "float64 longitude\n" +
00043 "\n" +
00044 "# Altitude [m]. Positive is above the WGS 84 ellipsoid.\n" +
00045 "float64 altitude\n" +
00046 "\n" +
00047 "# Position covariance [m^2] defined relative to a tangential plane\n" +
00048 "# through the reported position. The components are East, North, and\n" +
00049 "# Up (ENU), in row-major order.\n" +
00050 "#\n" +
00051 "# Beware: this coordinate system exhibits singularities at the poles.\n" +
00052 "\n" +
00053 "float64[9] position_covariance\n" +
00054 "\n" +
00055 "# If the covariance of the fix is known, fill it in completely. If the\n" +
00056 "# GPS receiver provides the variance of each measurement, put them\n" +
00057 "# along the diagonal. If only Dilution of Precision is available,\n" +
00058 "# estimate an approximate covariance from that.\n" +
00059 "\n" +
00060 "uint8 COVARIANCE_TYPE_UNKNOWN = 0\n" +
00061 "uint8 COVARIANCE_TYPE_APPROXIMATED = 1\n" +
00062 "uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\n" +
00063 "uint8 COVARIANCE_TYPE_KNOWN = 3\n" +
00064 "\n" +
00065 "uint8 position_covariance_type\n" +
00066 "\n" +
00067 "================================================================================\n" +
00068 "MSG: std_msgs/Header\n" +
00069 "# Standard metadata for higher-level stamped data types.\n" +
00070 "# This is generally used to communicate timestamped data \n" +
00071 "# in a particular coordinate frame.\n" +
00072 "# \n" +
00073 "# sequence ID: consecutively increasing ID \n" +
00074 "uint32 seq\n" +
00075 "#Two-integer timestamp that is expressed as:\n" +
00076 "# * stamp.secs: seconds (stamp_secs) since epoch\n" +
00077 "# * stamp.nsecs: nanoseconds since stamp_secs\n" +
00078 "# time-handling sugar is provided by the client library\n" +
00079 "time stamp\n" +
00080 "#Frame this data is associated with\n" +
00081 "# 0: no frame\n" +
00082 "# 1: global frame\n" +
00083 "string frame_id\n" +
00084 "\n" +
00085 "================================================================================\n" +
00086 "MSG: sensor_msgs/NavSatStatus\n" +
00087 "# Navigation Satellite fix status for any Global Navigation Satellite System\n" +
00088 "\n" +
00089 "# Whether to output an augmented fix is determined by both the fix\n" +
00090 "# type and the last time differential corrections were received. A\n" +
00091 "# fix is valid when status >= STATUS_FIX.\n" +
00092 "\n" +
00093 "int8 STATUS_NO_FIX = -1 # unable to fix position\n" +
00094 "int8 STATUS_FIX = 0 # unaugmented fix\n" +
00095 "int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation\n" +
00096 "int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation\n" +
00097 "\n" +
00098 "int8 status\n" +
00099 "\n" +
00100 "# Bits defining which Global Navigation Satellite System signals were\n" +
00101 "# used by the receiver.\n" +
00102 "\n" +
00103 "uint16 SERVICE_GPS = 1\n" +
00104 "uint16 SERVICE_GLONASS = 2\n" +
00105 "uint16 SERVICE_COMPASS = 4 # includes BeiDou.\n" +
00106 "uint16 SERVICE_GALILEO = 8\n" +
00107 "\n" +
00108 "uint16 service\n" +
00109 "\n" +
00110 ""; }
00111 public java.lang.String getMessageDefinition() { return __s_getMessageDefinition(); }
00112
00113 public NavSatFix clone() {
00114 NavSatFix c = new NavSatFix();
00115 c.deserialize(serialize(0));
00116 return c;
00117 }
00118
00119 public void setTo(ros.communication.Message m) {
00120 deserialize(m.serialize(0));
00121 }
00122
00123 public int serializationLength() {
00124 int __l = 0;
00125 __l += header.serializationLength();
00126 __l += status.serializationLength();
00127 __l += 8;
00128 __l += 8;
00129 __l += 8;
00130 __l += 72;
00131 __l += 1;
00132 return __l;
00133 }
00134
00135 public void serialize(ByteBuffer bb, int seq) {
00136 header.serialize(bb, seq);
00137 status.serialize(bb, seq);
00138 bb.putDouble(latitude);
00139 bb.putDouble(longitude);
00140 bb.putDouble(altitude);
00141
00142 for(double val : position_covariance) {
00143 bb.putDouble(val);
00144 }
00145 bb.put((byte)position_covariance_type);
00146 }
00147
00148 public void deserialize(ByteBuffer bb) {
00149 header.deserialize(bb);
00150 status.deserialize(bb);
00151 latitude = bb.getDouble();
00152 longitude = bb.getDouble();
00153 altitude = bb.getDouble();
00154
00155 int __position_covariance_len = position_covariance.length;;
00156 position_covariance = new double[__position_covariance_len];
00157 for(int __i=0; __i<__position_covariance_len; __i++) {
00158 position_covariance[__i] = bb.getDouble();
00159 }
00160 position_covariance_type = (short)(bb.get() & 0xff);
00161 }
00162
00163 @SuppressWarnings("all")
00164 public boolean equals(Object o) {
00165 if(!(o instanceof NavSatFix))
00166 return false;
00167 NavSatFix other = (NavSatFix) o;
00168 return
00169 header.equals(other.header) &&
00170 status.equals(other.status) &&
00171 latitude == other.latitude &&
00172 longitude == other.longitude &&
00173 altitude == other.altitude &&
00174 java.util.Arrays.equals(position_covariance, other.position_covariance) &&
00175 position_covariance_type == other.position_covariance_type &&
00176 true;
00177 }
00178
00179 @SuppressWarnings("all")
00180 public int hashCode() {
00181 final int prime = 31;
00182 int result = 1;
00183 long tmp;
00184 result = prime * result + (this.header == null ? 0 : this.header.hashCode());
00185 result = prime * result + (this.status == null ? 0 : this.status.hashCode());
00186 result = prime * result + (int)((tmp = Double.doubleToLongBits(this.latitude)) ^ (tmp >>> 32));
00187 result = prime * result + (int)((tmp = Double.doubleToLongBits(this.longitude)) ^ (tmp >>> 32));
00188 result = prime * result + (int)((tmp = Double.doubleToLongBits(this.altitude)) ^ (tmp >>> 32));
00189 result = prime * result + java.util.Arrays.hashCode(this.position_covariance);
00190 result = prime * result + this.position_covariance_type;
00191 return result;
00192 }
00193 }
00194