00001 """autogenerated by genmsg_py from SetLaserTrajCmdRequest.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import roslib.rostime
00006 import pr2_msgs.msg
00007 import std_msgs.msg
00008
00009 class SetLaserTrajCmdRequest(roslib.message.Message):
00010 _md5sum = "83f915c37d36f61442c752779261e7d4"
00011 _type = "pr2_msgs/SetLaserTrajCmdRequest"
00012 _has_header = False
00013 _full_text = """pr2_msgs/LaserTrajCmd command
00014
00015 ================================================================================
00016 MSG: pr2_msgs/LaserTrajCmd
00017 # This message is used to set the profile that the tilt laser controller
00018 # executes.
00019 Header header
00020 string profile # options are currently "linear" or "linear_blended"
00021 float64[] position # Laser positions
00022 duration[] time_from_start # Times to reach laser positions in seconds
00023 float64 max_velocity # Set <= 0 to use default
00024 float64 max_acceleration # Set <= 0 to use default
00025
00026 ================================================================================
00027 MSG: std_msgs/Header
00028 # Standard metadata for higher-level stamped data types.
00029 # This is generally used to communicate timestamped data
00030 # in a particular coordinate frame.
00031 #
00032 # sequence ID: consecutively increasing ID
00033 uint32 seq
00034 #Two-integer timestamp that is expressed as:
00035 # * stamp.secs: seconds (stamp_secs) since epoch
00036 # * stamp.nsecs: nanoseconds since stamp_secs
00037 # time-handling sugar is provided by the client library
00038 time stamp
00039 #Frame this data is associated with
00040 # 0: no frame
00041 # 1: global frame
00042 string frame_id
00043
00044 """
00045 __slots__ = ['command']
00046 _slot_types = ['pr2_msgs/LaserTrajCmd']
00047
00048 def __init__(self, *args, **kwds):
00049 """
00050 Constructor. Any message fields that are implicitly/explicitly
00051 set to None will be assigned a default value. The recommend
00052 use is keyword arguments as this is more robust to future message
00053 changes. You cannot mix in-order arguments and keyword arguments.
00054
00055 The available fields are:
00056 command
00057
00058 @param args: complete set of field values, in .msg order
00059 @param kwds: use keyword arguments corresponding to message field names
00060 to set specific fields.
00061 """
00062 if args or kwds:
00063 super(SetLaserTrajCmdRequest, self).__init__(*args, **kwds)
00064
00065 if self.command is None:
00066 self.command = pr2_msgs.msg.LaserTrajCmd()
00067 else:
00068 self.command = pr2_msgs.msg.LaserTrajCmd()
00069
00070 def _get_types(self):
00071 """
00072 internal API method
00073 """
00074 return self._slot_types
00075
00076 def serialize(self, buff):
00077 """
00078 serialize message into buffer
00079 @param buff: buffer
00080 @type buff: StringIO
00081 """
00082 try:
00083 _x = self
00084 buff.write(_struct_3I.pack(_x.command.header.seq, _x.command.header.stamp.secs, _x.command.header.stamp.nsecs))
00085 _x = self.command.header.frame_id
00086 length = len(_x)
00087 buff.write(struct.pack('<I%ss'%length, length, _x))
00088 _x = self.command.profile
00089 length = len(_x)
00090 buff.write(struct.pack('<I%ss'%length, length, _x))
00091 length = len(self.command.position)
00092 buff.write(_struct_I.pack(length))
00093 pattern = '<%sd'%length
00094 buff.write(struct.pack(pattern, *self.command.position))
00095 length = len(self.command.time_from_start)
00096 buff.write(_struct_I.pack(length))
00097 for val1 in self.command.time_from_start:
00098 _x = val1
00099 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00100 _x = self
00101 buff.write(_struct_2d.pack(_x.command.max_velocity, _x.command.max_acceleration))
00102 except struct.error, se: self._check_types(se)
00103 except TypeError, te: self._check_types(te)
00104
00105 def deserialize(self, str):
00106 """
00107 unpack serialized message in str into this message instance
00108 @param str: byte array of serialized message
00109 @type str: str
00110 """
00111 try:
00112 if self.command is None:
00113 self.command = pr2_msgs.msg.LaserTrajCmd()
00114 end = 0
00115 _x = self
00116 start = end
00117 end += 12
00118 (_x.command.header.seq, _x.command.header.stamp.secs, _x.command.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00119 start = end
00120 end += 4
00121 (length,) = _struct_I.unpack(str[start:end])
00122 start = end
00123 end += length
00124 self.command.header.frame_id = str[start:end]
00125 start = end
00126 end += 4
00127 (length,) = _struct_I.unpack(str[start:end])
00128 start = end
00129 end += length
00130 self.command.profile = str[start:end]
00131 start = end
00132 end += 4
00133 (length,) = _struct_I.unpack(str[start:end])
00134 pattern = '<%sd'%length
00135 start = end
00136 end += struct.calcsize(pattern)
00137 self.command.position = struct.unpack(pattern, str[start:end])
00138 start = end
00139 end += 4
00140 (length,) = _struct_I.unpack(str[start:end])
00141 self.command.time_from_start = []
00142 for i in xrange(0, length):
00143 val1 = roslib.rostime.Duration()
00144 _x = val1
00145 start = end
00146 end += 8
00147 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00148 self.command.time_from_start.append(val1)
00149 _x = self
00150 start = end
00151 end += 16
00152 (_x.command.max_velocity, _x.command.max_acceleration,) = _struct_2d.unpack(str[start:end])
00153 return self
00154 except struct.error, e:
00155 raise roslib.message.DeserializationError(e)
00156
00157
00158 def serialize_numpy(self, buff, numpy):
00159 """
00160 serialize message with numpy array types into buffer
00161 @param buff: buffer
00162 @type buff: StringIO
00163 @param numpy: numpy python module
00164 @type numpy module
00165 """
00166 try:
00167 _x = self
00168 buff.write(_struct_3I.pack(_x.command.header.seq, _x.command.header.stamp.secs, _x.command.header.stamp.nsecs))
00169 _x = self.command.header.frame_id
00170 length = len(_x)
00171 buff.write(struct.pack('<I%ss'%length, length, _x))
00172 _x = self.command.profile
00173 length = len(_x)
00174 buff.write(struct.pack('<I%ss'%length, length, _x))
00175 length = len(self.command.position)
00176 buff.write(_struct_I.pack(length))
00177 pattern = '<%sd'%length
00178 buff.write(self.command.position.tostring())
00179 length = len(self.command.time_from_start)
00180 buff.write(_struct_I.pack(length))
00181 for val1 in self.command.time_from_start:
00182 _x = val1
00183 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00184 _x = self
00185 buff.write(_struct_2d.pack(_x.command.max_velocity, _x.command.max_acceleration))
00186 except struct.error, se: self._check_types(se)
00187 except TypeError, te: self._check_types(te)
00188
00189 def deserialize_numpy(self, str, numpy):
00190 """
00191 unpack serialized message in str into this message instance using numpy for array types
00192 @param str: byte array of serialized message
00193 @type str: str
00194 @param numpy: numpy python module
00195 @type numpy: module
00196 """
00197 try:
00198 if self.command is None:
00199 self.command = pr2_msgs.msg.LaserTrajCmd()
00200 end = 0
00201 _x = self
00202 start = end
00203 end += 12
00204 (_x.command.header.seq, _x.command.header.stamp.secs, _x.command.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00205 start = end
00206 end += 4
00207 (length,) = _struct_I.unpack(str[start:end])
00208 start = end
00209 end += length
00210 self.command.header.frame_id = str[start:end]
00211 start = end
00212 end += 4
00213 (length,) = _struct_I.unpack(str[start:end])
00214 start = end
00215 end += length
00216 self.command.profile = str[start:end]
00217 start = end
00218 end += 4
00219 (length,) = _struct_I.unpack(str[start:end])
00220 pattern = '<%sd'%length
00221 start = end
00222 end += struct.calcsize(pattern)
00223 self.command.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00224 start = end
00225 end += 4
00226 (length,) = _struct_I.unpack(str[start:end])
00227 self.command.time_from_start = []
00228 for i in xrange(0, length):
00229 val1 = roslib.rostime.Duration()
00230 _x = val1
00231 start = end
00232 end += 8
00233 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00234 self.command.time_from_start.append(val1)
00235 _x = self
00236 start = end
00237 end += 16
00238 (_x.command.max_velocity, _x.command.max_acceleration,) = _struct_2d.unpack(str[start:end])
00239 return self
00240 except struct.error, e:
00241 raise roslib.message.DeserializationError(e)
00242
00243 _struct_I = roslib.message.struct_I
00244 _struct_2d = struct.Struct("<2d")
00245 _struct_3I = struct.Struct("<3I")
00246 _struct_2i = struct.Struct("<2i")
00247 """autogenerated by genmsg_py from SetLaserTrajCmdResponse.msg. Do not edit."""
00248 import roslib.message
00249 import struct
00250
00251 import roslib.rostime
00252
00253 class SetLaserTrajCmdResponse(roslib.message.Message):
00254 _md5sum = "3888666920054f1ef39d2df7a5d94b02"
00255 _type = "pr2_msgs/SetLaserTrajCmdResponse"
00256 _has_header = False
00257 _full_text = """time start_time
00258
00259 """
00260 __slots__ = ['start_time']
00261 _slot_types = ['time']
00262
00263 def __init__(self, *args, **kwds):
00264 """
00265 Constructor. Any message fields that are implicitly/explicitly
00266 set to None will be assigned a default value. The recommend
00267 use is keyword arguments as this is more robust to future message
00268 changes. You cannot mix in-order arguments and keyword arguments.
00269
00270 The available fields are:
00271 start_time
00272
00273 @param args: complete set of field values, in .msg order
00274 @param kwds: use keyword arguments corresponding to message field names
00275 to set specific fields.
00276 """
00277 if args or kwds:
00278 super(SetLaserTrajCmdResponse, self).__init__(*args, **kwds)
00279
00280 if self.start_time is None:
00281 self.start_time = roslib.rostime.Time()
00282 else:
00283 self.start_time = roslib.rostime.Time()
00284
00285 def _get_types(self):
00286 """
00287 internal API method
00288 """
00289 return self._slot_types
00290
00291 def serialize(self, buff):
00292 """
00293 serialize message into buffer
00294 @param buff: buffer
00295 @type buff: StringIO
00296 """
00297 try:
00298 _x = self
00299 buff.write(_struct_2I.pack(_x.start_time.secs, _x.start_time.nsecs))
00300 except struct.error, se: self._check_types(se)
00301 except TypeError, te: self._check_types(te)
00302
00303 def deserialize(self, str):
00304 """
00305 unpack serialized message in str into this message instance
00306 @param str: byte array of serialized message
00307 @type str: str
00308 """
00309 try:
00310 if self.start_time is None:
00311 self.start_time = roslib.rostime.Time()
00312 end = 0
00313 _x = self
00314 start = end
00315 end += 8
00316 (_x.start_time.secs, _x.start_time.nsecs,) = _struct_2I.unpack(str[start:end])
00317 self.start_time.canon()
00318 return self
00319 except struct.error, e:
00320 raise roslib.message.DeserializationError(e)
00321
00322
00323 def serialize_numpy(self, buff, numpy):
00324 """
00325 serialize message with numpy array types into buffer
00326 @param buff: buffer
00327 @type buff: StringIO
00328 @param numpy: numpy python module
00329 @type numpy module
00330 """
00331 try:
00332 _x = self
00333 buff.write(_struct_2I.pack(_x.start_time.secs, _x.start_time.nsecs))
00334 except struct.error, se: self._check_types(se)
00335 except TypeError, te: self._check_types(te)
00336
00337 def deserialize_numpy(self, str, numpy):
00338 """
00339 unpack serialized message in str into this message instance using numpy for array types
00340 @param str: byte array of serialized message
00341 @type str: str
00342 @param numpy: numpy python module
00343 @type numpy: module
00344 """
00345 try:
00346 if self.start_time is None:
00347 self.start_time = roslib.rostime.Time()
00348 end = 0
00349 _x = self
00350 start = end
00351 end += 8
00352 (_x.start_time.secs, _x.start_time.nsecs,) = _struct_2I.unpack(str[start:end])
00353 self.start_time.canon()
00354 return self
00355 except struct.error, e:
00356 raise roslib.message.DeserializationError(e)
00357
00358 _struct_I = roslib.message.struct_I
00359 _struct_2I = struct.Struct("<2I")
00360 class SetLaserTrajCmd(roslib.message.ServiceDefinition):
00361 _type = 'pr2_msgs/SetLaserTrajCmd'
00362 _md5sum = '28fe2ce397611c999952c74a1ea882aa'
00363 _request_class = SetLaserTrajCmdRequest
00364 _response_class = SetLaserTrajCmdResponse