00001
00002
00003 package ros.pkg.geometry_msgs.msg;
00004
00005 import java.nio.ByteBuffer;
00006
00007 public class PoseWithCovariance extends ros.communication.Message {
00008
00009 public ros.pkg.geometry_msgs.msg.Pose pose = new ros.pkg.geometry_msgs.msg.Pose();
00010 public double[] covariance = new double[36];
00011
00012 public PoseWithCovariance() {
00013 }
00014
00015 public static java.lang.String __s_getDataType() { return "geometry_msgs/PoseWithCovariance"; }
00016 public java.lang.String getDataType() { return __s_getDataType(); }
00017 public static java.lang.String __s_getMD5Sum() { return "c23e848cf1b7533a8d7c259073a97e6f"; }
00018 public java.lang.String getMD5Sum() { return __s_getMD5Sum(); }
00019 public static java.lang.String __s_getMessageDefinition() { return "# This represents a pose in free space with uncertainty.\n" +
00020 "\n" +
00021 "Pose pose\n" +
00022 "\n" +
00023 "# Row-major representation of the 6x6 covariance matrix\n" +
00024 "# The orientation parameters use a fixed-axis representation.\n" +
00025 "# In order, the parameters are:\n" +
00026 "# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n" +
00027 "float64[36] covariance\n" +
00028 "\n" +
00029 "================================================================================\n" +
00030 "MSG: geometry_msgs/Pose\n" +
00031 "# A representation of pose in free space, composed of postion and orientation. \n" +
00032 "Point position\n" +
00033 "Quaternion orientation\n" +
00034 "\n" +
00035 "================================================================================\n" +
00036 "MSG: geometry_msgs/Point\n" +
00037 "# This contains the position of a point in free space\n" +
00038 "float64 x\n" +
00039 "float64 y\n" +
00040 "float64 z\n" +
00041 "\n" +
00042 "================================================================================\n" +
00043 "MSG: geometry_msgs/Quaternion\n" +
00044 "# This represents an orientation in free space in quaternion form.\n" +
00045 "\n" +
00046 "float64 x\n" +
00047 "float64 y\n" +
00048 "float64 z\n" +
00049 "float64 w\n" +
00050 "\n" +
00051 ""; }
00052 public java.lang.String getMessageDefinition() { return __s_getMessageDefinition(); }
00053
00054 public PoseWithCovariance clone() {
00055 PoseWithCovariance c = new PoseWithCovariance();
00056 c.deserialize(serialize(0));
00057 return c;
00058 }
00059
00060 public void setTo(ros.communication.Message m) {
00061 deserialize(m.serialize(0));
00062 }
00063
00064 public int serializationLength() {
00065 int __l = 0;
00066 __l += pose.serializationLength();
00067 __l += 288;
00068 return __l;
00069 }
00070
00071 public void serialize(ByteBuffer bb, int seq) {
00072 pose.serialize(bb, seq);
00073
00074 for(double val : covariance) {
00075 bb.putDouble(val);
00076 }
00077 }
00078
00079 public void deserialize(ByteBuffer bb) {
00080 pose.deserialize(bb);
00081
00082 int __covariance_len = covariance.length;;
00083 covariance = new double[__covariance_len];
00084 for(int __i=0; __i<__covariance_len; __i++) {
00085 covariance[__i] = bb.getDouble();
00086 }
00087 }
00088
00089 @SuppressWarnings("all")
00090 public boolean equals(Object o) {
00091 if(!(o instanceof PoseWithCovariance))
00092 return false;
00093 PoseWithCovariance other = (PoseWithCovariance) o;
00094 return
00095 pose.equals(other.pose) &&
00096 java.util.Arrays.equals(covariance, other.covariance) &&
00097 true;
00098 }
00099
00100 @SuppressWarnings("all")
00101 public int hashCode() {
00102 final int prime = 31;
00103 int result = 1;
00104 long tmp;
00105 result = prime * result + (this.pose == null ? 0 : this.pose.hashCode());
00106 result = prime * result + java.util.Arrays.hashCode(this.covariance);
00107 return result;
00108 }
00109 }
00110