00001 """autogenerated by genmsg_py from CartesianPose.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import brics_actuator.msg
00006 import geometry_msgs.msg
00007 import roslib.rostime
00008
00009 class CartesianPose(roslib.message.Message):
00010 _md5sum = "0fe287468091771914ed98dea2d2a5a5"
00011 _type = "brics_actuator/CartesianPose"
00012 _has_header = False
00013 _full_text = """time timeStamp
00014 Poison poisonStamp
00015 string base_frame_uri
00016 string target_frame_uri
00017 CartesianVector position
00018 geometry_msgs/Quaternion orientation
00019
00020 ================================================================================
00021 MSG: brics_actuator/Poison
00022 string originator # node id
00023 string description # encoding still an issue
00024 float32 qos # reliability of the channel
00025 # 0..1 where 1 means healthy
00026
00027 ================================================================================
00028 MSG: brics_actuator/CartesianVector
00029 string unit
00030 float64 x
00031 float64 y
00032 float64 z
00033
00034 ================================================================================
00035 MSG: geometry_msgs/Quaternion
00036 # This represents an orientation in free space in quaternion form.
00037
00038 float64 x
00039 float64 y
00040 float64 z
00041 float64 w
00042
00043 """
00044 __slots__ = ['timeStamp','poisonStamp','base_frame_uri','target_frame_uri','position','orientation']
00045 _slot_types = ['time','brics_actuator/Poison','string','string','brics_actuator/CartesianVector','geometry_msgs/Quaternion']
00046
00047 def __init__(self, *args, **kwds):
00048 """
00049 Constructor. Any message fields that are implicitly/explicitly
00050 set to None will be assigned a default value. The recommend
00051 use is keyword arguments as this is more robust to future message
00052 changes. You cannot mix in-order arguments and keyword arguments.
00053
00054 The available fields are:
00055 timeStamp,poisonStamp,base_frame_uri,target_frame_uri,position,orientation
00056
00057 @param args: complete set of field values, in .msg order
00058 @param kwds: use keyword arguments corresponding to message field names
00059 to set specific fields.
00060 """
00061 if args or kwds:
00062 super(CartesianPose, self).__init__(*args, **kwds)
00063
00064 if self.timeStamp is None:
00065 self.timeStamp = roslib.rostime.Time()
00066 if self.poisonStamp is None:
00067 self.poisonStamp = brics_actuator.msg.Poison()
00068 if self.base_frame_uri is None:
00069 self.base_frame_uri = ''
00070 if self.target_frame_uri is None:
00071 self.target_frame_uri = ''
00072 if self.position is None:
00073 self.position = brics_actuator.msg.CartesianVector()
00074 if self.orientation is None:
00075 self.orientation = geometry_msgs.msg.Quaternion()
00076 else:
00077 self.timeStamp = roslib.rostime.Time()
00078 self.poisonStamp = brics_actuator.msg.Poison()
00079 self.base_frame_uri = ''
00080 self.target_frame_uri = ''
00081 self.position = brics_actuator.msg.CartesianVector()
00082 self.orientation = geometry_msgs.msg.Quaternion()
00083
00084 def _get_types(self):
00085 """
00086 internal API method
00087 """
00088 return self._slot_types
00089
00090 def serialize(self, buff):
00091 """
00092 serialize message into buffer
00093 @param buff: buffer
00094 @type buff: StringIO
00095 """
00096 try:
00097 _x = self
00098 buff.write(_struct_2I.pack(_x.timeStamp.secs, _x.timeStamp.nsecs))
00099 _x = self.poisonStamp.originator
00100 length = len(_x)
00101 buff.write(struct.pack('<I%ss'%length, length, _x))
00102 _x = self.poisonStamp.description
00103 length = len(_x)
00104 buff.write(struct.pack('<I%ss'%length, length, _x))
00105 buff.write(_struct_f.pack(self.poisonStamp.qos))
00106 _x = self.base_frame_uri
00107 length = len(_x)
00108 buff.write(struct.pack('<I%ss'%length, length, _x))
00109 _x = self.target_frame_uri
00110 length = len(_x)
00111 buff.write(struct.pack('<I%ss'%length, length, _x))
00112 _x = self.position.unit
00113 length = len(_x)
00114 buff.write(struct.pack('<I%ss'%length, length, _x))
00115 _x = self
00116 buff.write(_struct_7d.pack(_x.position.x, _x.position.y, _x.position.z, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w))
00117 except struct.error, se: self._check_types(se)
00118 except TypeError, te: self._check_types(te)
00119
00120 def deserialize(self, str):
00121 """
00122 unpack serialized message in str into this message instance
00123 @param str: byte array of serialized message
00124 @type str: str
00125 """
00126 try:
00127 if self.timeStamp is None:
00128 self.timeStamp = roslib.rostime.Time()
00129 if self.poisonStamp is None:
00130 self.poisonStamp = brics_actuator.msg.Poison()
00131 if self.position is None:
00132 self.position = brics_actuator.msg.CartesianVector()
00133 if self.orientation is None:
00134 self.orientation = geometry_msgs.msg.Quaternion()
00135 end = 0
00136 _x = self
00137 start = end
00138 end += 8
00139 (_x.timeStamp.secs, _x.timeStamp.nsecs,) = _struct_2I.unpack(str[start:end])
00140 start = end
00141 end += 4
00142 (length,) = _struct_I.unpack(str[start:end])
00143 start = end
00144 end += length
00145 self.poisonStamp.originator = str[start:end]
00146 start = end
00147 end += 4
00148 (length,) = _struct_I.unpack(str[start:end])
00149 start = end
00150 end += length
00151 self.poisonStamp.description = str[start:end]
00152 start = end
00153 end += 4
00154 (self.poisonStamp.qos,) = _struct_f.unpack(str[start:end])
00155 start = end
00156 end += 4
00157 (length,) = _struct_I.unpack(str[start:end])
00158 start = end
00159 end += length
00160 self.base_frame_uri = str[start:end]
00161 start = end
00162 end += 4
00163 (length,) = _struct_I.unpack(str[start:end])
00164 start = end
00165 end += length
00166 self.target_frame_uri = str[start:end]
00167 start = end
00168 end += 4
00169 (length,) = _struct_I.unpack(str[start:end])
00170 start = end
00171 end += length
00172 self.position.unit = str[start:end]
00173 _x = self
00174 start = end
00175 end += 56
00176 (_x.position.x, _x.position.y, _x.position.z, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w,) = _struct_7d.unpack(str[start:end])
00177 self.timeStamp.canon()
00178 return self
00179 except struct.error, e:
00180 raise roslib.message.DeserializationError(e)
00181
00182
00183 def serialize_numpy(self, buff, numpy):
00184 """
00185 serialize message with numpy array types into buffer
00186 @param buff: buffer
00187 @type buff: StringIO
00188 @param numpy: numpy python module
00189 @type numpy module
00190 """
00191 try:
00192 _x = self
00193 buff.write(_struct_2I.pack(_x.timeStamp.secs, _x.timeStamp.nsecs))
00194 _x = self.poisonStamp.originator
00195 length = len(_x)
00196 buff.write(struct.pack('<I%ss'%length, length, _x))
00197 _x = self.poisonStamp.description
00198 length = len(_x)
00199 buff.write(struct.pack('<I%ss'%length, length, _x))
00200 buff.write(_struct_f.pack(self.poisonStamp.qos))
00201 _x = self.base_frame_uri
00202 length = len(_x)
00203 buff.write(struct.pack('<I%ss'%length, length, _x))
00204 _x = self.target_frame_uri
00205 length = len(_x)
00206 buff.write(struct.pack('<I%ss'%length, length, _x))
00207 _x = self.position.unit
00208 length = len(_x)
00209 buff.write(struct.pack('<I%ss'%length, length, _x))
00210 _x = self
00211 buff.write(_struct_7d.pack(_x.position.x, _x.position.y, _x.position.z, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w))
00212 except struct.error, se: self._check_types(se)
00213 except TypeError, te: self._check_types(te)
00214
00215 def deserialize_numpy(self, str, numpy):
00216 """
00217 unpack serialized message in str into this message instance using numpy for array types
00218 @param str: byte array of serialized message
00219 @type str: str
00220 @param numpy: numpy python module
00221 @type numpy: module
00222 """
00223 try:
00224 if self.timeStamp is None:
00225 self.timeStamp = roslib.rostime.Time()
00226 if self.poisonStamp is None:
00227 self.poisonStamp = brics_actuator.msg.Poison()
00228 if self.position is None:
00229 self.position = brics_actuator.msg.CartesianVector()
00230 if self.orientation is None:
00231 self.orientation = geometry_msgs.msg.Quaternion()
00232 end = 0
00233 _x = self
00234 start = end
00235 end += 8
00236 (_x.timeStamp.secs, _x.timeStamp.nsecs,) = _struct_2I.unpack(str[start:end])
00237 start = end
00238 end += 4
00239 (length,) = _struct_I.unpack(str[start:end])
00240 start = end
00241 end += length
00242 self.poisonStamp.originator = str[start:end]
00243 start = end
00244 end += 4
00245 (length,) = _struct_I.unpack(str[start:end])
00246 start = end
00247 end += length
00248 self.poisonStamp.description = str[start:end]
00249 start = end
00250 end += 4
00251 (self.poisonStamp.qos,) = _struct_f.unpack(str[start:end])
00252 start = end
00253 end += 4
00254 (length,) = _struct_I.unpack(str[start:end])
00255 start = end
00256 end += length
00257 self.base_frame_uri = str[start:end]
00258 start = end
00259 end += 4
00260 (length,) = _struct_I.unpack(str[start:end])
00261 start = end
00262 end += length
00263 self.target_frame_uri = str[start:end]
00264 start = end
00265 end += 4
00266 (length,) = _struct_I.unpack(str[start:end])
00267 start = end
00268 end += length
00269 self.position.unit = str[start:end]
00270 _x = self
00271 start = end
00272 end += 56
00273 (_x.position.x, _x.position.y, _x.position.z, _x.orientation.x, _x.orientation.y, _x.orientation.z, _x.orientation.w,) = _struct_7d.unpack(str[start:end])
00274 self.timeStamp.canon()
00275 return self
00276 except struct.error, e:
00277 raise roslib.message.DeserializationError(e)
00278
00279 _struct_I = roslib.message.struct_I
00280 _struct_7d = struct.Struct("<7d")
00281 _struct_2I = struct.Struct("<2I")
00282 _struct_f = struct.Struct("<f")