00001 """autogenerated by genmsg_py from JointPath.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import motion_planning_msgs.msg
00006 import std_msgs.msg
00007
00008 class JointPath(roslib.message.Message):
00009 _md5sum = "f0b877c71d33d7868ae41a2e7a36d72d"
00010 _type = "motion_planning_msgs/JointPath"
00011 _has_header = True
00012 _full_text = """# This message defines a joint path
00013
00014 # The standard ROS header
00015 Header header
00016
00017 # Vector of joint names for which positions are specified.
00018 # The size of this vector must match the size of each waypoint below
00019 string[] joint_names
00020
00021 # A vector of waypoints.
00022 # Each waypoint is a vector of joint positions.
00023 # Each waypoint must have the same size as the vector of joint names
00024 JointPathPoint[] points
00025 ================================================================================
00026 MSG: std_msgs/Header
00027 # Standard metadata for higher-level stamped data types.
00028 # This is generally used to communicate timestamped data
00029 # in a particular coordinate frame.
00030 #
00031 # sequence ID: consecutively increasing ID
00032 uint32 seq
00033 #Two-integer timestamp that is expressed as:
00034 # * stamp.secs: seconds (stamp_secs) since epoch
00035 # * stamp.nsecs: nanoseconds since stamp_secs
00036 # time-handling sugar is provided by the client library
00037 time stamp
00038 #Frame this data is associated with
00039 # 0: no frame
00040 # 1: global frame
00041 string frame_id
00042
00043 ================================================================================
00044 MSG: motion_planning_msgs/JointPathPoint
00045 # The joint path point contains a vector of joint positions.
00046 float64[] positions
00047
00048 """
00049 __slots__ = ['header','joint_names','points']
00050 _slot_types = ['Header','string[]','motion_planning_msgs/JointPathPoint[]']
00051
00052 def __init__(self, *args, **kwds):
00053 """
00054 Constructor. Any message fields that are implicitly/explicitly
00055 set to None will be assigned a default value. The recommend
00056 use is keyword arguments as this is more robust to future message
00057 changes. You cannot mix in-order arguments and keyword arguments.
00058
00059 The available fields are:
00060 header,joint_names,points
00061
00062 @param args: complete set of field values, in .msg order
00063 @param kwds: use keyword arguments corresponding to message field names
00064 to set specific fields.
00065 """
00066 if args or kwds:
00067 super(JointPath, self).__init__(*args, **kwds)
00068
00069 if self.header is None:
00070 self.header = std_msgs.msg._Header.Header()
00071 if self.joint_names is None:
00072 self.joint_names = []
00073 if self.points is None:
00074 self.points = []
00075 else:
00076 self.header = std_msgs.msg._Header.Header()
00077 self.joint_names = []
00078 self.points = []
00079
00080 def _get_types(self):
00081 """
00082 internal API method
00083 """
00084 return self._slot_types
00085
00086 def serialize(self, buff):
00087 """
00088 serialize message into buffer
00089 @param buff: buffer
00090 @type buff: StringIO
00091 """
00092 try:
00093 _x = self
00094 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00095 _x = self.header.frame_id
00096 length = len(_x)
00097 buff.write(struct.pack('<I%ss'%length, length, _x))
00098 length = len(self.joint_names)
00099 buff.write(_struct_I.pack(length))
00100 for val1 in self.joint_names:
00101 length = len(val1)
00102 buff.write(struct.pack('<I%ss'%length, length, val1))
00103 length = len(self.points)
00104 buff.write(_struct_I.pack(length))
00105 for val1 in self.points:
00106 length = len(val1.positions)
00107 buff.write(_struct_I.pack(length))
00108 pattern = '<%sd'%length
00109 buff.write(struct.pack(pattern, *val1.positions))
00110 except struct.error, se: self._check_types(se)
00111 except TypeError, te: self._check_types(te)
00112
00113 def deserialize(self, str):
00114 """
00115 unpack serialized message in str into this message instance
00116 @param str: byte array of serialized message
00117 @type str: str
00118 """
00119 try:
00120 if self.header is None:
00121 self.header = std_msgs.msg._Header.Header()
00122 end = 0
00123 _x = self
00124 start = end
00125 end += 12
00126 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00127 start = end
00128 end += 4
00129 (length,) = _struct_I.unpack(str[start:end])
00130 start = end
00131 end += length
00132 self.header.frame_id = str[start:end]
00133 start = end
00134 end += 4
00135 (length,) = _struct_I.unpack(str[start:end])
00136 self.joint_names = []
00137 for i in xrange(0, length):
00138 start = end
00139 end += 4
00140 (length,) = _struct_I.unpack(str[start:end])
00141 start = end
00142 end += length
00143 val1 = str[start:end]
00144 self.joint_names.append(val1)
00145 start = end
00146 end += 4
00147 (length,) = _struct_I.unpack(str[start:end])
00148 self.points = []
00149 for i in xrange(0, length):
00150 val1 = motion_planning_msgs.msg.JointPathPoint()
00151 start = end
00152 end += 4
00153 (length,) = _struct_I.unpack(str[start:end])
00154 pattern = '<%sd'%length
00155 start = end
00156 end += struct.calcsize(pattern)
00157 val1.positions = struct.unpack(pattern, str[start:end])
00158 self.points.append(val1)
00159 return self
00160 except struct.error, e:
00161 raise roslib.message.DeserializationError(e)
00162
00163
00164 def serialize_numpy(self, buff, numpy):
00165 """
00166 serialize message with numpy array types into buffer
00167 @param buff: buffer
00168 @type buff: StringIO
00169 @param numpy: numpy python module
00170 @type numpy module
00171 """
00172 try:
00173 _x = self
00174 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00175 _x = self.header.frame_id
00176 length = len(_x)
00177 buff.write(struct.pack('<I%ss'%length, length, _x))
00178 length = len(self.joint_names)
00179 buff.write(_struct_I.pack(length))
00180 for val1 in self.joint_names:
00181 length = len(val1)
00182 buff.write(struct.pack('<I%ss'%length, length, val1))
00183 length = len(self.points)
00184 buff.write(_struct_I.pack(length))
00185 for val1 in self.points:
00186 length = len(val1.positions)
00187 buff.write(_struct_I.pack(length))
00188 pattern = '<%sd'%length
00189 buff.write(val1.positions.tostring())
00190 except struct.error, se: self._check_types(se)
00191 except TypeError, te: self._check_types(te)
00192
00193 def deserialize_numpy(self, str, numpy):
00194 """
00195 unpack serialized message in str into this message instance using numpy for array types
00196 @param str: byte array of serialized message
00197 @type str: str
00198 @param numpy: numpy python module
00199 @type numpy: module
00200 """
00201 try:
00202 if self.header is None:
00203 self.header = std_msgs.msg._Header.Header()
00204 end = 0
00205 _x = self
00206 start = end
00207 end += 12
00208 (_x.header.seq, _x.header.stamp.secs, _x.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 self.header.frame_id = str[start:end]
00215 start = end
00216 end += 4
00217 (length,) = _struct_I.unpack(str[start:end])
00218 self.joint_names = []
00219 for i in xrange(0, length):
00220 start = end
00221 end += 4
00222 (length,) = _struct_I.unpack(str[start:end])
00223 start = end
00224 end += length
00225 val1 = str[start:end]
00226 self.joint_names.append(val1)
00227 start = end
00228 end += 4
00229 (length,) = _struct_I.unpack(str[start:end])
00230 self.points = []
00231 for i in xrange(0, length):
00232 val1 = motion_planning_msgs.msg.JointPathPoint()
00233 start = end
00234 end += 4
00235 (length,) = _struct_I.unpack(str[start:end])
00236 pattern = '<%sd'%length
00237 start = end
00238 end += struct.calcsize(pattern)
00239 val1.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00240 self.points.append(val1)
00241 return self
00242 except struct.error, e:
00243 raise roslib.message.DeserializationError(e)
00244
00245 _struct_I = roslib.message.struct_I
00246 _struct_3I = struct.Struct("<3I")