00001 """autogenerated by genmsg_py from SetPoseRequest.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import nav_msgs.msg
00007 import std_msgs.msg
00008
00009 class SetPoseRequest(roslib.message.Message):
00010 _md5sum = "b2e3e5bc60333d71aad6db9918c64b22"
00011 _type = "gazebo_plugins/SetPoseRequest"
00012 _has_header = False
00013 _full_text = """nav_msgs/Odometry pose
00014
00015 ================================================================================
00016 MSG: nav_msgs/Odometry
00017 # This represents an estimate of a position and velocity in free space.
00018 # The pose in this message should be specified in the coordinate frame given by header.frame_id.
00019 # The twist in this message should be specified in the coordinate frame given by the child_frame_id
00020 Header header
00021 string child_frame_id
00022 geometry_msgs/PoseWithCovariance pose
00023 geometry_msgs/TwistWithCovariance twist
00024
00025 ================================================================================
00026 MSG: std_msgs/Header
00027 # Standard metadata for higher-level stamped data types.
00028 # This is generally used to communicate timestamped data
00029 # in a particular coordinate frame.
00030 #
00031 # sequence ID: consecutively increasing ID
00032 uint32 seq
00033 #Two-integer timestamp that is expressed as:
00034 # * stamp.secs: seconds (stamp_secs) since epoch
00035 # * stamp.nsecs: nanoseconds since stamp_secs
00036 # time-handling sugar is provided by the client library
00037 time stamp
00038 #Frame this data is associated with
00039 # 0: no frame
00040 # 1: global frame
00041 string frame_id
00042
00043 ================================================================================
00044 MSG: geometry_msgs/PoseWithCovariance
00045 # This represents a pose in free space with uncertainty.
00046
00047 Pose pose
00048
00049 # Row-major representation of the 6x6 covariance matrix
00050 # The orientation parameters use a fixed-axis representation.
00051 # In order, the parameters are:
00052 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
00053 float64[36] covariance
00054
00055 ================================================================================
00056 MSG: geometry_msgs/Pose
00057 # A representation of pose in free space, composed of postion and orientation.
00058 Point position
00059 Quaternion orientation
00060
00061 ================================================================================
00062 MSG: geometry_msgs/Point
00063 # This contains the position of a point in free space
00064 float64 x
00065 float64 y
00066 float64 z
00067
00068 ================================================================================
00069 MSG: geometry_msgs/Quaternion
00070 # This represents an orientation in free space in quaternion form.
00071
00072 float64 x
00073 float64 y
00074 float64 z
00075 float64 w
00076
00077 ================================================================================
00078 MSG: geometry_msgs/TwistWithCovariance
00079 # This expresses velocity in free space with uncertianty.
00080
00081 Twist twist
00082
00083 # Row-major representation of the 6x6 covariance matrix
00084 # The orientation parameters use a fixed-axis representation.
00085 # In order, the parameters are:
00086 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)
00087 float64[36] covariance
00088
00089 ================================================================================
00090 MSG: geometry_msgs/Twist
00091 # This expresses velocity in free space broken into it's linear and angular parts.
00092 Vector3 linear
00093 Vector3 angular
00094
00095 ================================================================================
00096 MSG: geometry_msgs/Vector3
00097 # This represents a vector in free space.
00098
00099 float64 x
00100 float64 y
00101 float64 z
00102 """
00103 __slots__ = ['pose']
00104 _slot_types = ['nav_msgs/Odometry']
00105
00106 def __init__(self, *args, **kwds):
00107 """
00108 Constructor. Any message fields that are implicitly/explicitly
00109 set to None will be assigned a default value. The recommend
00110 use is keyword arguments as this is more robust to future message
00111 changes. You cannot mix in-order arguments and keyword arguments.
00112
00113 The available fields are:
00114 pose
00115
00116 @param args: complete set of field values, in .msg order
00117 @param kwds: use keyword arguments corresponding to message field names
00118 to set specific fields.
00119 """
00120 if args or kwds:
00121 super(SetPoseRequest, self).__init__(*args, **kwds)
00122
00123 if self.pose is None:
00124 self.pose = nav_msgs.msg.Odometry()
00125 else:
00126 self.pose = nav_msgs.msg.Odometry()
00127
00128 def _get_types(self):
00129 """
00130 internal API method
00131 """
00132 return self._slot_types
00133
00134 def serialize(self, buff):
00135 """
00136 serialize message into buffer
00137 @param buff: buffer
00138 @type buff: StringIO
00139 """
00140 try:
00141 _x = self
00142 buff.write(_struct_3I.pack(_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs))
00143 _x = self.pose.header.frame_id
00144 length = len(_x)
00145 buff.write(struct.pack('<I%ss'%length, length, _x))
00146 _x = self.pose.child_frame_id
00147 length = len(_x)
00148 buff.write(struct.pack('<I%ss'%length, length, _x))
00149 _x = self
00150 buff.write(_struct_7d.pack(_x.pose.pose.pose.position.x, _x.pose.pose.pose.position.y, _x.pose.pose.pose.position.z, _x.pose.pose.pose.orientation.x, _x.pose.pose.pose.orientation.y, _x.pose.pose.pose.orientation.z, _x.pose.pose.pose.orientation.w))
00151 buff.write(_struct_36d.pack(*self.pose.pose.covariance))
00152 _x = self
00153 buff.write(_struct_6d.pack(_x.pose.twist.twist.linear.x, _x.pose.twist.twist.linear.y, _x.pose.twist.twist.linear.z, _x.pose.twist.twist.angular.x, _x.pose.twist.twist.angular.y, _x.pose.twist.twist.angular.z))
00154 buff.write(_struct_36d.pack(*self.pose.twist.covariance))
00155 except struct.error, se: self._check_types(se)
00156 except TypeError, te: self._check_types(te)
00157
00158 def deserialize(self, str):
00159 """
00160 unpack serialized message in str into this message instance
00161 @param str: byte array of serialized message
00162 @type str: str
00163 """
00164 try:
00165 if self.pose is None:
00166 self.pose = nav_msgs.msg.Odometry()
00167 end = 0
00168 _x = self
00169 start = end
00170 end += 12
00171 (_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00172 start = end
00173 end += 4
00174 (length,) = _struct_I.unpack(str[start:end])
00175 start = end
00176 end += length
00177 self.pose.header.frame_id = str[start:end]
00178 start = end
00179 end += 4
00180 (length,) = _struct_I.unpack(str[start:end])
00181 start = end
00182 end += length
00183 self.pose.child_frame_id = str[start:end]
00184 _x = self
00185 start = end
00186 end += 56
00187 (_x.pose.pose.pose.position.x, _x.pose.pose.pose.position.y, _x.pose.pose.pose.position.z, _x.pose.pose.pose.orientation.x, _x.pose.pose.pose.orientation.y, _x.pose.pose.pose.orientation.z, _x.pose.pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00188 start = end
00189 end += 288
00190 self.pose.pose.covariance = _struct_36d.unpack(str[start:end])
00191 _x = self
00192 start = end
00193 end += 48
00194 (_x.pose.twist.twist.linear.x, _x.pose.twist.twist.linear.y, _x.pose.twist.twist.linear.z, _x.pose.twist.twist.angular.x, _x.pose.twist.twist.angular.y, _x.pose.twist.twist.angular.z,) = _struct_6d.unpack(str[start:end])
00195 start = end
00196 end += 288
00197 self.pose.twist.covariance = _struct_36d.unpack(str[start:end])
00198 return self
00199 except struct.error, e:
00200 raise roslib.message.DeserializationError(e)
00201
00202
00203 def serialize_numpy(self, buff, numpy):
00204 """
00205 serialize message with numpy array types into buffer
00206 @param buff: buffer
00207 @type buff: StringIO
00208 @param numpy: numpy python module
00209 @type numpy module
00210 """
00211 try:
00212 _x = self
00213 buff.write(_struct_3I.pack(_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs))
00214 _x = self.pose.header.frame_id
00215 length = len(_x)
00216 buff.write(struct.pack('<I%ss'%length, length, _x))
00217 _x = self.pose.child_frame_id
00218 length = len(_x)
00219 buff.write(struct.pack('<I%ss'%length, length, _x))
00220 _x = self
00221 buff.write(_struct_7d.pack(_x.pose.pose.pose.position.x, _x.pose.pose.pose.position.y, _x.pose.pose.pose.position.z, _x.pose.pose.pose.orientation.x, _x.pose.pose.pose.orientation.y, _x.pose.pose.pose.orientation.z, _x.pose.pose.pose.orientation.w))
00222 buff.write(self.pose.pose.covariance.tostring())
00223 _x = self
00224 buff.write(_struct_6d.pack(_x.pose.twist.twist.linear.x, _x.pose.twist.twist.linear.y, _x.pose.twist.twist.linear.z, _x.pose.twist.twist.angular.x, _x.pose.twist.twist.angular.y, _x.pose.twist.twist.angular.z))
00225 buff.write(self.pose.twist.covariance.tostring())
00226 except struct.error, se: self._check_types(se)
00227 except TypeError, te: self._check_types(te)
00228
00229 def deserialize_numpy(self, str, numpy):
00230 """
00231 unpack serialized message in str into this message instance using numpy for array types
00232 @param str: byte array of serialized message
00233 @type str: str
00234 @param numpy: numpy python module
00235 @type numpy: module
00236 """
00237 try:
00238 if self.pose is None:
00239 self.pose = nav_msgs.msg.Odometry()
00240 end = 0
00241 _x = self
00242 start = end
00243 end += 12
00244 (_x.pose.header.seq, _x.pose.header.stamp.secs, _x.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00245 start = end
00246 end += 4
00247 (length,) = _struct_I.unpack(str[start:end])
00248 start = end
00249 end += length
00250 self.pose.header.frame_id = str[start:end]
00251 start = end
00252 end += 4
00253 (length,) = _struct_I.unpack(str[start:end])
00254 start = end
00255 end += length
00256 self.pose.child_frame_id = str[start:end]
00257 _x = self
00258 start = end
00259 end += 56
00260 (_x.pose.pose.pose.position.x, _x.pose.pose.pose.position.y, _x.pose.pose.pose.position.z, _x.pose.pose.pose.orientation.x, _x.pose.pose.pose.orientation.y, _x.pose.pose.pose.orientation.z, _x.pose.pose.pose.orientation.w,) = _struct_7d.unpack(str[start:end])
00261 start = end
00262 end += 288
00263 self.pose.pose.covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36)
00264 _x = self
00265 start = end
00266 end += 48
00267 (_x.pose.twist.twist.linear.x, _x.pose.twist.twist.linear.y, _x.pose.twist.twist.linear.z, _x.pose.twist.twist.angular.x, _x.pose.twist.twist.angular.y, _x.pose.twist.twist.angular.z,) = _struct_6d.unpack(str[start:end])
00268 start = end
00269 end += 288
00270 self.pose.twist.covariance = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36)
00271 return self
00272 except struct.error, e:
00273 raise roslib.message.DeserializationError(e)
00274
00275 _struct_I = roslib.message.struct_I
00276 _struct_3I = struct.Struct("<3I")
00277 _struct_7d = struct.Struct("<7d")
00278 _struct_6d = struct.Struct("<6d")
00279 _struct_36d = struct.Struct("<36d")
00280 """autogenerated by genmsg_py from SetPoseResponse.msg. Do not edit."""
00281 import roslib.message
00282 import struct
00283
00284
00285 class SetPoseResponse(roslib.message.Message):
00286 _md5sum = "2ec6f3eff0161f4257b808b12bc830c2"
00287 _type = "gazebo_plugins/SetPoseResponse"
00288 _has_header = False
00289 _full_text = """bool success
00290 string status_message
00291
00292
00293 """
00294 __slots__ = ['success','status_message']
00295 _slot_types = ['bool','string']
00296
00297 def __init__(self, *args, **kwds):
00298 """
00299 Constructor. Any message fields that are implicitly/explicitly
00300 set to None will be assigned a default value. The recommend
00301 use is keyword arguments as this is more robust to future message
00302 changes. You cannot mix in-order arguments and keyword arguments.
00303
00304 The available fields are:
00305 success,status_message
00306
00307 @param args: complete set of field values, in .msg order
00308 @param kwds: use keyword arguments corresponding to message field names
00309 to set specific fields.
00310 """
00311 if args or kwds:
00312 super(SetPoseResponse, self).__init__(*args, **kwds)
00313
00314 if self.success is None:
00315 self.success = False
00316 if self.status_message is None:
00317 self.status_message = ''
00318 else:
00319 self.success = False
00320 self.status_message = ''
00321
00322 def _get_types(self):
00323 """
00324 internal API method
00325 """
00326 return self._slot_types
00327
00328 def serialize(self, buff):
00329 """
00330 serialize message into buffer
00331 @param buff: buffer
00332 @type buff: StringIO
00333 """
00334 try:
00335 buff.write(_struct_B.pack(self.success))
00336 _x = self.status_message
00337 length = len(_x)
00338 buff.write(struct.pack('<I%ss'%length, length, _x))
00339 except struct.error, se: self._check_types(se)
00340 except TypeError, te: self._check_types(te)
00341
00342 def deserialize(self, str):
00343 """
00344 unpack serialized message in str into this message instance
00345 @param str: byte array of serialized message
00346 @type str: str
00347 """
00348 try:
00349 end = 0
00350 start = end
00351 end += 1
00352 (self.success,) = _struct_B.unpack(str[start:end])
00353 self.success = bool(self.success)
00354 start = end
00355 end += 4
00356 (length,) = _struct_I.unpack(str[start:end])
00357 start = end
00358 end += length
00359 self.status_message = str[start:end]
00360 return self
00361 except struct.error, e:
00362 raise roslib.message.DeserializationError(e)
00363
00364
00365 def serialize_numpy(self, buff, numpy):
00366 """
00367 serialize message with numpy array types into buffer
00368 @param buff: buffer
00369 @type buff: StringIO
00370 @param numpy: numpy python module
00371 @type numpy module
00372 """
00373 try:
00374 buff.write(_struct_B.pack(self.success))
00375 _x = self.status_message
00376 length = len(_x)
00377 buff.write(struct.pack('<I%ss'%length, length, _x))
00378 except struct.error, se: self._check_types(se)
00379 except TypeError, te: self._check_types(te)
00380
00381 def deserialize_numpy(self, str, numpy):
00382 """
00383 unpack serialized message in str into this message instance using numpy for array types
00384 @param str: byte array of serialized message
00385 @type str: str
00386 @param numpy: numpy python module
00387 @type numpy: module
00388 """
00389 try:
00390 end = 0
00391 start = end
00392 end += 1
00393 (self.success,) = _struct_B.unpack(str[start:end])
00394 self.success = bool(self.success)
00395 start = end
00396 end += 4
00397 (length,) = _struct_I.unpack(str[start:end])
00398 start = end
00399 end += length
00400 self.status_message = str[start:end]
00401 return self
00402 except struct.error, e:
00403 raise roslib.message.DeserializationError(e)
00404
00405 _struct_I = roslib.message.struct_I
00406 _struct_B = struct.Struct("<B")
00407 class SetPose(roslib.message.ServiceDefinition):
00408 _type = 'gazebo_plugins/SetPose'
00409 _md5sum = 'b302d2ba34678ac3098522ed0bd73f44'
00410 _request_class = SetPoseRequest
00411 _response_class = SetPoseResponse