_GetNavPoseActionGoal.py
Go to the documentation of this file.
00001 """autogenerated by genpy from pr2_object_manipulation_msgs/GetNavPoseActionGoal.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 pr2_object_manipulation_msgs.msg
00008 import geometry_msgs.msg
00009 import genpy
00010 import actionlib_msgs.msg
00011 import std_msgs.msg
00012 
00013 class GetNavPoseActionGoal(genpy.Message):
00014   _md5sum = "e46735325132cb6eb60ed036d0430c18"
00015   _type = "pr2_object_manipulation_msgs/GetNavPoseActionGoal"
00016   _has_header = True #flag to mark the presence of a Header object
00017   _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018 
00019 Header header
00020 actionlib_msgs/GoalID goal_id
00021 GetNavPoseGoal goal
00022 
00023 ================================================================================
00024 MSG: std_msgs/Header
00025 # Standard metadata for higher-level stamped data types.
00026 # This is generally used to communicate timestamped data 
00027 # in a particular coordinate frame.
00028 # 
00029 # sequence ID: consecutively increasing ID 
00030 uint32 seq
00031 #Two-integer timestamp that is expressed as:
00032 # * stamp.secs: seconds (stamp_secs) since epoch
00033 # * stamp.nsecs: nanoseconds since stamp_secs
00034 # time-handling sugar is provided by the client library
00035 time stamp
00036 #Frame this data is associated with
00037 # 0: no frame
00038 # 1: global frame
00039 string frame_id
00040 
00041 ================================================================================
00042 MSG: actionlib_msgs/GoalID
00043 # The stamp should store the time at which this goal was requested.
00044 # It is used by an action server when it tries to preempt all
00045 # goals that were requested before a certain time
00046 time stamp
00047 
00048 # The id provides a way to associate feedback and
00049 # result message with specific goal requests. The id
00050 # specified must be unique.
00051 string id
00052 
00053 
00054 ================================================================================
00055 MSG: pr2_object_manipulation_msgs/GetNavPoseGoal
00056 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00057 
00058 # a seed position for the pose marker. If empty (quaternion of norm 0)
00059 # the marker will be initialized at the current pose of the header frame.
00060 geometry_msgs/PoseStamped starting_pose
00061 
00062 # The maximum in-plane distance that the action will allow
00063 float32 max_distance
00064 
00065 ================================================================================
00066 MSG: geometry_msgs/PoseStamped
00067 # A Pose with reference coordinate frame and timestamp
00068 Header header
00069 Pose pose
00070 
00071 ================================================================================
00072 MSG: geometry_msgs/Pose
00073 # A representation of pose in free space, composed of postion and orientation. 
00074 Point position
00075 Quaternion orientation
00076 
00077 ================================================================================
00078 MSG: geometry_msgs/Point
00079 # This contains the position of a point in free space
00080 float64 x
00081 float64 y
00082 float64 z
00083 
00084 ================================================================================
00085 MSG: geometry_msgs/Quaternion
00086 # This represents an orientation in free space in quaternion form.
00087 
00088 float64 x
00089 float64 y
00090 float64 z
00091 float64 w
00092 
00093 """
00094   __slots__ = ['header','goal_id','goal']
00095   _slot_types = ['std_msgs/Header','actionlib_msgs/GoalID','pr2_object_manipulation_msgs/GetNavPoseGoal']
00096 
00097   def __init__(self, *args, **kwds):
00098     """
00099     Constructor. Any message fields that are implicitly/explicitly
00100     set to None will be assigned a default value. The recommend
00101     use is keyword arguments as this is more robust to future message
00102     changes.  You cannot mix in-order arguments and keyword arguments.
00103 
00104     The available fields are:
00105        header,goal_id,goal
00106 
00107     :param args: complete set of field values, in .msg order
00108     :param kwds: use keyword arguments corresponding to message field names
00109     to set specific fields.
00110     """
00111     if args or kwds:
00112       super(GetNavPoseActionGoal, self).__init__(*args, **kwds)
00113       #message fields cannot be None, assign default values for those that are
00114       if self.header is None:
00115         self.header = std_msgs.msg.Header()
00116       if self.goal_id is None:
00117         self.goal_id = actionlib_msgs.msg.GoalID()
00118       if self.goal is None:
00119         self.goal = pr2_object_manipulation_msgs.msg.GetNavPoseGoal()
00120     else:
00121       self.header = std_msgs.msg.Header()
00122       self.goal_id = actionlib_msgs.msg.GoalID()
00123       self.goal = pr2_object_manipulation_msgs.msg.GetNavPoseGoal()
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, ``StringIO``
00135     """
00136     try:
00137       _x = self
00138       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00139       _x = self.header.frame_id
00140       length = len(_x)
00141       if python3 or type(_x) == unicode:
00142         _x = _x.encode('utf-8')
00143         length = len(_x)
00144       buff.write(struct.pack('<I%ss'%length, length, _x))
00145       _x = self
00146       buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00147       _x = self.goal_id.id
00148       length = len(_x)
00149       if python3 or type(_x) == unicode:
00150         _x = _x.encode('utf-8')
00151         length = len(_x)
00152       buff.write(struct.pack('<I%ss'%length, length, _x))
00153       _x = self
00154       buff.write(_struct_3I.pack(_x.goal.starting_pose.header.seq, _x.goal.starting_pose.header.stamp.secs, _x.goal.starting_pose.header.stamp.nsecs))
00155       _x = self.goal.starting_pose.header.frame_id
00156       length = len(_x)
00157       if python3 or type(_x) == unicode:
00158         _x = _x.encode('utf-8')
00159         length = len(_x)
00160       buff.write(struct.pack('<I%ss'%length, length, _x))
00161       _x = self
00162       buff.write(_struct_7df.pack(_x.goal.starting_pose.pose.position.x, _x.goal.starting_pose.pose.position.y, _x.goal.starting_pose.pose.position.z, _x.goal.starting_pose.pose.orientation.x, _x.goal.starting_pose.pose.orientation.y, _x.goal.starting_pose.pose.orientation.z, _x.goal.starting_pose.pose.orientation.w, _x.goal.max_distance))
00163     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00164     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00165 
00166   def deserialize(self, str):
00167     """
00168     unpack serialized message in str into this message instance
00169     :param str: byte array of serialized message, ``str``
00170     """
00171     try:
00172       if self.header is None:
00173         self.header = std_msgs.msg.Header()
00174       if self.goal_id is None:
00175         self.goal_id = actionlib_msgs.msg.GoalID()
00176       if self.goal is None:
00177         self.goal = pr2_object_manipulation_msgs.msg.GetNavPoseGoal()
00178       end = 0
00179       _x = self
00180       start = end
00181       end += 12
00182       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00183       start = end
00184       end += 4
00185       (length,) = _struct_I.unpack(str[start:end])
00186       start = end
00187       end += length
00188       if python3:
00189         self.header.frame_id = str[start:end].decode('utf-8')
00190       else:
00191         self.header.frame_id = str[start:end]
00192       _x = self
00193       start = end
00194       end += 8
00195       (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00196       start = end
00197       end += 4
00198       (length,) = _struct_I.unpack(str[start:end])
00199       start = end
00200       end += length
00201       if python3:
00202         self.goal_id.id = str[start:end].decode('utf-8')
00203       else:
00204         self.goal_id.id = str[start:end]
00205       _x = self
00206       start = end
00207       end += 12
00208       (_x.goal.starting_pose.header.seq, _x.goal.starting_pose.header.stamp.secs, _x.goal.starting_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00209       start = end
00210       end += 4
00211       (length,) = _struct_I.unpack(str[start:end])
00212       start = end
00213       end += length
00214       if python3:
00215         self.goal.starting_pose.header.frame_id = str[start:end].decode('utf-8')
00216       else:
00217         self.goal.starting_pose.header.frame_id = str[start:end]
00218       _x = self
00219       start = end
00220       end += 60
00221       (_x.goal.starting_pose.pose.position.x, _x.goal.starting_pose.pose.position.y, _x.goal.starting_pose.pose.position.z, _x.goal.starting_pose.pose.orientation.x, _x.goal.starting_pose.pose.orientation.y, _x.goal.starting_pose.pose.orientation.z, _x.goal.starting_pose.pose.orientation.w, _x.goal.max_distance,) = _struct_7df.unpack(str[start:end])
00222       return self
00223     except struct.error as e:
00224       raise genpy.DeserializationError(e) #most likely buffer underfill
00225 
00226 
00227   def serialize_numpy(self, buff, numpy):
00228     """
00229     serialize message with numpy array types into buffer
00230     :param buff: buffer, ``StringIO``
00231     :param numpy: numpy python module
00232     """
00233     try:
00234       _x = self
00235       buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00236       _x = self.header.frame_id
00237       length = len(_x)
00238       if python3 or type(_x) == unicode:
00239         _x = _x.encode('utf-8')
00240         length = len(_x)
00241       buff.write(struct.pack('<I%ss'%length, length, _x))
00242       _x = self
00243       buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs))
00244       _x = self.goal_id.id
00245       length = len(_x)
00246       if python3 or type(_x) == unicode:
00247         _x = _x.encode('utf-8')
00248         length = len(_x)
00249       buff.write(struct.pack('<I%ss'%length, length, _x))
00250       _x = self
00251       buff.write(_struct_3I.pack(_x.goal.starting_pose.header.seq, _x.goal.starting_pose.header.stamp.secs, _x.goal.starting_pose.header.stamp.nsecs))
00252       _x = self.goal.starting_pose.header.frame_id
00253       length = len(_x)
00254       if python3 or type(_x) == unicode:
00255         _x = _x.encode('utf-8')
00256         length = len(_x)
00257       buff.write(struct.pack('<I%ss'%length, length, _x))
00258       _x = self
00259       buff.write(_struct_7df.pack(_x.goal.starting_pose.pose.position.x, _x.goal.starting_pose.pose.position.y, _x.goal.starting_pose.pose.position.z, _x.goal.starting_pose.pose.orientation.x, _x.goal.starting_pose.pose.orientation.y, _x.goal.starting_pose.pose.orientation.z, _x.goal.starting_pose.pose.orientation.w, _x.goal.max_distance))
00260     except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00261     except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00262 
00263   def deserialize_numpy(self, str, numpy):
00264     """
00265     unpack serialized message in str into this message instance using numpy for array types
00266     :param str: byte array of serialized message, ``str``
00267     :param numpy: numpy python module
00268     """
00269     try:
00270       if self.header is None:
00271         self.header = std_msgs.msg.Header()
00272       if self.goal_id is None:
00273         self.goal_id = actionlib_msgs.msg.GoalID()
00274       if self.goal is None:
00275         self.goal = pr2_object_manipulation_msgs.msg.GetNavPoseGoal()
00276       end = 0
00277       _x = self
00278       start = end
00279       end += 12
00280       (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00281       start = end
00282       end += 4
00283       (length,) = _struct_I.unpack(str[start:end])
00284       start = end
00285       end += length
00286       if python3:
00287         self.header.frame_id = str[start:end].decode('utf-8')
00288       else:
00289         self.header.frame_id = str[start:end]
00290       _x = self
00291       start = end
00292       end += 8
00293       (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00294       start = end
00295       end += 4
00296       (length,) = _struct_I.unpack(str[start:end])
00297       start = end
00298       end += length
00299       if python3:
00300         self.goal_id.id = str[start:end].decode('utf-8')
00301       else:
00302         self.goal_id.id = str[start:end]
00303       _x = self
00304       start = end
00305       end += 12
00306       (_x.goal.starting_pose.header.seq, _x.goal.starting_pose.header.stamp.secs, _x.goal.starting_pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00307       start = end
00308       end += 4
00309       (length,) = _struct_I.unpack(str[start:end])
00310       start = end
00311       end += length
00312       if python3:
00313         self.goal.starting_pose.header.frame_id = str[start:end].decode('utf-8')
00314       else:
00315         self.goal.starting_pose.header.frame_id = str[start:end]
00316       _x = self
00317       start = end
00318       end += 60
00319       (_x.goal.starting_pose.pose.position.x, _x.goal.starting_pose.pose.position.y, _x.goal.starting_pose.pose.position.z, _x.goal.starting_pose.pose.orientation.x, _x.goal.starting_pose.pose.orientation.y, _x.goal.starting_pose.pose.orientation.z, _x.goal.starting_pose.pose.orientation.w, _x.goal.max_distance,) = _struct_7df.unpack(str[start:end])
00320       return self
00321     except struct.error as e:
00322       raise genpy.DeserializationError(e) #most likely buffer underfill
00323 
00324 _struct_I = genpy.struct_I
00325 _struct_3I = struct.Struct("<3I")
00326 _struct_2I = struct.Struct("<2I")
00327 _struct_7df = struct.Struct("<7df")


pr2_object_manipulation_msgs
Author(s): Matei Ciocarlie
autogenerated on Mon Oct 6 2014 11:55:20