00001
00002
00003 package ros.pkg.sensor_msgs.msg;
00004
00005 import java.nio.ByteBuffer;
00006
00007 public class Imu extends ros.communication.Message {
00008
00009 public ros.pkg.std_msgs.msg.Header header = new ros.pkg.std_msgs.msg.Header();
00010 public ros.pkg.geometry_msgs.msg.Quaternion orientation = new ros.pkg.geometry_msgs.msg.Quaternion();
00011 public double[] orientation_covariance = new double[9];
00012 public ros.pkg.geometry_msgs.msg.Vector3 angular_velocity = new ros.pkg.geometry_msgs.msg.Vector3();
00013 public double[] angular_velocity_covariance = new double[9];
00014 public ros.pkg.geometry_msgs.msg.Vector3 linear_acceleration = new ros.pkg.geometry_msgs.msg.Vector3();
00015 public double[] linear_acceleration_covariance = new double[9];
00016
00017 public Imu() {
00018 }
00019
00020 public static java.lang.String __s_getDataType() { return "sensor_msgs/Imu"; }
00021 public java.lang.String getDataType() { return __s_getDataType(); }
00022 public static java.lang.String __s_getMD5Sum() { return "6a62c6daae103f4ff57a132d6f95cec2"; }
00023 public java.lang.String getMD5Sum() { return __s_getMD5Sum(); }
00024 public static java.lang.String __s_getMessageDefinition() { return "# This is a message to hold data from an IMU (Inertial Measurement Unit)\n" +
00025 "#\n" +
00026 "# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec\n" +
00027 "#\n" +
00028 "# If the covariance of the measurement is known, it should be filled in (if all you know is the variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n" +
00029 "# A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the data a covariance will have to be assumed or gotten from some other source\n" +
00030 "#\n" +
00031 "# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation estimate), please set element 0 of the associated covariance matrix to -1\n" +
00032 "# If you are interpreting this message, please check for a value of -1 in the first element of each covariance matrix, and disregard the associated estimate.\n" +
00033 "\n" +
00034 "Header header\n" +
00035 "\n" +
00036 "geometry_msgs/Quaternion orientation\n" +
00037 "float64[9] orientation_covariance # Row major about x, y, z axes\n" +
00038 "\n" +
00039 "geometry_msgs/Vector3 angular_velocity\n" +
00040 "float64[9] angular_velocity_covariance # Row major about x, y, z axes\n" +
00041 "\n" +
00042 "geometry_msgs/Vector3 linear_acceleration\n" +
00043 "float64[9] linear_acceleration_covariance # Row major x, y z \n" +
00044 "\n" +
00045 "================================================================================\n" +
00046 "MSG: std_msgs/Header\n" +
00047 "# Standard metadata for higher-level stamped data types.\n" +
00048 "# This is generally used to communicate timestamped data \n" +
00049 "# in a particular coordinate frame.\n" +
00050 "# \n" +
00051 "# sequence ID: consecutively increasing ID \n" +
00052 "uint32 seq\n" +
00053 "#Two-integer timestamp that is expressed as:\n" +
00054 "# * stamp.secs: seconds (stamp_secs) since epoch\n" +
00055 "# * stamp.nsecs: nanoseconds since stamp_secs\n" +
00056 "# time-handling sugar is provided by the client library\n" +
00057 "time stamp\n" +
00058 "#Frame this data is associated with\n" +
00059 "# 0: no frame\n" +
00060 "# 1: global frame\n" +
00061 "string frame_id\n" +
00062 "\n" +
00063 "================================================================================\n" +
00064 "MSG: geometry_msgs/Quaternion\n" +
00065 "# This represents an orientation in free space in quaternion form.\n" +
00066 "\n" +
00067 "float64 x\n" +
00068 "float64 y\n" +
00069 "float64 z\n" +
00070 "float64 w\n" +
00071 "\n" +
00072 "================================================================================\n" +
00073 "MSG: geometry_msgs/Vector3\n" +
00074 "# This represents a vector in free space. \n" +
00075 "\n" +
00076 "float64 x\n" +
00077 "float64 y\n" +
00078 "float64 z\n" +
00079 ""; }
00080 public java.lang.String getMessageDefinition() { return __s_getMessageDefinition(); }
00081
00082 public Imu clone() {
00083 Imu c = new Imu();
00084 c.deserialize(serialize(0));
00085 return c;
00086 }
00087
00088 public void setTo(ros.communication.Message m) {
00089 deserialize(m.serialize(0));
00090 }
00091
00092 public int serializationLength() {
00093 int __l = 0;
00094 __l += header.serializationLength();
00095 __l += orientation.serializationLength();
00096 __l += 72;
00097 __l += angular_velocity.serializationLength();
00098 __l += 72;
00099 __l += linear_acceleration.serializationLength();
00100 __l += 72;
00101 return __l;
00102 }
00103
00104 public void serialize(ByteBuffer bb, int seq) {
00105 header.serialize(bb, seq);
00106 orientation.serialize(bb, seq);
00107
00108 for(double val : orientation_covariance) {
00109 bb.putDouble(val);
00110 }
00111 angular_velocity.serialize(bb, seq);
00112
00113 for(double val : angular_velocity_covariance) {
00114 bb.putDouble(val);
00115 }
00116 linear_acceleration.serialize(bb, seq);
00117
00118 for(double val : linear_acceleration_covariance) {
00119 bb.putDouble(val);
00120 }
00121 }
00122
00123 public void deserialize(ByteBuffer bb) {
00124 header.deserialize(bb);
00125 orientation.deserialize(bb);
00126
00127 int __orientation_covariance_len = orientation_covariance.length;;
00128 orientation_covariance = new double[__orientation_covariance_len];
00129 for(int __i=0; __i<__orientation_covariance_len; __i++) {
00130 orientation_covariance[__i] = bb.getDouble();
00131 }
00132 angular_velocity.deserialize(bb);
00133
00134 int __angular_velocity_covariance_len = angular_velocity_covariance.length;;
00135 angular_velocity_covariance = new double[__angular_velocity_covariance_len];
00136 for(int __i=0; __i<__angular_velocity_covariance_len; __i++) {
00137 angular_velocity_covariance[__i] = bb.getDouble();
00138 }
00139 linear_acceleration.deserialize(bb);
00140
00141 int __linear_acceleration_covariance_len = linear_acceleration_covariance.length;;
00142 linear_acceleration_covariance = new double[__linear_acceleration_covariance_len];
00143 for(int __i=0; __i<__linear_acceleration_covariance_len; __i++) {
00144 linear_acceleration_covariance[__i] = bb.getDouble();
00145 }
00146 }
00147
00148 @SuppressWarnings("all")
00149 public boolean equals(Object o) {
00150 if(!(o instanceof Imu))
00151 return false;
00152 Imu other = (Imu) o;
00153 return
00154 header.equals(other.header) &&
00155 orientation.equals(other.orientation) &&
00156 java.util.Arrays.equals(orientation_covariance, other.orientation_covariance) &&
00157 angular_velocity.equals(other.angular_velocity) &&
00158 java.util.Arrays.equals(angular_velocity_covariance, other.angular_velocity_covariance) &&
00159 linear_acceleration.equals(other.linear_acceleration) &&
00160 java.util.Arrays.equals(linear_acceleration_covariance, other.linear_acceleration_covariance) &&
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 + (this.orientation == null ? 0 : this.orientation.hashCode());
00171 result = prime * result + java.util.Arrays.hashCode(this.orientation_covariance);
00172 result = prime * result + (this.angular_velocity == null ? 0 : this.angular_velocity.hashCode());
00173 result = prime * result + java.util.Arrays.hashCode(this.angular_velocity_covariance);
00174 result = prime * result + (this.linear_acceleration == null ? 0 : this.linear_acceleration.hashCode());
00175 result = prime * result + java.util.Arrays.hashCode(this.linear_acceleration_covariance);
00176 return result;
00177 }
00178 }
00179