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