00001 """autogenerated by genpy from chomp_motion_planner/GetStateCostRequest.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 arm_navigation_msgs.msg
00008 import geometry_msgs.msg
00009 import std_msgs.msg
00010 import genpy
00011 import sensor_msgs.msg
00012
00013 class GetStateCostRequest(genpy.Message):
00014 _md5sum = "8eb8c1ec9dda8058aa5e5d82c1d8cda6"
00015 _type = "chomp_motion_planner/GetStateCostRequest"
00016 _has_header = False
00017 _full_text = """
00018
00019
00020 string[] link_names
00021
00022 arm_navigation_msgs/RobotState robot_state
00023
00024 ================================================================================
00025 MSG: arm_navigation_msgs/RobotState
00026 # This message contains information about the robot state, i.e. the positions of its joints and links
00027 sensor_msgs/JointState joint_state
00028 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state
00029
00030 ================================================================================
00031 MSG: sensor_msgs/JointState
00032 # This is a message that holds data to describe the state of a set of torque controlled joints.
00033 #
00034 # The state of each joint (revolute or prismatic) is defined by:
00035 # * the position of the joint (rad or m),
00036 # * the velocity of the joint (rad/s or m/s) and
00037 # * the effort that is applied in the joint (Nm or N).
00038 #
00039 # Each joint is uniquely identified by its name
00040 # The header specifies the time at which the joint states were recorded. All the joint states
00041 # in one message have to be recorded at the same time.
00042 #
00043 # This message consists of a multiple arrays, one for each part of the joint state.
00044 # The goal is to make each of the fields optional. When e.g. your joints have no
00045 # effort associated with them, you can leave the effort array empty.
00046 #
00047 # All arrays in this message should have the same size, or be empty.
00048 # This is the only way to uniquely associate the joint name with the correct
00049 # states.
00050
00051
00052 Header header
00053
00054 string[] name
00055 float64[] position
00056 float64[] velocity
00057 float64[] effort
00058
00059 ================================================================================
00060 MSG: std_msgs/Header
00061 # Standard metadata for higher-level stamped data types.
00062 # This is generally used to communicate timestamped data
00063 # in a particular coordinate frame.
00064 #
00065 # sequence ID: consecutively increasing ID
00066 uint32 seq
00067 #Two-integer timestamp that is expressed as:
00068 # * stamp.secs: seconds (stamp_secs) since epoch
00069 # * stamp.nsecs: nanoseconds since stamp_secs
00070 # time-handling sugar is provided by the client library
00071 time stamp
00072 #Frame this data is associated with
00073 # 0: no frame
00074 # 1: global frame
00075 string frame_id
00076
00077 ================================================================================
00078 MSG: arm_navigation_msgs/MultiDOFJointState
00079 #A representation of a multi-dof joint state
00080 time stamp
00081 string[] joint_names
00082 string[] frame_ids
00083 string[] child_frame_ids
00084 geometry_msgs/Pose[] poses
00085
00086 ================================================================================
00087 MSG: geometry_msgs/Pose
00088 # A representation of pose in free space, composed of postion and orientation.
00089 Point position
00090 Quaternion orientation
00091
00092 ================================================================================
00093 MSG: geometry_msgs/Point
00094 # This contains the position of a point in free space
00095 float64 x
00096 float64 y
00097 float64 z
00098
00099 ================================================================================
00100 MSG: geometry_msgs/Quaternion
00101 # This represents an orientation in free space in quaternion form.
00102
00103 float64 x
00104 float64 y
00105 float64 z
00106 float64 w
00107
00108 """
00109 __slots__ = ['link_names','robot_state']
00110 _slot_types = ['string[]','arm_navigation_msgs/RobotState']
00111
00112 def __init__(self, *args, **kwds):
00113 """
00114 Constructor. Any message fields that are implicitly/explicitly
00115 set to None will be assigned a default value. The recommend
00116 use is keyword arguments as this is more robust to future message
00117 changes. You cannot mix in-order arguments and keyword arguments.
00118
00119 The available fields are:
00120 link_names,robot_state
00121
00122 :param args: complete set of field values, in .msg order
00123 :param kwds: use keyword arguments corresponding to message field names
00124 to set specific fields.
00125 """
00126 if args or kwds:
00127 super(GetStateCostRequest, self).__init__(*args, **kwds)
00128
00129 if self.link_names is None:
00130 self.link_names = []
00131 if self.robot_state is None:
00132 self.robot_state = arm_navigation_msgs.msg.RobotState()
00133 else:
00134 self.link_names = []
00135 self.robot_state = arm_navigation_msgs.msg.RobotState()
00136
00137 def _get_types(self):
00138 """
00139 internal API method
00140 """
00141 return self._slot_types
00142
00143 def serialize(self, buff):
00144 """
00145 serialize message into buffer
00146 :param buff: buffer, ``StringIO``
00147 """
00148 try:
00149 length = len(self.link_names)
00150 buff.write(_struct_I.pack(length))
00151 for val1 in self.link_names:
00152 length = len(val1)
00153 if python3 or type(val1) == unicode:
00154 val1 = val1.encode('utf-8')
00155 length = len(val1)
00156 buff.write(struct.pack('<I%ss'%length, length, val1))
00157 _x = self
00158 buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs))
00159 _x = self.robot_state.joint_state.header.frame_id
00160 length = len(_x)
00161 if python3 or type(_x) == unicode:
00162 _x = _x.encode('utf-8')
00163 length = len(_x)
00164 buff.write(struct.pack('<I%ss'%length, length, _x))
00165 length = len(self.robot_state.joint_state.name)
00166 buff.write(_struct_I.pack(length))
00167 for val1 in self.robot_state.joint_state.name:
00168 length = len(val1)
00169 if python3 or type(val1) == unicode:
00170 val1 = val1.encode('utf-8')
00171 length = len(val1)
00172 buff.write(struct.pack('<I%ss'%length, length, val1))
00173 length = len(self.robot_state.joint_state.position)
00174 buff.write(_struct_I.pack(length))
00175 pattern = '<%sd'%length
00176 buff.write(struct.pack(pattern, *self.robot_state.joint_state.position))
00177 length = len(self.robot_state.joint_state.velocity)
00178 buff.write(_struct_I.pack(length))
00179 pattern = '<%sd'%length
00180 buff.write(struct.pack(pattern, *self.robot_state.joint_state.velocity))
00181 length = len(self.robot_state.joint_state.effort)
00182 buff.write(_struct_I.pack(length))
00183 pattern = '<%sd'%length
00184 buff.write(struct.pack(pattern, *self.robot_state.joint_state.effort))
00185 _x = self
00186 buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs))
00187 length = len(self.robot_state.multi_dof_joint_state.joint_names)
00188 buff.write(_struct_I.pack(length))
00189 for val1 in self.robot_state.multi_dof_joint_state.joint_names:
00190 length = len(val1)
00191 if python3 or type(val1) == unicode:
00192 val1 = val1.encode('utf-8')
00193 length = len(val1)
00194 buff.write(struct.pack('<I%ss'%length, length, val1))
00195 length = len(self.robot_state.multi_dof_joint_state.frame_ids)
00196 buff.write(_struct_I.pack(length))
00197 for val1 in self.robot_state.multi_dof_joint_state.frame_ids:
00198 length = len(val1)
00199 if python3 or type(val1) == unicode:
00200 val1 = val1.encode('utf-8')
00201 length = len(val1)
00202 buff.write(struct.pack('<I%ss'%length, length, val1))
00203 length = len(self.robot_state.multi_dof_joint_state.child_frame_ids)
00204 buff.write(_struct_I.pack(length))
00205 for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids:
00206 length = len(val1)
00207 if python3 or type(val1) == unicode:
00208 val1 = val1.encode('utf-8')
00209 length = len(val1)
00210 buff.write(struct.pack('<I%ss'%length, length, val1))
00211 length = len(self.robot_state.multi_dof_joint_state.poses)
00212 buff.write(_struct_I.pack(length))
00213 for val1 in self.robot_state.multi_dof_joint_state.poses:
00214 _v1 = val1.position
00215 _x = _v1
00216 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00217 _v2 = val1.orientation
00218 _x = _v2
00219 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00220 except struct.error as se: self._check_types(se)
00221 except TypeError as te: self._check_types(te)
00222
00223 def deserialize(self, str):
00224 """
00225 unpack serialized message in str into this message instance
00226 :param str: byte array of serialized message, ``str``
00227 """
00228 try:
00229 if self.robot_state is None:
00230 self.robot_state = arm_navigation_msgs.msg.RobotState()
00231 end = 0
00232 start = end
00233 end += 4
00234 (length,) = _struct_I.unpack(str[start:end])
00235 self.link_names = []
00236 for i in range(0, length):
00237 start = end
00238 end += 4
00239 (length,) = _struct_I.unpack(str[start:end])
00240 start = end
00241 end += length
00242 if python3:
00243 val1 = str[start:end].decode('utf-8')
00244 else:
00245 val1 = str[start:end]
00246 self.link_names.append(val1)
00247 _x = self
00248 start = end
00249 end += 12
00250 (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00251 start = end
00252 end += 4
00253 (length,) = _struct_I.unpack(str[start:end])
00254 start = end
00255 end += length
00256 if python3:
00257 self.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
00258 else:
00259 self.robot_state.joint_state.header.frame_id = str[start:end]
00260 start = end
00261 end += 4
00262 (length,) = _struct_I.unpack(str[start:end])
00263 self.robot_state.joint_state.name = []
00264 for i in range(0, length):
00265 start = end
00266 end += 4
00267 (length,) = _struct_I.unpack(str[start:end])
00268 start = end
00269 end += length
00270 if python3:
00271 val1 = str[start:end].decode('utf-8')
00272 else:
00273 val1 = str[start:end]
00274 self.robot_state.joint_state.name.append(val1)
00275 start = end
00276 end += 4
00277 (length,) = _struct_I.unpack(str[start:end])
00278 pattern = '<%sd'%length
00279 start = end
00280 end += struct.calcsize(pattern)
00281 self.robot_state.joint_state.position = struct.unpack(pattern, str[start:end])
00282 start = end
00283 end += 4
00284 (length,) = _struct_I.unpack(str[start:end])
00285 pattern = '<%sd'%length
00286 start = end
00287 end += struct.calcsize(pattern)
00288 self.robot_state.joint_state.velocity = struct.unpack(pattern, str[start:end])
00289 start = end
00290 end += 4
00291 (length,) = _struct_I.unpack(str[start:end])
00292 pattern = '<%sd'%length
00293 start = end
00294 end += struct.calcsize(pattern)
00295 self.robot_state.joint_state.effort = struct.unpack(pattern, str[start:end])
00296 _x = self
00297 start = end
00298 end += 8
00299 (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00300 start = end
00301 end += 4
00302 (length,) = _struct_I.unpack(str[start:end])
00303 self.robot_state.multi_dof_joint_state.joint_names = []
00304 for i in range(0, length):
00305 start = end
00306 end += 4
00307 (length,) = _struct_I.unpack(str[start:end])
00308 start = end
00309 end += length
00310 if python3:
00311 val1 = str[start:end].decode('utf-8')
00312 else:
00313 val1 = str[start:end]
00314 self.robot_state.multi_dof_joint_state.joint_names.append(val1)
00315 start = end
00316 end += 4
00317 (length,) = _struct_I.unpack(str[start:end])
00318 self.robot_state.multi_dof_joint_state.frame_ids = []
00319 for i in range(0, length):
00320 start = end
00321 end += 4
00322 (length,) = _struct_I.unpack(str[start:end])
00323 start = end
00324 end += length
00325 if python3:
00326 val1 = str[start:end].decode('utf-8')
00327 else:
00328 val1 = str[start:end]
00329 self.robot_state.multi_dof_joint_state.frame_ids.append(val1)
00330 start = end
00331 end += 4
00332 (length,) = _struct_I.unpack(str[start:end])
00333 self.robot_state.multi_dof_joint_state.child_frame_ids = []
00334 for i in range(0, length):
00335 start = end
00336 end += 4
00337 (length,) = _struct_I.unpack(str[start:end])
00338 start = end
00339 end += length
00340 if python3:
00341 val1 = str[start:end].decode('utf-8')
00342 else:
00343 val1 = str[start:end]
00344 self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
00345 start = end
00346 end += 4
00347 (length,) = _struct_I.unpack(str[start:end])
00348 self.robot_state.multi_dof_joint_state.poses = []
00349 for i in range(0, length):
00350 val1 = geometry_msgs.msg.Pose()
00351 _v3 = val1.position
00352 _x = _v3
00353 start = end
00354 end += 24
00355 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00356 _v4 = val1.orientation
00357 _x = _v4
00358 start = end
00359 end += 32
00360 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00361 self.robot_state.multi_dof_joint_state.poses.append(val1)
00362 return self
00363 except struct.error as e:
00364 raise genpy.DeserializationError(e)
00365
00366
00367 def serialize_numpy(self, buff, numpy):
00368 """
00369 serialize message with numpy array types into buffer
00370 :param buff: buffer, ``StringIO``
00371 :param numpy: numpy python module
00372 """
00373 try:
00374 length = len(self.link_names)
00375 buff.write(_struct_I.pack(length))
00376 for val1 in self.link_names:
00377 length = len(val1)
00378 if python3 or type(val1) == unicode:
00379 val1 = val1.encode('utf-8')
00380 length = len(val1)
00381 buff.write(struct.pack('<I%ss'%length, length, val1))
00382 _x = self
00383 buff.write(_struct_3I.pack(_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs))
00384 _x = self.robot_state.joint_state.header.frame_id
00385 length = len(_x)
00386 if python3 or type(_x) == unicode:
00387 _x = _x.encode('utf-8')
00388 length = len(_x)
00389 buff.write(struct.pack('<I%ss'%length, length, _x))
00390 length = len(self.robot_state.joint_state.name)
00391 buff.write(_struct_I.pack(length))
00392 for val1 in self.robot_state.joint_state.name:
00393 length = len(val1)
00394 if python3 or type(val1) == unicode:
00395 val1 = val1.encode('utf-8')
00396 length = len(val1)
00397 buff.write(struct.pack('<I%ss'%length, length, val1))
00398 length = len(self.robot_state.joint_state.position)
00399 buff.write(_struct_I.pack(length))
00400 pattern = '<%sd'%length
00401 buff.write(self.robot_state.joint_state.position.tostring())
00402 length = len(self.robot_state.joint_state.velocity)
00403 buff.write(_struct_I.pack(length))
00404 pattern = '<%sd'%length
00405 buff.write(self.robot_state.joint_state.velocity.tostring())
00406 length = len(self.robot_state.joint_state.effort)
00407 buff.write(_struct_I.pack(length))
00408 pattern = '<%sd'%length
00409 buff.write(self.robot_state.joint_state.effort.tostring())
00410 _x = self
00411 buff.write(_struct_2I.pack(_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs))
00412 length = len(self.robot_state.multi_dof_joint_state.joint_names)
00413 buff.write(_struct_I.pack(length))
00414 for val1 in self.robot_state.multi_dof_joint_state.joint_names:
00415 length = len(val1)
00416 if python3 or type(val1) == unicode:
00417 val1 = val1.encode('utf-8')
00418 length = len(val1)
00419 buff.write(struct.pack('<I%ss'%length, length, val1))
00420 length = len(self.robot_state.multi_dof_joint_state.frame_ids)
00421 buff.write(_struct_I.pack(length))
00422 for val1 in self.robot_state.multi_dof_joint_state.frame_ids:
00423 length = len(val1)
00424 if python3 or type(val1) == unicode:
00425 val1 = val1.encode('utf-8')
00426 length = len(val1)
00427 buff.write(struct.pack('<I%ss'%length, length, val1))
00428 length = len(self.robot_state.multi_dof_joint_state.child_frame_ids)
00429 buff.write(_struct_I.pack(length))
00430 for val1 in self.robot_state.multi_dof_joint_state.child_frame_ids:
00431 length = len(val1)
00432 if python3 or type(val1) == unicode:
00433 val1 = val1.encode('utf-8')
00434 length = len(val1)
00435 buff.write(struct.pack('<I%ss'%length, length, val1))
00436 length = len(self.robot_state.multi_dof_joint_state.poses)
00437 buff.write(_struct_I.pack(length))
00438 for val1 in self.robot_state.multi_dof_joint_state.poses:
00439 _v5 = val1.position
00440 _x = _v5
00441 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00442 _v6 = val1.orientation
00443 _x = _v6
00444 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00445 except struct.error as se: self._check_types(se)
00446 except TypeError as te: self._check_types(te)
00447
00448 def deserialize_numpy(self, str, numpy):
00449 """
00450 unpack serialized message in str into this message instance using numpy for array types
00451 :param str: byte array of serialized message, ``str``
00452 :param numpy: numpy python module
00453 """
00454 try:
00455 if self.robot_state is None:
00456 self.robot_state = arm_navigation_msgs.msg.RobotState()
00457 end = 0
00458 start = end
00459 end += 4
00460 (length,) = _struct_I.unpack(str[start:end])
00461 self.link_names = []
00462 for i in range(0, length):
00463 start = end
00464 end += 4
00465 (length,) = _struct_I.unpack(str[start:end])
00466 start = end
00467 end += length
00468 if python3:
00469 val1 = str[start:end].decode('utf-8')
00470 else:
00471 val1 = str[start:end]
00472 self.link_names.append(val1)
00473 _x = self
00474 start = end
00475 end += 12
00476 (_x.robot_state.joint_state.header.seq, _x.robot_state.joint_state.header.stamp.secs, _x.robot_state.joint_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00477 start = end
00478 end += 4
00479 (length,) = _struct_I.unpack(str[start:end])
00480 start = end
00481 end += length
00482 if python3:
00483 self.robot_state.joint_state.header.frame_id = str[start:end].decode('utf-8')
00484 else:
00485 self.robot_state.joint_state.header.frame_id = str[start:end]
00486 start = end
00487 end += 4
00488 (length,) = _struct_I.unpack(str[start:end])
00489 self.robot_state.joint_state.name = []
00490 for i in range(0, length):
00491 start = end
00492 end += 4
00493 (length,) = _struct_I.unpack(str[start:end])
00494 start = end
00495 end += length
00496 if python3:
00497 val1 = str[start:end].decode('utf-8')
00498 else:
00499 val1 = str[start:end]
00500 self.robot_state.joint_state.name.append(val1)
00501 start = end
00502 end += 4
00503 (length,) = _struct_I.unpack(str[start:end])
00504 pattern = '<%sd'%length
00505 start = end
00506 end += struct.calcsize(pattern)
00507 self.robot_state.joint_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00508 start = end
00509 end += 4
00510 (length,) = _struct_I.unpack(str[start:end])
00511 pattern = '<%sd'%length
00512 start = end
00513 end += struct.calcsize(pattern)
00514 self.robot_state.joint_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00515 start = end
00516 end += 4
00517 (length,) = _struct_I.unpack(str[start:end])
00518 pattern = '<%sd'%length
00519 start = end
00520 end += struct.calcsize(pattern)
00521 self.robot_state.joint_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00522 _x = self
00523 start = end
00524 end += 8
00525 (_x.robot_state.multi_dof_joint_state.stamp.secs, _x.robot_state.multi_dof_joint_state.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00526 start = end
00527 end += 4
00528 (length,) = _struct_I.unpack(str[start:end])
00529 self.robot_state.multi_dof_joint_state.joint_names = []
00530 for i in range(0, length):
00531 start = end
00532 end += 4
00533 (length,) = _struct_I.unpack(str[start:end])
00534 start = end
00535 end += length
00536 if python3:
00537 val1 = str[start:end].decode('utf-8')
00538 else:
00539 val1 = str[start:end]
00540 self.robot_state.multi_dof_joint_state.joint_names.append(val1)
00541 start = end
00542 end += 4
00543 (length,) = _struct_I.unpack(str[start:end])
00544 self.robot_state.multi_dof_joint_state.frame_ids = []
00545 for i in range(0, length):
00546 start = end
00547 end += 4
00548 (length,) = _struct_I.unpack(str[start:end])
00549 start = end
00550 end += length
00551 if python3:
00552 val1 = str[start:end].decode('utf-8')
00553 else:
00554 val1 = str[start:end]
00555 self.robot_state.multi_dof_joint_state.frame_ids.append(val1)
00556 start = end
00557 end += 4
00558 (length,) = _struct_I.unpack(str[start:end])
00559 self.robot_state.multi_dof_joint_state.child_frame_ids = []
00560 for i in range(0, length):
00561 start = end
00562 end += 4
00563 (length,) = _struct_I.unpack(str[start:end])
00564 start = end
00565 end += length
00566 if python3:
00567 val1 = str[start:end].decode('utf-8')
00568 else:
00569 val1 = str[start:end]
00570 self.robot_state.multi_dof_joint_state.child_frame_ids.append(val1)
00571 start = end
00572 end += 4
00573 (length,) = _struct_I.unpack(str[start:end])
00574 self.robot_state.multi_dof_joint_state.poses = []
00575 for i in range(0, length):
00576 val1 = geometry_msgs.msg.Pose()
00577 _v7 = val1.position
00578 _x = _v7
00579 start = end
00580 end += 24
00581 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00582 _v8 = val1.orientation
00583 _x = _v8
00584 start = end
00585 end += 32
00586 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00587 self.robot_state.multi_dof_joint_state.poses.append(val1)
00588 return self
00589 except struct.error as e:
00590 raise genpy.DeserializationError(e)
00591
00592 _struct_I = genpy.struct_I
00593 _struct_4d = struct.Struct("<4d")
00594 _struct_3I = struct.Struct("<3I")
00595 _struct_2I = struct.Struct("<2I")
00596 _struct_3d = struct.Struct("<3d")
00597 """autogenerated by genpy from chomp_motion_planner/GetStateCostResponse.msg. Do not edit."""
00598 import sys
00599 python3 = True if sys.hexversion > 0x03000000 else False
00600 import genpy
00601 import struct
00602
00603
00604 class GetStateCostResponse(genpy.Message):
00605 _md5sum = "125a150f1be009a543837c8732501336"
00606 _type = "chomp_motion_planner/GetStateCostResponse"
00607 _has_header = False
00608 _full_text = """
00609 bool valid
00610
00611 float64[] costs
00612
00613
00614 """
00615 __slots__ = ['valid','costs']
00616 _slot_types = ['bool','float64[]']
00617
00618 def __init__(self, *args, **kwds):
00619 """
00620 Constructor. Any message fields that are implicitly/explicitly
00621 set to None will be assigned a default value. The recommend
00622 use is keyword arguments as this is more robust to future message
00623 changes. You cannot mix in-order arguments and keyword arguments.
00624
00625 The available fields are:
00626 valid,costs
00627
00628 :param args: complete set of field values, in .msg order
00629 :param kwds: use keyword arguments corresponding to message field names
00630 to set specific fields.
00631 """
00632 if args or kwds:
00633 super(GetStateCostResponse, self).__init__(*args, **kwds)
00634
00635 if self.valid is None:
00636 self.valid = False
00637 if self.costs is None:
00638 self.costs = []
00639 else:
00640 self.valid = False
00641 self.costs = []
00642
00643 def _get_types(self):
00644 """
00645 internal API method
00646 """
00647 return self._slot_types
00648
00649 def serialize(self, buff):
00650 """
00651 serialize message into buffer
00652 :param buff: buffer, ``StringIO``
00653 """
00654 try:
00655 buff.write(_struct_B.pack(self.valid))
00656 length = len(self.costs)
00657 buff.write(_struct_I.pack(length))
00658 pattern = '<%sd'%length
00659 buff.write(struct.pack(pattern, *self.costs))
00660 except struct.error as se: self._check_types(se)
00661 except TypeError as te: self._check_types(te)
00662
00663 def deserialize(self, str):
00664 """
00665 unpack serialized message in str into this message instance
00666 :param str: byte array of serialized message, ``str``
00667 """
00668 try:
00669 end = 0
00670 start = end
00671 end += 1
00672 (self.valid,) = _struct_B.unpack(str[start:end])
00673 self.valid = bool(self.valid)
00674 start = end
00675 end += 4
00676 (length,) = _struct_I.unpack(str[start:end])
00677 pattern = '<%sd'%length
00678 start = end
00679 end += struct.calcsize(pattern)
00680 self.costs = struct.unpack(pattern, str[start:end])
00681 return self
00682 except struct.error as e:
00683 raise genpy.DeserializationError(e)
00684
00685
00686 def serialize_numpy(self, buff, numpy):
00687 """
00688 serialize message with numpy array types into buffer
00689 :param buff: buffer, ``StringIO``
00690 :param numpy: numpy python module
00691 """
00692 try:
00693 buff.write(_struct_B.pack(self.valid))
00694 length = len(self.costs)
00695 buff.write(_struct_I.pack(length))
00696 pattern = '<%sd'%length
00697 buff.write(self.costs.tostring())
00698 except struct.error as se: self._check_types(se)
00699 except TypeError as te: self._check_types(te)
00700
00701 def deserialize_numpy(self, str, numpy):
00702 """
00703 unpack serialized message in str into this message instance using numpy for array types
00704 :param str: byte array of serialized message, ``str``
00705 :param numpy: numpy python module
00706 """
00707 try:
00708 end = 0
00709 start = end
00710 end += 1
00711 (self.valid,) = _struct_B.unpack(str[start:end])
00712 self.valid = bool(self.valid)
00713 start = end
00714 end += 4
00715 (length,) = _struct_I.unpack(str[start:end])
00716 pattern = '<%sd'%length
00717 start = end
00718 end += struct.calcsize(pattern)
00719 self.costs = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00720 return self
00721 except struct.error as e:
00722 raise genpy.DeserializationError(e)
00723
00724 _struct_I = genpy.struct_I
00725 _struct_B = struct.Struct("<B")
00726 class GetStateCost(object):
00727 _type = 'chomp_motion_planner/GetStateCost'
00728 _md5sum = 'e5ac7b8628485266624f522d76c812fd'
00729 _request_class = GetStateCostRequest
00730 _response_class = GetStateCostResponse