00001 """autogenerated by genmsg_py from RobotState.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import roslib.rostime
00007 import std_msgs.msg
00008 import motion_planning_msgs.msg
00009 import sensor_msgs.msg
00010
00011 class RobotState(roslib.message.Message):
00012 _md5sum = "970d46b2ca41b9686adbdaeb592d97a7"
00013 _type = "motion_planning_msgs/RobotState"
00014 _has_header = False
00015 _full_text = """# This message contains information about the robot state, i.e. the positions of its joints and links
00016 sensor_msgs/JointState joint_state
00017 motion_planning_msgs/MultiDOFJointState multi_dof_joint_state
00018 ================================================================================
00019 MSG: sensor_msgs/JointState
00020 # This is a message that holds data to describe the state of a set of torque controlled joints.
00021 #
00022 # The state of each joint (revolute or prismatic) is defined by:
00023 # * the position of the joint (rad or m),
00024 # * the velocity of the joint (rad/s or m/s) and
00025 # * the effort that is applied in the joint (Nm or N).
00026 #
00027 # Each joint is uniquely identified by its name
00028 # The header specifies the time at which the joint states were recorded. All the joint states
00029 # in one message have to be recorded at the same time.
00030 #
00031 # This message consists of a multiple arrays, one for each part of the joint state.
00032 # The goal is to make each of the fields optional. When e.g. your joints have no
00033 # effort associated with them, you can leave the effort array empty.
00034 #
00035 # All arrays in this message should have the same size, or be empty.
00036 # This is the only way to uniquely associate the joint name with the correct
00037 # states.
00038
00039
00040 Header header
00041
00042 string[] name
00043 float64[] position
00044 float64[] velocity
00045 float64[] effort
00046
00047 ================================================================================
00048 MSG: std_msgs/Header
00049 # Standard metadata for higher-level stamped data types.
00050 # This is generally used to communicate timestamped data
00051 # in a particular coordinate frame.
00052 #
00053 # sequence ID: consecutively increasing ID
00054 uint32 seq
00055 #Two-integer timestamp that is expressed as:
00056 # * stamp.secs: seconds (stamp_secs) since epoch
00057 # * stamp.nsecs: nanoseconds since stamp_secs
00058 # time-handling sugar is provided by the client library
00059 time stamp
00060 #Frame this data is associated with
00061 # 0: no frame
00062 # 1: global frame
00063 string frame_id
00064
00065 ================================================================================
00066 MSG: motion_planning_msgs/MultiDOFJointState
00067 #A representation of a multi-dof joint state
00068 time stamp
00069 string[] joint_names
00070 string[] frame_ids
00071 string[] child_frame_ids
00072 geometry_msgs/Pose[] poses
00073
00074 ================================================================================
00075 MSG: geometry_msgs/Pose
00076 # A representation of pose in free space, composed of postion and orientation.
00077 Point position
00078 Quaternion orientation
00079
00080 ================================================================================
00081 MSG: geometry_msgs/Point
00082 # This contains the position of a point in free space
00083 float64 x
00084 float64 y
00085 float64 z
00086
00087 ================================================================================
00088 MSG: geometry_msgs/Quaternion
00089 # This represents an orientation in free space in quaternion form.
00090
00091 float64 x
00092 float64 y
00093 float64 z
00094 float64 w
00095
00096 """
00097 __slots__ = ['joint_state','multi_dof_joint_state']
00098 _slot_types = ['sensor_msgs/JointState','motion_planning_msgs/MultiDOFJointState']
00099
00100 def __init__(self, *args, **kwds):
00101 """
00102 Constructor. Any message fields that are implicitly/explicitly
00103 set to None will be assigned a default value. The recommend
00104 use is keyword arguments as this is more robust to future message
00105 changes. You cannot mix in-order arguments and keyword arguments.
00106
00107 The available fields are:
00108 joint_state,multi_dof_joint_state
00109
00110 @param args: complete set of field values, in .msg order
00111 @param kwds: use keyword arguments corresponding to message field names
00112 to set specific fields.
00113 """
00114 if args or kwds:
00115 super(RobotState, self).__init__(*args, **kwds)
00116
00117 if self.joint_state is None:
00118 self.joint_state = sensor_msgs.msg.JointState()
00119 if self.multi_dof_joint_state is None:
00120 self.multi_dof_joint_state = motion_planning_msgs.msg.MultiDOFJointState()
00121 else:
00122 self.joint_state = sensor_msgs.msg.JointState()
00123 self.multi_dof_joint_state = motion_planning_msgs.msg.MultiDOFJointState()
00124
00125 def _get_types(self):
00126 """
00127 internal API method
00128 """
00129 return self._slot_types
00130
00131 def serialize(self, buff):
00132 """
00133 serialize message into buffer
00134 @param buff: buffer
00135 @type buff: StringIO
00136 """
00137 try:
00138 _x = self
00139 buff.write(_struct_3I.pack(_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs))
00140 _x = self.joint_state.header.frame_id
00141 length = len(_x)
00142 buff.write(struct.pack('<I%ss'%length, length, _x))
00143 length = len(self.joint_state.name)
00144 buff.write(_struct_I.pack(length))
00145 for val1 in self.joint_state.name:
00146 length = len(val1)
00147 buff.write(struct.pack('<I%ss'%length, length, val1))
00148 length = len(self.joint_state.position)
00149 buff.write(_struct_I.pack(length))
00150 pattern = '<%sd'%length
00151 buff.write(struct.pack(pattern, *self.joint_state.position))
00152 length = len(self.joint_state.velocity)
00153 buff.write(_struct_I.pack(length))
00154 pattern = '<%sd'%length
00155 buff.write(struct.pack(pattern, *self.joint_state.velocity))
00156 length = len(self.joint_state.effort)
00157 buff.write(_struct_I.pack(length))
00158 pattern = '<%sd'%length
00159 buff.write(struct.pack(pattern, *self.joint_state.effort))
00160 _x = self
00161 buff.write(_struct_2I.pack(_x.multi_dof_joint_state.stamp.secs, _x.multi_dof_joint_state.stamp.nsecs))
00162 length = len(self.multi_dof_joint_state.joint_names)
00163 buff.write(_struct_I.pack(length))
00164 for val1 in self.multi_dof_joint_state.joint_names:
00165 length = len(val1)
00166 buff.write(struct.pack('<I%ss'%length, length, val1))
00167 length = len(self.multi_dof_joint_state.frame_ids)
00168 buff.write(_struct_I.pack(length))
00169 for val1 in self.multi_dof_joint_state.frame_ids:
00170 length = len(val1)
00171 buff.write(struct.pack('<I%ss'%length, length, val1))
00172 length = len(self.multi_dof_joint_state.child_frame_ids)
00173 buff.write(_struct_I.pack(length))
00174 for val1 in self.multi_dof_joint_state.child_frame_ids:
00175 length = len(val1)
00176 buff.write(struct.pack('<I%ss'%length, length, val1))
00177 length = len(self.multi_dof_joint_state.poses)
00178 buff.write(_struct_I.pack(length))
00179 for val1 in self.multi_dof_joint_state.poses:
00180 _v1 = val1.position
00181 _x = _v1
00182 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00183 _v2 = val1.orientation
00184 _x = _v2
00185 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00186 except struct.error, se: self._check_types(se)
00187 except TypeError, te: self._check_types(te)
00188
00189 def deserialize(self, str):
00190 """
00191 unpack serialized message in str into this message instance
00192 @param str: byte array of serialized message
00193 @type str: str
00194 """
00195 try:
00196 if self.joint_state is None:
00197 self.joint_state = sensor_msgs.msg.JointState()
00198 if self.multi_dof_joint_state is None:
00199 self.multi_dof_joint_state = motion_planning_msgs.msg.MultiDOFJointState()
00200 end = 0
00201 _x = self
00202 start = end
00203 end += 12
00204 (_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00205 start = end
00206 end += 4
00207 (length,) = _struct_I.unpack(str[start:end])
00208 start = end
00209 end += length
00210 self.joint_state.header.frame_id = str[start:end]
00211 start = end
00212 end += 4
00213 (length,) = _struct_I.unpack(str[start:end])
00214 self.joint_state.name = []
00215 for i in xrange(0, length):
00216 start = end
00217 end += 4
00218 (length,) = _struct_I.unpack(str[start:end])
00219 start = end
00220 end += length
00221 val1 = str[start:end]
00222 self.joint_state.name.append(val1)
00223 start = end
00224 end += 4
00225 (length,) = _struct_I.unpack(str[start:end])
00226 pattern = '<%sd'%length
00227 start = end
00228 end += struct.calcsize(pattern)
00229 self.joint_state.position = struct.unpack(pattern, str[start:end])
00230 start = end
00231 end += 4
00232 (length,) = _struct_I.unpack(str[start:end])
00233 pattern = '<%sd'%length
00234 start = end
00235 end += struct.calcsize(pattern)
00236 self.joint_state.velocity = struct.unpack(pattern, str[start:end])
00237 start = end
00238 end += 4
00239 (length,) = _struct_I.unpack(str[start:end])
00240 pattern = '<%sd'%length
00241 start = end
00242 end += struct.calcsize(pattern)
00243 self.joint_state.effort = struct.unpack(pattern, str[start:end])
00244 _x = self
00245 start = end
00246 end += 8
00247 (_x.multi_dof_joint_state.stamp.secs, _x.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00248 start = end
00249 end += 4
00250 (length,) = _struct_I.unpack(str[start:end])
00251 self.multi_dof_joint_state.joint_names = []
00252 for i in xrange(0, length):
00253 start = end
00254 end += 4
00255 (length,) = _struct_I.unpack(str[start:end])
00256 start = end
00257 end += length
00258 val1 = str[start:end]
00259 self.multi_dof_joint_state.joint_names.append(val1)
00260 start = end
00261 end += 4
00262 (length,) = _struct_I.unpack(str[start:end])
00263 self.multi_dof_joint_state.frame_ids = []
00264 for i in xrange(0, length):
00265 start = end
00266 end += 4
00267 (length,) = _struct_I.unpack(str[start:end])
00268 start = end
00269 end += length
00270 val1 = str[start:end]
00271 self.multi_dof_joint_state.frame_ids.append(val1)
00272 start = end
00273 end += 4
00274 (length,) = _struct_I.unpack(str[start:end])
00275 self.multi_dof_joint_state.child_frame_ids = []
00276 for i in xrange(0, length):
00277 start = end
00278 end += 4
00279 (length,) = _struct_I.unpack(str[start:end])
00280 start = end
00281 end += length
00282 val1 = str[start:end]
00283 self.multi_dof_joint_state.child_frame_ids.append(val1)
00284 start = end
00285 end += 4
00286 (length,) = _struct_I.unpack(str[start:end])
00287 self.multi_dof_joint_state.poses = []
00288 for i in xrange(0, length):
00289 val1 = geometry_msgs.msg.Pose()
00290 _v3 = val1.position
00291 _x = _v3
00292 start = end
00293 end += 24
00294 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00295 _v4 = val1.orientation
00296 _x = _v4
00297 start = end
00298 end += 32
00299 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00300 self.multi_dof_joint_state.poses.append(val1)
00301 return self
00302 except struct.error, e:
00303 raise roslib.message.DeserializationError(e)
00304
00305
00306 def serialize_numpy(self, buff, numpy):
00307 """
00308 serialize message with numpy array types into buffer
00309 @param buff: buffer
00310 @type buff: StringIO
00311 @param numpy: numpy python module
00312 @type numpy module
00313 """
00314 try:
00315 _x = self
00316 buff.write(_struct_3I.pack(_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs))
00317 _x = self.joint_state.header.frame_id
00318 length = len(_x)
00319 buff.write(struct.pack('<I%ss'%length, length, _x))
00320 length = len(self.joint_state.name)
00321 buff.write(_struct_I.pack(length))
00322 for val1 in self.joint_state.name:
00323 length = len(val1)
00324 buff.write(struct.pack('<I%ss'%length, length, val1))
00325 length = len(self.joint_state.position)
00326 buff.write(_struct_I.pack(length))
00327 pattern = '<%sd'%length
00328 buff.write(self.joint_state.position.tostring())
00329 length = len(self.joint_state.velocity)
00330 buff.write(_struct_I.pack(length))
00331 pattern = '<%sd'%length
00332 buff.write(self.joint_state.velocity.tostring())
00333 length = len(self.joint_state.effort)
00334 buff.write(_struct_I.pack(length))
00335 pattern = '<%sd'%length
00336 buff.write(self.joint_state.effort.tostring())
00337 _x = self
00338 buff.write(_struct_2I.pack(_x.multi_dof_joint_state.stamp.secs, _x.multi_dof_joint_state.stamp.nsecs))
00339 length = len(self.multi_dof_joint_state.joint_names)
00340 buff.write(_struct_I.pack(length))
00341 for val1 in self.multi_dof_joint_state.joint_names:
00342 length = len(val1)
00343 buff.write(struct.pack('<I%ss'%length, length, val1))
00344 length = len(self.multi_dof_joint_state.frame_ids)
00345 buff.write(_struct_I.pack(length))
00346 for val1 in self.multi_dof_joint_state.frame_ids:
00347 length = len(val1)
00348 buff.write(struct.pack('<I%ss'%length, length, val1))
00349 length = len(self.multi_dof_joint_state.child_frame_ids)
00350 buff.write(_struct_I.pack(length))
00351 for val1 in self.multi_dof_joint_state.child_frame_ids:
00352 length = len(val1)
00353 buff.write(struct.pack('<I%ss'%length, length, val1))
00354 length = len(self.multi_dof_joint_state.poses)
00355 buff.write(_struct_I.pack(length))
00356 for val1 in self.multi_dof_joint_state.poses:
00357 _v5 = val1.position
00358 _x = _v5
00359 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00360 _v6 = val1.orientation
00361 _x = _v6
00362 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00363 except struct.error, se: self._check_types(se)
00364 except TypeError, te: self._check_types(te)
00365
00366 def deserialize_numpy(self, str, numpy):
00367 """
00368 unpack serialized message in str into this message instance using numpy for array types
00369 @param str: byte array of serialized message
00370 @type str: str
00371 @param numpy: numpy python module
00372 @type numpy: module
00373 """
00374 try:
00375 if self.joint_state is None:
00376 self.joint_state = sensor_msgs.msg.JointState()
00377 if self.multi_dof_joint_state is None:
00378 self.multi_dof_joint_state = motion_planning_msgs.msg.MultiDOFJointState()
00379 end = 0
00380 _x = self
00381 start = end
00382 end += 12
00383 (_x.joint_state.header.seq, _x.joint_state.header.stamp.secs, _x.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00384 start = end
00385 end += 4
00386 (length,) = _struct_I.unpack(str[start:end])
00387 start = end
00388 end += length
00389 self.joint_state.header.frame_id = str[start:end]
00390 start = end
00391 end += 4
00392 (length,) = _struct_I.unpack(str[start:end])
00393 self.joint_state.name = []
00394 for i in xrange(0, length):
00395 start = end
00396 end += 4
00397 (length,) = _struct_I.unpack(str[start:end])
00398 start = end
00399 end += length
00400 val1 = str[start:end]
00401 self.joint_state.name.append(val1)
00402 start = end
00403 end += 4
00404 (length,) = _struct_I.unpack(str[start:end])
00405 pattern = '<%sd'%length
00406 start = end
00407 end += struct.calcsize(pattern)
00408 self.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00409 start = end
00410 end += 4
00411 (length,) = _struct_I.unpack(str[start:end])
00412 pattern = '<%sd'%length
00413 start = end
00414 end += struct.calcsize(pattern)
00415 self.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00416 start = end
00417 end += 4
00418 (length,) = _struct_I.unpack(str[start:end])
00419 pattern = '<%sd'%length
00420 start = end
00421 end += struct.calcsize(pattern)
00422 self.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00423 _x = self
00424 start = end
00425 end += 8
00426 (_x.multi_dof_joint_state.stamp.secs, _x.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00427 start = end
00428 end += 4
00429 (length,) = _struct_I.unpack(str[start:end])
00430 self.multi_dof_joint_state.joint_names = []
00431 for i in xrange(0, length):
00432 start = end
00433 end += 4
00434 (length,) = _struct_I.unpack(str[start:end])
00435 start = end
00436 end += length
00437 val1 = str[start:end]
00438 self.multi_dof_joint_state.joint_names.append(val1)
00439 start = end
00440 end += 4
00441 (length,) = _struct_I.unpack(str[start:end])
00442 self.multi_dof_joint_state.frame_ids = []
00443 for i in xrange(0, length):
00444 start = end
00445 end += 4
00446 (length,) = _struct_I.unpack(str[start:end])
00447 start = end
00448 end += length
00449 val1 = str[start:end]
00450 self.multi_dof_joint_state.frame_ids.append(val1)
00451 start = end
00452 end += 4
00453 (length,) = _struct_I.unpack(str[start:end])
00454 self.multi_dof_joint_state.child_frame_ids = []
00455 for i in xrange(0, length):
00456 start = end
00457 end += 4
00458 (length,) = _struct_I.unpack(str[start:end])
00459 start = end
00460 end += length
00461 val1 = str[start:end]
00462 self.multi_dof_joint_state.child_frame_ids.append(val1)
00463 start = end
00464 end += 4
00465 (length,) = _struct_I.unpack(str[start:end])
00466 self.multi_dof_joint_state.poses = []
00467 for i in xrange(0, length):
00468 val1 = geometry_msgs.msg.Pose()
00469 _v7 = val1.position
00470 _x = _v7
00471 start = end
00472 end += 24
00473 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00474 _v8 = val1.orientation
00475 _x = _v8
00476 start = end
00477 end += 32
00478 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00479 self.multi_dof_joint_state.poses.append(val1)
00480 return self
00481 except struct.error, e:
00482 raise roslib.message.DeserializationError(e)
00483
00484 _struct_I = roslib.message.struct_I
00485 _struct_4d = struct.Struct("<4d")
00486 _struct_3I = struct.Struct("<3I")
00487 _struct_2I = struct.Struct("<2I")
00488 _struct_3d = struct.Struct("<3d")