00001 """autogenerated by genpy from gazebo_msgs/ApplyBodyWrenchRequest.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 genpy
00009
00010 class ApplyBodyWrenchRequest(genpy.Message):
00011 _md5sum = "e37e6adf97eba5095baa77dffb71e5bd"
00012 _type = "gazebo_msgs/ApplyBodyWrenchRequest"
00013 _has_header = False
00014 _full_text = """
00015
00016
00017 string body_name
00018
00019
00020 string reference_frame
00021
00022
00023 geometry_msgs/Point reference_point
00024 geometry_msgs/Wrench wrench
00025 time start_time
00026
00027
00028 duration duration
00029
00030
00031
00032
00033
00034 ================================================================================
00035 MSG: geometry_msgs/Point
00036 # This contains the position of a point in free space
00037 float64 x
00038 float64 y
00039 float64 z
00040
00041 ================================================================================
00042 MSG: geometry_msgs/Wrench
00043 # This represents force in free space, separated into
00044 # its linear and angular parts.
00045 Vector3 force
00046 Vector3 torque
00047
00048 ================================================================================
00049 MSG: geometry_msgs/Vector3
00050 # This represents a vector in free space.
00051
00052 float64 x
00053 float64 y
00054 float64 z
00055 """
00056 __slots__ = ['body_name','reference_frame','reference_point','wrench','start_time','duration']
00057 _slot_types = ['string','string','geometry_msgs/Point','geometry_msgs/Wrench','time','duration']
00058
00059 def __init__(self, *args, **kwds):
00060 """
00061 Constructor. Any message fields that are implicitly/explicitly
00062 set to None will be assigned a default value. The recommend
00063 use is keyword arguments as this is more robust to future message
00064 changes. You cannot mix in-order arguments and keyword arguments.
00065
00066 The available fields are:
00067 body_name,reference_frame,reference_point,wrench,start_time,duration
00068
00069 :param args: complete set of field values, in .msg order
00070 :param kwds: use keyword arguments corresponding to message field names
00071 to set specific fields.
00072 """
00073 if args or kwds:
00074 super(ApplyBodyWrenchRequest, self).__init__(*args, **kwds)
00075
00076 if self.body_name is None:
00077 self.body_name = ''
00078 if self.reference_frame is None:
00079 self.reference_frame = ''
00080 if self.reference_point is None:
00081 self.reference_point = geometry_msgs.msg.Point()
00082 if self.wrench is None:
00083 self.wrench = geometry_msgs.msg.Wrench()
00084 if self.start_time is None:
00085 self.start_time = genpy.Time()
00086 if self.duration is None:
00087 self.duration = genpy.Duration()
00088 else:
00089 self.body_name = ''
00090 self.reference_frame = ''
00091 self.reference_point = geometry_msgs.msg.Point()
00092 self.wrench = geometry_msgs.msg.Wrench()
00093 self.start_time = genpy.Time()
00094 self.duration = genpy.Duration()
00095
00096 def _get_types(self):
00097 """
00098 internal API method
00099 """
00100 return self._slot_types
00101
00102 def serialize(self, buff):
00103 """
00104 serialize message into buffer
00105 :param buff: buffer, ``StringIO``
00106 """
00107 try:
00108 _x = self.body_name
00109 length = len(_x)
00110 if python3 or type(_x) == unicode:
00111 _x = _x.encode('utf-8')
00112 length = len(_x)
00113 buff.write(struct.pack('<I%ss'%length, length, _x))
00114 _x = self.reference_frame
00115 length = len(_x)
00116 if python3 or type(_x) == unicode:
00117 _x = _x.encode('utf-8')
00118 length = len(_x)
00119 buff.write(struct.pack('<I%ss'%length, length, _x))
00120 _x = self
00121 buff.write(_struct_9d2I2i.pack(_x.reference_point.x, _x.reference_point.y, _x.reference_point.z, _x.wrench.force.x, _x.wrench.force.y, _x.wrench.force.z, _x.wrench.torque.x, _x.wrench.torque.y, _x.wrench.torque.z, _x.start_time.secs, _x.start_time.nsecs, _x.duration.secs, _x.duration.nsecs))
00122 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00123 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00124
00125 def deserialize(self, str):
00126 """
00127 unpack serialized message in str into this message instance
00128 :param str: byte array of serialized message, ``str``
00129 """
00130 try:
00131 if self.reference_point is None:
00132 self.reference_point = geometry_msgs.msg.Point()
00133 if self.wrench is None:
00134 self.wrench = geometry_msgs.msg.Wrench()
00135 if self.start_time is None:
00136 self.start_time = genpy.Time()
00137 if self.duration is None:
00138 self.duration = genpy.Duration()
00139 end = 0
00140 start = end
00141 end += 4
00142 (length,) = _struct_I.unpack(str[start:end])
00143 start = end
00144 end += length
00145 if python3:
00146 self.body_name = str[start:end].decode('utf-8')
00147 else:
00148 self.body_name = str[start:end]
00149 start = end
00150 end += 4
00151 (length,) = _struct_I.unpack(str[start:end])
00152 start = end
00153 end += length
00154 if python3:
00155 self.reference_frame = str[start:end].decode('utf-8')
00156 else:
00157 self.reference_frame = str[start:end]
00158 _x = self
00159 start = end
00160 end += 88
00161 (_x.reference_point.x, _x.reference_point.y, _x.reference_point.z, _x.wrench.force.x, _x.wrench.force.y, _x.wrench.force.z, _x.wrench.torque.x, _x.wrench.torque.y, _x.wrench.torque.z, _x.start_time.secs, _x.start_time.nsecs, _x.duration.secs, _x.duration.nsecs,) = _struct_9d2I2i.unpack(str[start:end])
00162 self.start_time.canon()
00163 self.duration.canon()
00164 return self
00165 except struct.error as e:
00166 raise genpy.DeserializationError(e)
00167
00168
00169 def serialize_numpy(self, buff, numpy):
00170 """
00171 serialize message with numpy array types into buffer
00172 :param buff: buffer, ``StringIO``
00173 :param numpy: numpy python module
00174 """
00175 try:
00176 _x = self.body_name
00177 length = len(_x)
00178 if python3 or type(_x) == unicode:
00179 _x = _x.encode('utf-8')
00180 length = len(_x)
00181 buff.write(struct.pack('<I%ss'%length, length, _x))
00182 _x = self.reference_frame
00183 length = len(_x)
00184 if python3 or type(_x) == unicode:
00185 _x = _x.encode('utf-8')
00186 length = len(_x)
00187 buff.write(struct.pack('<I%ss'%length, length, _x))
00188 _x = self
00189 buff.write(_struct_9d2I2i.pack(_x.reference_point.x, _x.reference_point.y, _x.reference_point.z, _x.wrench.force.x, _x.wrench.force.y, _x.wrench.force.z, _x.wrench.torque.x, _x.wrench.torque.y, _x.wrench.torque.z, _x.start_time.secs, _x.start_time.nsecs, _x.duration.secs, _x.duration.nsecs))
00190 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00191 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00192
00193 def deserialize_numpy(self, str, numpy):
00194 """
00195 unpack serialized message in str into this message instance using numpy for array types
00196 :param str: byte array of serialized message, ``str``
00197 :param numpy: numpy python module
00198 """
00199 try:
00200 if self.reference_point is None:
00201 self.reference_point = geometry_msgs.msg.Point()
00202 if self.wrench is None:
00203 self.wrench = geometry_msgs.msg.Wrench()
00204 if self.start_time is None:
00205 self.start_time = genpy.Time()
00206 if self.duration is None:
00207 self.duration = genpy.Duration()
00208 end = 0
00209 start = end
00210 end += 4
00211 (length,) = _struct_I.unpack(str[start:end])
00212 start = end
00213 end += length
00214 if python3:
00215 self.body_name = str[start:end].decode('utf-8')
00216 else:
00217 self.body_name = str[start:end]
00218 start = end
00219 end += 4
00220 (length,) = _struct_I.unpack(str[start:end])
00221 start = end
00222 end += length
00223 if python3:
00224 self.reference_frame = str[start:end].decode('utf-8')
00225 else:
00226 self.reference_frame = str[start:end]
00227 _x = self
00228 start = end
00229 end += 88
00230 (_x.reference_point.x, _x.reference_point.y, _x.reference_point.z, _x.wrench.force.x, _x.wrench.force.y, _x.wrench.force.z, _x.wrench.torque.x, _x.wrench.torque.y, _x.wrench.torque.z, _x.start_time.secs, _x.start_time.nsecs, _x.duration.secs, _x.duration.nsecs,) = _struct_9d2I2i.unpack(str[start:end])
00231 self.start_time.canon()
00232 self.duration.canon()
00233 return self
00234 except struct.error as e:
00235 raise genpy.DeserializationError(e)
00236
00237 _struct_I = genpy.struct_I
00238 _struct_9d2I2i = struct.Struct("<9d2I2i")
00239 """autogenerated by genpy from gazebo_msgs/ApplyBodyWrenchResponse.msg. Do not edit."""
00240 import sys
00241 python3 = True if sys.hexversion > 0x03000000 else False
00242 import genpy
00243 import struct
00244
00245
00246 class ApplyBodyWrenchResponse(genpy.Message):
00247 _md5sum = "2ec6f3eff0161f4257b808b12bc830c2"
00248 _type = "gazebo_msgs/ApplyBodyWrenchResponse"
00249 _has_header = False
00250 _full_text = """bool success
00251 string status_message
00252
00253
00254 """
00255 __slots__ = ['success','status_message']
00256 _slot_types = ['bool','string']
00257
00258 def __init__(self, *args, **kwds):
00259 """
00260 Constructor. Any message fields that are implicitly/explicitly
00261 set to None will be assigned a default value. The recommend
00262 use is keyword arguments as this is more robust to future message
00263 changes. You cannot mix in-order arguments and keyword arguments.
00264
00265 The available fields are:
00266 success,status_message
00267
00268 :param args: complete set of field values, in .msg order
00269 :param kwds: use keyword arguments corresponding to message field names
00270 to set specific fields.
00271 """
00272 if args or kwds:
00273 super(ApplyBodyWrenchResponse, self).__init__(*args, **kwds)
00274
00275 if self.success is None:
00276 self.success = False
00277 if self.status_message is None:
00278 self.status_message = ''
00279 else:
00280 self.success = False
00281 self.status_message = ''
00282
00283 def _get_types(self):
00284 """
00285 internal API method
00286 """
00287 return self._slot_types
00288
00289 def serialize(self, buff):
00290 """
00291 serialize message into buffer
00292 :param buff: buffer, ``StringIO``
00293 """
00294 try:
00295 buff.write(_struct_B.pack(self.success))
00296 _x = self.status_message
00297 length = len(_x)
00298 if python3 or type(_x) == unicode:
00299 _x = _x.encode('utf-8')
00300 length = len(_x)
00301 buff.write(struct.pack('<I%ss'%length, length, _x))
00302 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00303 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00304
00305 def deserialize(self, str):
00306 """
00307 unpack serialized message in str into this message instance
00308 :param str: byte array of serialized message, ``str``
00309 """
00310 try:
00311 end = 0
00312 start = end
00313 end += 1
00314 (self.success,) = _struct_B.unpack(str[start:end])
00315 self.success = bool(self.success)
00316 start = end
00317 end += 4
00318 (length,) = _struct_I.unpack(str[start:end])
00319 start = end
00320 end += length
00321 if python3:
00322 self.status_message = str[start:end].decode('utf-8')
00323 else:
00324 self.status_message = str[start:end]
00325 return self
00326 except struct.error as e:
00327 raise genpy.DeserializationError(e)
00328
00329
00330 def serialize_numpy(self, buff, numpy):
00331 """
00332 serialize message with numpy array types into buffer
00333 :param buff: buffer, ``StringIO``
00334 :param numpy: numpy python module
00335 """
00336 try:
00337 buff.write(_struct_B.pack(self.success))
00338 _x = self.status_message
00339 length = len(_x)
00340 if python3 or type(_x) == unicode:
00341 _x = _x.encode('utf-8')
00342 length = len(_x)
00343 buff.write(struct.pack('<I%ss'%length, length, _x))
00344 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00345 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00346
00347 def deserialize_numpy(self, str, numpy):
00348 """
00349 unpack serialized message in str into this message instance using numpy for array types
00350 :param str: byte array of serialized message, ``str``
00351 :param numpy: numpy python module
00352 """
00353 try:
00354 end = 0
00355 start = end
00356 end += 1
00357 (self.success,) = _struct_B.unpack(str[start:end])
00358 self.success = bool(self.success)
00359 start = end
00360 end += 4
00361 (length,) = _struct_I.unpack(str[start:end])
00362 start = end
00363 end += length
00364 if python3:
00365 self.status_message = str[start:end].decode('utf-8')
00366 else:
00367 self.status_message = str[start:end]
00368 return self
00369 except struct.error as e:
00370 raise genpy.DeserializationError(e)
00371
00372 _struct_I = genpy.struct_I
00373 _struct_B = struct.Struct("<B")
00374 class ApplyBodyWrench(object):
00375 _type = 'gazebo_msgs/ApplyBodyWrench'
00376 _md5sum = '585b9f9618aa0581b207e2f2d90866bc'
00377 _request_class = ApplyBodyWrenchRequest
00378 _response_class = ApplyBodyWrenchResponse