00001 """autogenerated by genpy from arm_navigation_msgs/OrientationConstraint.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006
00007 import geometry_msgs.msg
00008 import std_msgs.msg
00009
00010 class OrientationConstraint(genpy.Message):
00011 _md5sum = "27d99749ba49d4a822298bbd1e0988ba"
00012 _type = "arm_navigation_msgs/OrientationConstraint"
00013 _has_header = True
00014 _full_text = """# This message contains the definition of an orientation constraint.
00015 Header header
00016
00017 # The robot link this constraint refers to
00018 string link_name
00019
00020 # The type of the constraint
00021 int32 type
00022 int32 LINK_FRAME=0
00023 int32 HEADER_FRAME=1
00024
00025 # The desired orientation of the robot link specified as a quaternion
00026 geometry_msgs/Quaternion orientation
00027
00028 # optional RPY error tolerances specified if
00029 float64 absolute_roll_tolerance
00030 float64 absolute_pitch_tolerance
00031 float64 absolute_yaw_tolerance
00032
00033 # Constraint weighting factor - a weight for this constraint
00034 float64 weight
00035
00036 ================================================================================
00037 MSG: std_msgs/Header
00038 # Standard metadata for higher-level stamped data types.
00039 # This is generally used to communicate timestamped data
00040 # in a particular coordinate frame.
00041 #
00042 # sequence ID: consecutively increasing ID
00043 uint32 seq
00044 #Two-integer timestamp that is expressed as:
00045 # * stamp.secs: seconds (stamp_secs) since epoch
00046 # * stamp.nsecs: nanoseconds since stamp_secs
00047 # time-handling sugar is provided by the client library
00048 time stamp
00049 #Frame this data is associated with
00050 # 0: no frame
00051 # 1: global frame
00052 string frame_id
00053
00054 ================================================================================
00055 MSG: geometry_msgs/Quaternion
00056 # This represents an orientation in free space in quaternion form.
00057
00058 float64 x
00059 float64 y
00060 float64 z
00061 float64 w
00062
00063 """
00064
00065 LINK_FRAME = 0
00066 HEADER_FRAME = 1
00067
00068 __slots__ = ['header','link_name','type','orientation','absolute_roll_tolerance','absolute_pitch_tolerance','absolute_yaw_tolerance','weight']
00069 _slot_types = ['std_msgs/Header','string','int32','geometry_msgs/Quaternion','float64','float64','float64','float64']
00070
00071 def __init__(self, *args, **kwds):
00072 """
00073 Constructor. Any message fields that are implicitly/explicitly
00074 set to None will be assigned a default value. The recommend
00075 use is keyword arguments as this is more robust to future message
00076 changes. You cannot mix in-order arguments and keyword arguments.
00077
00078 The available fields are:
00079 header,link_name,type,orientation,absolute_roll_tolerance,absolute_pitch_tolerance,absolute_yaw_tolerance,weight
00080
00081 :param args: complete set of field values, in .msg order
00082 :param kwds: use keyword arguments corresponding to message field names
00083 to set specific fields.
00084 """
00085 if args or kwds:
00086 super(OrientationConstraint, self).__init__(*args, **kwds)
00087
00088 if self.header is None:
00089 self.header = std_msgs.msg.Header()
00090 if self.link_name is None:
00091 self.link_name = ''
00092 if self.type is None:
00093 self.type = 0
00094 if self.orientation is None:
00095 self.orientation = geometry_msgs.msg.Quaternion()
00096 if self.absolute_roll_tolerance is None:
00097 self.absolute_roll_tolerance = 0.
00098 if self.absolute_pitch_tolerance is None:
00099 self.absolute_pitch_tolerance = 0.
00100 if self.absolute_yaw_tolerance is None:
00101 self.absolute_yaw_tolerance = 0.
00102 if self.weight is None:
00103 self.weight = 0.
00104 else:
00105 self.header = std_msgs.msg.Header()
00106 self.link_name = ''
00107 self.type = 0
00108 self.orientation = geometry_msgs.msg.Quaternion()
00109 self.absolute_roll_tolerance = 0.
00110 self.absolute_pitch_tolerance = 0.
00111 self.absolute_yaw_tolerance = 0.
00112 self.weight = 0.
00113
00114 def _get_types(self):
00115 """
00116 internal API method
00117 """
00118 return self._slot_types
00119
00120 def serialize(self, buff):
00121 """
00122 serialize message into buffer
00123 :param buff: buffer, ``StringIO``
00124 """
00125 try:
00126 _x = self
00127 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00128 _x = self.header.frame_id
00129 length = len(_x)
00130 if python3 or type(_x) == unicode:
00131 _x = _x.encode('utf-8')
00132 length = len(_x)
00133 buff.write(struct.pack('<I%ss'%length, length, _x))
00134 _x = self.link_name
00135 length = len(_x)
00136 if python3 or type(_x) == unicode:
00137 _x = _x.encode('utf-8')
00138 length = len(_x)
00139 buff.write(struct.pack('<I%ss'%length, length, _x))
00140 _x = self
00141 buff.write(_struct_i8d.pack(_x.type, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w, _x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00142 except struct.error as se: self._check_types(se)
00143 except TypeError as te: self._check_types(te)
00144
00145 def deserialize(self, str):
00146 """
00147 unpack serialized message in str into this message instance
00148 :param str: byte array of serialized message, ``str``
00149 """
00150 try:
00151 if self.header is None:
00152 self.header = std_msgs.msg.Header()
00153 if self.orientation is None:
00154 self.orientation = geometry_msgs.msg.Quaternion()
00155 end = 0
00156 _x = self
00157 start = end
00158 end += 12
00159 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00160 start = end
00161 end += 4
00162 (length,) = _struct_I.unpack(str[start:end])
00163 start = end
00164 end += length
00165 if python3:
00166 self.header.frame_id = str[start:end].decode('utf-8')
00167 else:
00168 self.header.frame_id = str[start:end]
00169 start = end
00170 end += 4
00171 (length,) = _struct_I.unpack(str[start:end])
00172 start = end
00173 end += length
00174 if python3:
00175 self.link_name = str[start:end].decode('utf-8')
00176 else:
00177 self.link_name = str[start:end]
00178 _x = self
00179 start = end
00180 end += 68
00181 (_x.type, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w, _x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_i8d.unpack(str[start:end])
00182 return self
00183 except struct.error as e:
00184 raise genpy.DeserializationError(e)
00185
00186
00187 def serialize_numpy(self, buff, numpy):
00188 """
00189 serialize message with numpy array types into buffer
00190 :param buff: buffer, ``StringIO``
00191 :param numpy: numpy python module
00192 """
00193 try:
00194 _x = self
00195 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00196 _x = self.header.frame_id
00197 length = len(_x)
00198 if python3 or type(_x) == unicode:
00199 _x = _x.encode('utf-8')
00200 length = len(_x)
00201 buff.write(struct.pack('<I%ss'%length, length, _x))
00202 _x = self.link_name
00203 length = len(_x)
00204 if python3 or type(_x) == unicode:
00205 _x = _x.encode('utf-8')
00206 length = len(_x)
00207 buff.write(struct.pack('<I%ss'%length, length, _x))
00208 _x = self
00209 buff.write(_struct_i8d.pack(_x.type, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w, _x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight))
00210 except struct.error as se: self._check_types(se)
00211 except TypeError as te: self._check_types(te)
00212
00213 def deserialize_numpy(self, str, numpy):
00214 """
00215 unpack serialized message in str into this message instance using numpy for array types
00216 :param str: byte array of serialized message, ``str``
00217 :param numpy: numpy python module
00218 """
00219 try:
00220 if self.header is None:
00221 self.header = std_msgs.msg.Header()
00222 if self.orientation is None:
00223 self.orientation = geometry_msgs.msg.Quaternion()
00224 end = 0
00225 _x = self
00226 start = end
00227 end += 12
00228 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00229 start = end
00230 end += 4
00231 (length,) = _struct_I.unpack(str[start:end])
00232 start = end
00233 end += length
00234 if python3:
00235 self.header.frame_id = str[start:end].decode('utf-8')
00236 else:
00237 self.header.frame_id = str[start:end]
00238 start = end
00239 end += 4
00240 (length,) = _struct_I.unpack(str[start:end])
00241 start = end
00242 end += length
00243 if python3:
00244 self.link_name = str[start:end].decode('utf-8')
00245 else:
00246 self.link_name = str[start:end]
00247 _x = self
00248 start = end
00249 end += 68
00250 (_x.type, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w, _x.absolute_roll_tolerance, _x.absolute_pitch_tolerance, _x.absolute_yaw_tolerance, _x.weight,) = _struct_i8d.unpack(str[start:end])
00251 return self
00252 except struct.error as e:
00253 raise genpy.DeserializationError(e)
00254
00255 _struct_I = genpy.struct_I
00256 _struct_3I = struct.Struct("<3I")
00257 _struct_i8d = struct.Struct("<i8d")