00001 """autogenerated by genmsg_py from JointState.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import std_msgs.msg
00006
00007 class JointState(roslib.message.Message):
00008 _md5sum = "3066dcd76a6cfaef579bd0f34173e9fd"
00009 _type = "sensor_msgs/JointState"
00010 _has_header = True
00011 _full_text = """# This is a message that holds data to describe the state of a set of torque controlled joints.
00012 #
00013 # The state of each joint (revolute or prismatic) is defined by:
00014 # * the position of the joint (rad or m),
00015 # * the velocity of the joint (rad/s or m/s) and
00016 # * the effort that is applied in the joint (Nm or N).
00017 #
00018 # Each joint is uniquely identified by its name
00019 # The header specifies the time at which the joint states were recorded. All the joint states
00020 # in one message have to be recorded at the same time.
00021 #
00022 # This message consists of a multiple arrays, one for each part of the joint state.
00023 # The goal is to make each of the fields optional. When e.g. your joints have no
00024 # effort associated with them, you can leave the effort array empty.
00025 #
00026 # All arrays in this message should have the same size, or be empty.
00027 # This is the only way to uniquely associate the joint name with the correct
00028 # states.
00029
00030
00031 Header header
00032
00033 string[] name
00034 float64[] position
00035 float64[] velocity
00036 float64[] effort
00037
00038 ================================================================================
00039 MSG: std_msgs/Header
00040 # Standard metadata for higher-level stamped data types.
00041 # This is generally used to communicate timestamped data
00042 # in a particular coordinate frame.
00043 #
00044 # sequence ID: consecutively increasing ID
00045 uint32 seq
00046 #Two-integer timestamp that is expressed as:
00047 # * stamp.secs: seconds (stamp_secs) since epoch
00048 # * stamp.nsecs: nanoseconds since stamp_secs
00049 # time-handling sugar is provided by the client library
00050 time stamp
00051 #Frame this data is associated with
00052 # 0: no frame
00053 # 1: global frame
00054 string frame_id
00055
00056 """
00057 __slots__ = ['header','name','position','velocity','effort']
00058 _slot_types = ['Header','string[]','float64[]','float64[]','float64[]']
00059
00060 def __init__(self, *args, **kwds):
00061 """
00062 Constructor. Any message fields that are implicitly/explicitly
00063 set to None will be assigned a default value. The recommend
00064 use is keyword arguments as this is more robust to future message
00065 changes. You cannot mix in-order arguments and keyword arguments.
00066
00067 The available fields are:
00068 header,name,position,velocity,effort
00069
00070 @param args: complete set of field values, in .msg order
00071 @param kwds: use keyword arguments corresponding to message field names
00072 to set specific fields.
00073 """
00074 if args or kwds:
00075 super(JointState, self).__init__(*args, **kwds)
00076
00077 if self.header is None:
00078 self.header = std_msgs.msg._Header.Header()
00079 if self.name is None:
00080 self.name = []
00081 if self.position is None:
00082 self.position = []
00083 if self.velocity is None:
00084 self.velocity = []
00085 if self.effort is None:
00086 self.effort = []
00087 else:
00088 self.header = std_msgs.msg._Header.Header()
00089 self.name = []
00090 self.position = []
00091 self.velocity = []
00092 self.effort = []
00093
00094 def _get_types(self):
00095 """
00096 internal API method
00097 """
00098 return self._slot_types
00099
00100 def serialize(self, buff):
00101 """
00102 serialize message into buffer
00103 @param buff: buffer
00104 @type buff: StringIO
00105 """
00106 try:
00107 _x = self
00108 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00109 _x = self.header.frame_id
00110 length = len(_x)
00111 buff.write(struct.pack('<I%ss'%length, length, _x))
00112 length = len(self.name)
00113 buff.write(_struct_I.pack(length))
00114 for val1 in self.name:
00115 length = len(val1)
00116 buff.write(struct.pack('<I%ss'%length, length, val1))
00117 length = len(self.position)
00118 buff.write(_struct_I.pack(length))
00119 pattern = '<%sd'%length
00120 buff.write(struct.pack(pattern, *self.position))
00121 length = len(self.velocity)
00122 buff.write(_struct_I.pack(length))
00123 pattern = '<%sd'%length
00124 buff.write(struct.pack(pattern, *self.velocity))
00125 length = len(self.effort)
00126 buff.write(_struct_I.pack(length))
00127 pattern = '<%sd'%length
00128 buff.write(struct.pack(pattern, *self.effort))
00129 except struct.error as se: self._check_types(se)
00130 except TypeError as te: self._check_types(te)
00131
00132 def deserialize(self, str):
00133 """
00134 unpack serialized message in str into this message instance
00135 @param str: byte array of serialized message
00136 @type str: str
00137 """
00138 try:
00139 if self.header is None:
00140 self.header = std_msgs.msg._Header.Header()
00141 end = 0
00142 _x = self
00143 start = end
00144 end += 12
00145 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00146 start = end
00147 end += 4
00148 (length,) = _struct_I.unpack(str[start:end])
00149 start = end
00150 end += length
00151 self.header.frame_id = str[start:end]
00152 start = end
00153 end += 4
00154 (length,) = _struct_I.unpack(str[start:end])
00155 self.name = []
00156 for i in range(0, length):
00157 start = end
00158 end += 4
00159 (length,) = _struct_I.unpack(str[start:end])
00160 start = end
00161 end += length
00162 val1 = str[start:end]
00163 self.name.append(val1)
00164 start = end
00165 end += 4
00166 (length,) = _struct_I.unpack(str[start:end])
00167 pattern = '<%sd'%length
00168 start = end
00169 end += struct.calcsize(pattern)
00170 self.position = struct.unpack(pattern, str[start:end])
00171 start = end
00172 end += 4
00173 (length,) = _struct_I.unpack(str[start:end])
00174 pattern = '<%sd'%length
00175 start = end
00176 end += struct.calcsize(pattern)
00177 self.velocity = struct.unpack(pattern, str[start:end])
00178 start = end
00179 end += 4
00180 (length,) = _struct_I.unpack(str[start:end])
00181 pattern = '<%sd'%length
00182 start = end
00183 end += struct.calcsize(pattern)
00184 self.effort = struct.unpack(pattern, str[start:end])
00185 return self
00186 except struct.error as e:
00187 raise roslib.message.DeserializationError(e)
00188
00189
00190 def serialize_numpy(self, buff, numpy):
00191 """
00192 serialize message with numpy array types into buffer
00193 @param buff: buffer
00194 @type buff: StringIO
00195 @param numpy: numpy python module
00196 @type numpy module
00197 """
00198 try:
00199 _x = self
00200 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00201 _x = self.header.frame_id
00202 length = len(_x)
00203 buff.write(struct.pack('<I%ss'%length, length, _x))
00204 length = len(self.name)
00205 buff.write(_struct_I.pack(length))
00206 for val1 in self.name:
00207 length = len(val1)
00208 buff.write(struct.pack('<I%ss'%length, length, val1))
00209 length = len(self.position)
00210 buff.write(_struct_I.pack(length))
00211 pattern = '<%sd'%length
00212 buff.write(self.position.tostring())
00213 length = len(self.velocity)
00214 buff.write(_struct_I.pack(length))
00215 pattern = '<%sd'%length
00216 buff.write(self.velocity.tostring())
00217 length = len(self.effort)
00218 buff.write(_struct_I.pack(length))
00219 pattern = '<%sd'%length
00220 buff.write(self.effort.tostring())
00221 except struct.error as se: self._check_types(se)
00222 except TypeError as te: self._check_types(te)
00223
00224 def deserialize_numpy(self, str, numpy):
00225 """
00226 unpack serialized message in str into this message instance using numpy for array types
00227 @param str: byte array of serialized message
00228 @type str: str
00229 @param numpy: numpy python module
00230 @type numpy: module
00231 """
00232 try:
00233 if self.header is None:
00234 self.header = std_msgs.msg._Header.Header()
00235 end = 0
00236 _x = self
00237 start = end
00238 end += 12
00239 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00240 start = end
00241 end += 4
00242 (length,) = _struct_I.unpack(str[start:end])
00243 start = end
00244 end += length
00245 self.header.frame_id = str[start:end]
00246 start = end
00247 end += 4
00248 (length,) = _struct_I.unpack(str[start:end])
00249 self.name = []
00250 for i in range(0, length):
00251 start = end
00252 end += 4
00253 (length,) = _struct_I.unpack(str[start:end])
00254 start = end
00255 end += length
00256 val1 = str[start:end]
00257 self.name.append(val1)
00258 start = end
00259 end += 4
00260 (length,) = _struct_I.unpack(str[start:end])
00261 pattern = '<%sd'%length
00262 start = end
00263 end += struct.calcsize(pattern)
00264 self.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00265 start = end
00266 end += 4
00267 (length,) = _struct_I.unpack(str[start:end])
00268 pattern = '<%sd'%length
00269 start = end
00270 end += struct.calcsize(pattern)
00271 self.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00272 start = end
00273 end += 4
00274 (length,) = _struct_I.unpack(str[start:end])
00275 pattern = '<%sd'%length
00276 start = end
00277 end += struct.calcsize(pattern)
00278 self.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00279 return self
00280 except struct.error as e:
00281 raise roslib.message.DeserializationError(e)
00282
00283 _struct_I = roslib.message.struct_I
00284 _struct_3I = struct.Struct("<3I")