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