00001 """autogenerated by genmsg_py from GraphConstraint.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import graph_mapping_msgs.msg
00007
00008 class GraphConstraint(roslib.message.Message):
00009 _md5sum = "9373a29b959ebfb34f1271bdd2b8a95f"
00010 _type = "graph_mapping_msgs/GraphConstraint"
00011 _has_header = False
00012 _full_text = """uint32 src
00013 uint32 dest
00014 PoseWithPrecision constraint
00015 ================================================================================
00016 MSG: graph_mapping_msgs/PoseWithPrecision
00017 geometry_msgs/Pose pose
00018 float64[36] precision
00019 ================================================================================
00020 MSG: geometry_msgs/Pose
00021 # A representation of pose in free space, composed of postion and orientation.
00022 Point position
00023 Quaternion orientation
00024
00025 ================================================================================
00026 MSG: geometry_msgs/Point
00027 # This contains the position of a point in free space
00028 float64 x
00029 float64 y
00030 float64 z
00031
00032 ================================================================================
00033 MSG: geometry_msgs/Quaternion
00034 # This represents an orientation in free space in quaternion form.
00035
00036 float64 x
00037 float64 y
00038 float64 z
00039 float64 w
00040
00041 """
00042 __slots__ = ['src','dest','constraint']
00043 _slot_types = ['uint32','uint32','graph_mapping_msgs/PoseWithPrecision']
00044
00045 def __init__(self, *args, **kwds):
00046 """
00047 Constructor. Any message fields that are implicitly/explicitly
00048 set to None will be assigned a default value. The recommend
00049 use is keyword arguments as this is more robust to future message
00050 changes. You cannot mix in-order arguments and keyword arguments.
00051
00052 The available fields are:
00053 src,dest,constraint
00054
00055 @param args: complete set of field values, in .msg order
00056 @param kwds: use keyword arguments corresponding to message field names
00057 to set specific fields.
00058 """
00059 if args or kwds:
00060 super(GraphConstraint, self).__init__(*args, **kwds)
00061
00062 if self.src is None:
00063 self.src = 0
00064 if self.dest is None:
00065 self.dest = 0
00066 if self.constraint is None:
00067 self.constraint = graph_mapping_msgs.msg.PoseWithPrecision()
00068 else:
00069 self.src = 0
00070 self.dest = 0
00071 self.constraint = graph_mapping_msgs.msg.PoseWithPrecision()
00072
00073 def _get_types(self):
00074 """
00075 internal API method
00076 """
00077 return self._slot_types
00078
00079 def serialize(self, buff):
00080 """
00081 serialize message into buffer
00082 @param buff: buffer
00083 @type buff: StringIO
00084 """
00085 try:
00086 _x = self
00087 buff.write(_struct_2I7d.pack(_x.src, _x.dest, _x.constraint.pose.position.x, _x.constraint.pose.position.y, _x.constraint.pose.position.z, _x.constraint.pose.orientation.x, _x.constraint.pose.orientation.y, _x.constraint.pose.orientation.z, _x.constraint.pose.orientation.w))
00088 buff.write(_struct_36d.pack(*self.constraint.precision))
00089 except struct.error, se: self._check_types(se)
00090 except TypeError, te: self._check_types(te)
00091
00092 def deserialize(self, str):
00093 """
00094 unpack serialized message in str into this message instance
00095 @param str: byte array of serialized message
00096 @type str: str
00097 """
00098 try:
00099 if self.constraint is None:
00100 self.constraint = graph_mapping_msgs.msg.PoseWithPrecision()
00101 end = 0
00102 _x = self
00103 start = end
00104 end += 64
00105 (_x.src, _x.dest, _x.constraint.pose.position.x, _x.constraint.pose.position.y, _x.constraint.pose.position.z, _x.constraint.pose.orientation.x, _x.constraint.pose.orientation.y, _x.constraint.pose.orientation.z, _x.constraint.pose.orientation.w,) = _struct_2I7d.unpack(str[start:end])
00106 start = end
00107 end += 288
00108 self.constraint.precision = _struct_36d.unpack(str[start:end])
00109 return self
00110 except struct.error, e:
00111 raise roslib.message.DeserializationError(e)
00112
00113
00114 def serialize_numpy(self, buff, numpy):
00115 """
00116 serialize message with numpy array types into buffer
00117 @param buff: buffer
00118 @type buff: StringIO
00119 @param numpy: numpy python module
00120 @type numpy module
00121 """
00122 try:
00123 _x = self
00124 buff.write(_struct_2I7d.pack(_x.src, _x.dest, _x.constraint.pose.position.x, _x.constraint.pose.position.y, _x.constraint.pose.position.z, _x.constraint.pose.orientation.x, _x.constraint.pose.orientation.y, _x.constraint.pose.orientation.z, _x.constraint.pose.orientation.w))
00125 buff.write(self.constraint.precision.tostring())
00126 except struct.error, se: self._check_types(se)
00127 except TypeError, te: self._check_types(te)
00128
00129 def deserialize_numpy(self, str, numpy):
00130 """
00131 unpack serialized message in str into this message instance using numpy for array types
00132 @param str: byte array of serialized message
00133 @type str: str
00134 @param numpy: numpy python module
00135 @type numpy: module
00136 """
00137 try:
00138 if self.constraint is None:
00139 self.constraint = graph_mapping_msgs.msg.PoseWithPrecision()
00140 end = 0
00141 _x = self
00142 start = end
00143 end += 64
00144 (_x.src, _x.dest, _x.constraint.pose.position.x, _x.constraint.pose.position.y, _x.constraint.pose.position.z, _x.constraint.pose.orientation.x, _x.constraint.pose.orientation.y, _x.constraint.pose.orientation.z, _x.constraint.pose.orientation.w,) = _struct_2I7d.unpack(str[start:end])
00145 start = end
00146 end += 288
00147 self.constraint.precision = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36)
00148 return self
00149 except struct.error, e:
00150 raise roslib.message.DeserializationError(e)
00151
00152 _struct_I = roslib.message.struct_I
00153 _struct_36d = struct.Struct("<36d")
00154 _struct_2I7d = struct.Struct("<2I7d")