00001 """autogenerated by genpy from asctec_hl_comm/MavCtrlSrvRequest.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 asctec_hl_comm.msg
00008 import std_msgs.msg
00009
00010 class MavCtrlSrvRequest(genpy.Message):
00011 _md5sum = "38a627ff8fcd6d0f534f521aa37786af"
00012 _type = "asctec_hl_comm/MavCtrlSrvRequest"
00013 _has_header = False
00014 _full_text = """mav_ctrl ctrl
00015
00016 ================================================================================
00017 MSG: asctec_hl_comm/mav_ctrl
00018 Header header
00019
00020 int8 type #message type
00021
00022 # control commands, all units in SI units !!!
00023 # There are 3 operating modes of the helicopter:
00024 # 1. Acceleration: x, y, z correspond to x_dotdot etc... with the exception that yaw is angular velocity
00025 # Inputs must be in body-coordinates
00026 # Currently x~pitch, y~roll, z~thrust, units in rad and rad/s for yaw
00027 # 2. Velocity: x, y, z, yaw correspond to x_dot etc...
00028 # Vehicle must have it's own pose estimation e.g. vision/GPS
00029 # Inputs must be in body-coordinates
00030 # Units in m/s and rad/s respectively
00031 # 3. Position
00032 # Vehicle must have it's own pose estimation e.g. vision/GPS
00033 # Inputs in fixed coordinate system
00034 # v_max_* is only valid for this mode and limits the velocity a vehicle approaches the waypoint
00035
00036 float32 x
00037 float32 y
00038 float32 z
00039 float32 yaw
00040 float32 v_max_xy
00041 float32 v_max_z
00042
00043 int8 acceleration = 1
00044 int8 velocity = 2
00045 int8 position = 3
00046 int8 velocity_body = 4
00047 int8 position_body = 5
00048
00049 ================================================================================
00050 MSG: std_msgs/Header
00051 # Standard metadata for higher-level stamped data types.
00052 # This is generally used to communicate timestamped data
00053 # in a particular coordinate frame.
00054 #
00055 # sequence ID: consecutively increasing ID
00056 uint32 seq
00057 #Two-integer timestamp that is expressed as:
00058 # * stamp.secs: seconds (stamp_secs) since epoch
00059 # * stamp.nsecs: nanoseconds since stamp_secs
00060 # time-handling sugar is provided by the client library
00061 time stamp
00062 #Frame this data is associated with
00063 # 0: no frame
00064 # 1: global frame
00065 string frame_id
00066
00067 """
00068 __slots__ = ['ctrl']
00069 _slot_types = ['asctec_hl_comm/mav_ctrl']
00070
00071 def __init__(self, *args, **kwds):
00072 """
00073 Constructor. Any message fields that are implicitly/explicitly
00074 set to None will be assigned a default value. The recommend
00075 use is keyword arguments as this is more robust to future message
00076 changes. You cannot mix in-order arguments and keyword arguments.
00077
00078 The available fields are:
00079 ctrl
00080
00081 :param args: complete set of field values, in .msg order
00082 :param kwds: use keyword arguments corresponding to message field names
00083 to set specific fields.
00084 """
00085 if args or kwds:
00086 super(MavCtrlSrvRequest, self).__init__(*args, **kwds)
00087
00088 if self.ctrl is None:
00089 self.ctrl = asctec_hl_comm.msg.mav_ctrl()
00090 else:
00091 self.ctrl = asctec_hl_comm.msg.mav_ctrl()
00092
00093 def _get_types(self):
00094 """
00095 internal API method
00096 """
00097 return self._slot_types
00098
00099 def serialize(self, buff):
00100 """
00101 serialize message into buffer
00102 :param buff: buffer, ``StringIO``
00103 """
00104 try:
00105 _x = self
00106 buff.write(_struct_3I.pack(_x.ctrl.header.seq, _x.ctrl.header.stamp.secs, _x.ctrl.header.stamp.nsecs))
00107 _x = self.ctrl.header.frame_id
00108 length = len(_x)
00109 if python3 or type(_x) == unicode:
00110 _x = _x.encode('utf-8')
00111 length = len(_x)
00112 buff.write(struct.pack('<I%ss'%length, length, _x))
00113 _x = self
00114 buff.write(_struct_b6f.pack(_x.ctrl.type, _x.ctrl.x, _x.ctrl.y, _x.ctrl.z, _x.ctrl.yaw, _x.ctrl.v_max_xy, _x.ctrl.v_max_z))
00115 except struct.error as se: self._check_types(se)
00116 except TypeError as te: self._check_types(te)
00117
00118 def deserialize(self, str):
00119 """
00120 unpack serialized message in str into this message instance
00121 :param str: byte array of serialized message, ``str``
00122 """
00123 try:
00124 if self.ctrl is None:
00125 self.ctrl = asctec_hl_comm.msg.mav_ctrl()
00126 end = 0
00127 _x = self
00128 start = end
00129 end += 12
00130 (_x.ctrl.header.seq, _x.ctrl.header.stamp.secs, _x.ctrl.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00131 start = end
00132 end += 4
00133 (length,) = _struct_I.unpack(str[start:end])
00134 start = end
00135 end += length
00136 if python3:
00137 self.ctrl.header.frame_id = str[start:end].decode('utf-8')
00138 else:
00139 self.ctrl.header.frame_id = str[start:end]
00140 _x = self
00141 start = end
00142 end += 25
00143 (_x.ctrl.type, _x.ctrl.x, _x.ctrl.y, _x.ctrl.z, _x.ctrl.yaw, _x.ctrl.v_max_xy, _x.ctrl.v_max_z,) = _struct_b6f.unpack(str[start:end])
00144 return self
00145 except struct.error as e:
00146 raise genpy.DeserializationError(e)
00147
00148
00149 def serialize_numpy(self, buff, numpy):
00150 """
00151 serialize message with numpy array types into buffer
00152 :param buff: buffer, ``StringIO``
00153 :param numpy: numpy python module
00154 """
00155 try:
00156 _x = self
00157 buff.write(_struct_3I.pack(_x.ctrl.header.seq, _x.ctrl.header.stamp.secs, _x.ctrl.header.stamp.nsecs))
00158 _x = self.ctrl.header.frame_id
00159 length = len(_x)
00160 if python3 or type(_x) == unicode:
00161 _x = _x.encode('utf-8')
00162 length = len(_x)
00163 buff.write(struct.pack('<I%ss'%length, length, _x))
00164 _x = self
00165 buff.write(_struct_b6f.pack(_x.ctrl.type, _x.ctrl.x, _x.ctrl.y, _x.ctrl.z, _x.ctrl.yaw, _x.ctrl.v_max_xy, _x.ctrl.v_max_z))
00166 except struct.error as se: self._check_types(se)
00167 except TypeError as te: self._check_types(te)
00168
00169 def deserialize_numpy(self, str, numpy):
00170 """
00171 unpack serialized message in str into this message instance using numpy for array types
00172 :param str: byte array of serialized message, ``str``
00173 :param numpy: numpy python module
00174 """
00175 try:
00176 if self.ctrl is None:
00177 self.ctrl = asctec_hl_comm.msg.mav_ctrl()
00178 end = 0
00179 _x = self
00180 start = end
00181 end += 12
00182 (_x.ctrl.header.seq, _x.ctrl.header.stamp.secs, _x.ctrl.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.ctrl.header.frame_id = str[start:end].decode('utf-8')
00190 else:
00191 self.ctrl.header.frame_id = str[start:end]
00192 _x = self
00193 start = end
00194 end += 25
00195 (_x.ctrl.type, _x.ctrl.x, _x.ctrl.y, _x.ctrl.z, _x.ctrl.yaw, _x.ctrl.v_max_xy, _x.ctrl.v_max_z,) = _struct_b6f.unpack(str[start:end])
00196 return self
00197 except struct.error as e:
00198 raise genpy.DeserializationError(e)
00199
00200 _struct_I = genpy.struct_I
00201 _struct_3I = struct.Struct("<3I")
00202 _struct_b6f = struct.Struct("<b6f")
00203 """autogenerated by genpy from asctec_hl_comm/MavCtrlSrvResponse.msg. Do not edit."""
00204 import sys
00205 python3 = True if sys.hexversion > 0x03000000 else False
00206 import genpy
00207 import struct
00208
00209 import asctec_hl_comm.msg
00210 import std_msgs.msg
00211
00212 class MavCtrlSrvResponse(genpy.Message):
00213 _md5sum = "b903b08125ca08bbbb20320238af4215"
00214 _type = "asctec_hl_comm/MavCtrlSrvResponse"
00215 _has_header = False
00216 _full_text = """mav_ctrl ctrl_result
00217
00218 ================================================================================
00219 MSG: asctec_hl_comm/mav_ctrl
00220 Header header
00221
00222 int8 type #message type
00223
00224 # control commands, all units in SI units !!!
00225 # There are 3 operating modes of the helicopter:
00226 # 1. Acceleration: x, y, z correspond to x_dotdot etc... with the exception that yaw is angular velocity
00227 # Inputs must be in body-coordinates
00228 # Currently x~pitch, y~roll, z~thrust, units in rad and rad/s for yaw
00229 # 2. Velocity: x, y, z, yaw correspond to x_dot etc...
00230 # Vehicle must have it's own pose estimation e.g. vision/GPS
00231 # Inputs must be in body-coordinates
00232 # Units in m/s and rad/s respectively
00233 # 3. Position
00234 # Vehicle must have it's own pose estimation e.g. vision/GPS
00235 # Inputs in fixed coordinate system
00236 # v_max_* is only valid for this mode and limits the velocity a vehicle approaches the waypoint
00237
00238 float32 x
00239 float32 y
00240 float32 z
00241 float32 yaw
00242 float32 v_max_xy
00243 float32 v_max_z
00244
00245 int8 acceleration = 1
00246 int8 velocity = 2
00247 int8 position = 3
00248 int8 velocity_body = 4
00249 int8 position_body = 5
00250
00251 ================================================================================
00252 MSG: std_msgs/Header
00253 # Standard metadata for higher-level stamped data types.
00254 # This is generally used to communicate timestamped data
00255 # in a particular coordinate frame.
00256 #
00257 # sequence ID: consecutively increasing ID
00258 uint32 seq
00259 #Two-integer timestamp that is expressed as:
00260 # * stamp.secs: seconds (stamp_secs) since epoch
00261 # * stamp.nsecs: nanoseconds since stamp_secs
00262 # time-handling sugar is provided by the client library
00263 time stamp
00264 #Frame this data is associated with
00265 # 0: no frame
00266 # 1: global frame
00267 string frame_id
00268
00269 """
00270 __slots__ = ['ctrl_result']
00271 _slot_types = ['asctec_hl_comm/mav_ctrl']
00272
00273 def __init__(self, *args, **kwds):
00274 """
00275 Constructor. Any message fields that are implicitly/explicitly
00276 set to None will be assigned a default value. The recommend
00277 use is keyword arguments as this is more robust to future message
00278 changes. You cannot mix in-order arguments and keyword arguments.
00279
00280 The available fields are:
00281 ctrl_result
00282
00283 :param args: complete set of field values, in .msg order
00284 :param kwds: use keyword arguments corresponding to message field names
00285 to set specific fields.
00286 """
00287 if args or kwds:
00288 super(MavCtrlSrvResponse, self).__init__(*args, **kwds)
00289
00290 if self.ctrl_result is None:
00291 self.ctrl_result = asctec_hl_comm.msg.mav_ctrl()
00292 else:
00293 self.ctrl_result = asctec_hl_comm.msg.mav_ctrl()
00294
00295 def _get_types(self):
00296 """
00297 internal API method
00298 """
00299 return self._slot_types
00300
00301 def serialize(self, buff):
00302 """
00303 serialize message into buffer
00304 :param buff: buffer, ``StringIO``
00305 """
00306 try:
00307 _x = self
00308 buff.write(_struct_3I.pack(_x.ctrl_result.header.seq, _x.ctrl_result.header.stamp.secs, _x.ctrl_result.header.stamp.nsecs))
00309 _x = self.ctrl_result.header.frame_id
00310 length = len(_x)
00311 if python3 or type(_x) == unicode:
00312 _x = _x.encode('utf-8')
00313 length = len(_x)
00314 buff.write(struct.pack('<I%ss'%length, length, _x))
00315 _x = self
00316 buff.write(_struct_b6f.pack(_x.ctrl_result.type, _x.ctrl_result.x, _x.ctrl_result.y, _x.ctrl_result.z, _x.ctrl_result.yaw, _x.ctrl_result.v_max_xy, _x.ctrl_result.v_max_z))
00317 except struct.error as se: self._check_types(se)
00318 except TypeError as te: self._check_types(te)
00319
00320 def deserialize(self, str):
00321 """
00322 unpack serialized message in str into this message instance
00323 :param str: byte array of serialized message, ``str``
00324 """
00325 try:
00326 if self.ctrl_result is None:
00327 self.ctrl_result = asctec_hl_comm.msg.mav_ctrl()
00328 end = 0
00329 _x = self
00330 start = end
00331 end += 12
00332 (_x.ctrl_result.header.seq, _x.ctrl_result.header.stamp.secs, _x.ctrl_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00333 start = end
00334 end += 4
00335 (length,) = _struct_I.unpack(str[start:end])
00336 start = end
00337 end += length
00338 if python3:
00339 self.ctrl_result.header.frame_id = str[start:end].decode('utf-8')
00340 else:
00341 self.ctrl_result.header.frame_id = str[start:end]
00342 _x = self
00343 start = end
00344 end += 25
00345 (_x.ctrl_result.type, _x.ctrl_result.x, _x.ctrl_result.y, _x.ctrl_result.z, _x.ctrl_result.yaw, _x.ctrl_result.v_max_xy, _x.ctrl_result.v_max_z,) = _struct_b6f.unpack(str[start:end])
00346 return self
00347 except struct.error as e:
00348 raise genpy.DeserializationError(e)
00349
00350
00351 def serialize_numpy(self, buff, numpy):
00352 """
00353 serialize message with numpy array types into buffer
00354 :param buff: buffer, ``StringIO``
00355 :param numpy: numpy python module
00356 """
00357 try:
00358 _x = self
00359 buff.write(_struct_3I.pack(_x.ctrl_result.header.seq, _x.ctrl_result.header.stamp.secs, _x.ctrl_result.header.stamp.nsecs))
00360 _x = self.ctrl_result.header.frame_id
00361 length = len(_x)
00362 if python3 or type(_x) == unicode:
00363 _x = _x.encode('utf-8')
00364 length = len(_x)
00365 buff.write(struct.pack('<I%ss'%length, length, _x))
00366 _x = self
00367 buff.write(_struct_b6f.pack(_x.ctrl_result.type, _x.ctrl_result.x, _x.ctrl_result.y, _x.ctrl_result.z, _x.ctrl_result.yaw, _x.ctrl_result.v_max_xy, _x.ctrl_result.v_max_z))
00368 except struct.error as se: self._check_types(se)
00369 except TypeError as te: self._check_types(te)
00370
00371 def deserialize_numpy(self, str, numpy):
00372 """
00373 unpack serialized message in str into this message instance using numpy for array types
00374 :param str: byte array of serialized message, ``str``
00375 :param numpy: numpy python module
00376 """
00377 try:
00378 if self.ctrl_result is None:
00379 self.ctrl_result = asctec_hl_comm.msg.mav_ctrl()
00380 end = 0
00381 _x = self
00382 start = end
00383 end += 12
00384 (_x.ctrl_result.header.seq, _x.ctrl_result.header.stamp.secs, _x.ctrl_result.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00385 start = end
00386 end += 4
00387 (length,) = _struct_I.unpack(str[start:end])
00388 start = end
00389 end += length
00390 if python3:
00391 self.ctrl_result.header.frame_id = str[start:end].decode('utf-8')
00392 else:
00393 self.ctrl_result.header.frame_id = str[start:end]
00394 _x = self
00395 start = end
00396 end += 25
00397 (_x.ctrl_result.type, _x.ctrl_result.x, _x.ctrl_result.y, _x.ctrl_result.z, _x.ctrl_result.yaw, _x.ctrl_result.v_max_xy, _x.ctrl_result.v_max_z,) = _struct_b6f.unpack(str[start:end])
00398 return self
00399 except struct.error as e:
00400 raise genpy.DeserializationError(e)
00401
00402 _struct_I = genpy.struct_I
00403 _struct_3I = struct.Struct("<3I")
00404 _struct_b6f = struct.Struct("<b6f")
00405 class MavCtrlSrv(object):
00406 _type = 'asctec_hl_comm/MavCtrlSrv'
00407 _md5sum = 'ed4ced4e777c3a84e6602a79aaabcdfe'
00408 _request_class = MavCtrlSrvRequest
00409 _response_class = MavCtrlSrvResponse