$search
00001 """autogenerated by genmsg_py from LLStatus.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import std_msgs.msg 00006 00007 class LLStatus(roslib.message.Message): 00008 _md5sum = "e0dae36eea5774367686a40e1843c5e2" 00009 _type = "asctec_msgs/LLStatus" 00010 _has_header = True #flag to mark the presence of a Header object 00011 _full_text = """# Software License Agreement (BSD License) 00012 # 00013 # Copyright (c) 2010 00014 # William Morris <morris@ee.ccny.cuny.edu> 00015 # Ivan Dryanovski <ivan.dryanovski@gmail.com> 00016 # All rights reserved. 00017 # 00018 # Redistribution and use in source and binary forms, with or without 00019 # modification, are permitted provided that the following conditions 00020 # are met: 00021 # 00022 # * Redistributions of source code must retain the above copyright 00023 # notice, this list of conditions and the following disclaimer. 00024 # * Redistributions in binary form must reproduce the above 00025 # copyright notice, this list of conditions and the following 00026 # disclaimer in the documentation and/or other materials provided 00027 # with the distribution. 00028 # * Neither the name of CCNY Robotics Lab nor the names of its 00029 # contributors may be used to endorse or promote products derived 00030 # from this software without specific prior written permission. 00031 # 00032 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00033 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00034 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00035 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00036 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00037 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00038 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00039 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00040 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00041 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00042 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00043 # POSSIBILITY OF SUCH DAMAGE. 00044 00045 Header header 00046 # battery voltages in mV 00047 int16 battery_voltage_1 00048 int16 battery_voltage_2 00049 # dont care 00050 int16 status 00051 # Controller cycles per second (should be about 1000) 00052 int16 cpu_load 00053 # dont care 00054 int8 compass_enabled 00055 int8 chksum_error 00056 int8 flying 00057 int8 motors_on 00058 int16 flightMode 00059 # Time motors are turning 00060 int16 up_time 00061 00062 00063 ================================================================================ 00064 MSG: std_msgs/Header 00065 # Standard metadata for higher-level stamped data types. 00066 # This is generally used to communicate timestamped data 00067 # in a particular coordinate frame. 00068 # 00069 # sequence ID: consecutively increasing ID 00070 uint32 seq 00071 #Two-integer timestamp that is expressed as: 00072 # * stamp.secs: seconds (stamp_secs) since epoch 00073 # * stamp.nsecs: nanoseconds since stamp_secs 00074 # time-handling sugar is provided by the client library 00075 time stamp 00076 #Frame this data is associated with 00077 # 0: no frame 00078 # 1: global frame 00079 string frame_id 00080 00081 """ 00082 __slots__ = ['header','battery_voltage_1','battery_voltage_2','status','cpu_load','compass_enabled','chksum_error','flying','motors_on','flightMode','up_time'] 00083 _slot_types = ['Header','int16','int16','int16','int16','int8','int8','int8','int8','int16','int16'] 00084 00085 def __init__(self, *args, **kwds): 00086 """ 00087 Constructor. Any message fields that are implicitly/explicitly 00088 set to None will be assigned a default value. The recommend 00089 use is keyword arguments as this is more robust to future message 00090 changes. You cannot mix in-order arguments and keyword arguments. 00091 00092 The available fields are: 00093 header,battery_voltage_1,battery_voltage_2,status,cpu_load,compass_enabled,chksum_error,flying,motors_on,flightMode,up_time 00094 00095 @param args: complete set of field values, in .msg order 00096 @param kwds: use keyword arguments corresponding to message field names 00097 to set specific fields. 00098 """ 00099 if args or kwds: 00100 super(LLStatus, self).__init__(*args, **kwds) 00101 #message fields cannot be None, assign default values for those that are 00102 if self.header is None: 00103 self.header = std_msgs.msg._Header.Header() 00104 if self.battery_voltage_1 is None: 00105 self.battery_voltage_1 = 0 00106 if self.battery_voltage_2 is None: 00107 self.battery_voltage_2 = 0 00108 if self.status is None: 00109 self.status = 0 00110 if self.cpu_load is None: 00111 self.cpu_load = 0 00112 if self.compass_enabled is None: 00113 self.compass_enabled = 0 00114 if self.chksum_error is None: 00115 self.chksum_error = 0 00116 if self.flying is None: 00117 self.flying = 0 00118 if self.motors_on is None: 00119 self.motors_on = 0 00120 if self.flightMode is None: 00121 self.flightMode = 0 00122 if self.up_time is None: 00123 self.up_time = 0 00124 else: 00125 self.header = std_msgs.msg._Header.Header() 00126 self.battery_voltage_1 = 0 00127 self.battery_voltage_2 = 0 00128 self.status = 0 00129 self.cpu_load = 0 00130 self.compass_enabled = 0 00131 self.chksum_error = 0 00132 self.flying = 0 00133 self.motors_on = 0 00134 self.flightMode = 0 00135 self.up_time = 0 00136 00137 def _get_types(self): 00138 """ 00139 internal API method 00140 """ 00141 return self._slot_types 00142 00143 def serialize(self, buff): 00144 """ 00145 serialize message into buffer 00146 @param buff: buffer 00147 @type buff: StringIO 00148 """ 00149 try: 00150 _x = self 00151 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00152 _x = self.header.frame_id 00153 length = len(_x) 00154 buff.write(struct.pack('<I%ss'%length, length, _x)) 00155 _x = self 00156 buff.write(_struct_4h4b2h.pack(_x.battery_voltage_1, _x.battery_voltage_2, _x.status, _x.cpu_load, _x.compass_enabled, _x.chksum_error, _x.flying, _x.motors_on, _x.flightMode, _x.up_time)) 00157 except struct.error as se: self._check_types(se) 00158 except TypeError as te: self._check_types(te) 00159 00160 def deserialize(self, str): 00161 """ 00162 unpack serialized message in str into this message instance 00163 @param str: byte array of serialized message 00164 @type str: str 00165 """ 00166 try: 00167 if self.header is None: 00168 self.header = std_msgs.msg._Header.Header() 00169 end = 0 00170 _x = self 00171 start = end 00172 end += 12 00173 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00174 start = end 00175 end += 4 00176 (length,) = _struct_I.unpack(str[start:end]) 00177 start = end 00178 end += length 00179 self.header.frame_id = str[start:end] 00180 _x = self 00181 start = end 00182 end += 16 00183 (_x.battery_voltage_1, _x.battery_voltage_2, _x.status, _x.cpu_load, _x.compass_enabled, _x.chksum_error, _x.flying, _x.motors_on, _x.flightMode, _x.up_time,) = _struct_4h4b2h.unpack(str[start:end]) 00184 return self 00185 except struct.error as e: 00186 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00187 00188 00189 def serialize_numpy(self, buff, numpy): 00190 """ 00191 serialize message with numpy array types into buffer 00192 @param buff: buffer 00193 @type buff: StringIO 00194 @param numpy: numpy python module 00195 @type numpy module 00196 """ 00197 try: 00198 _x = self 00199 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00200 _x = self.header.frame_id 00201 length = len(_x) 00202 buff.write(struct.pack('<I%ss'%length, length, _x)) 00203 _x = self 00204 buff.write(_struct_4h4b2h.pack(_x.battery_voltage_1, _x.battery_voltage_2, _x.status, _x.cpu_load, _x.compass_enabled, _x.chksum_error, _x.flying, _x.motors_on, _x.flightMode, _x.up_time)) 00205 except struct.error as se: self._check_types(se) 00206 except TypeError as te: self._check_types(te) 00207 00208 def deserialize_numpy(self, str, numpy): 00209 """ 00210 unpack serialized message in str into this message instance using numpy for array types 00211 @param str: byte array of serialized message 00212 @type str: str 00213 @param numpy: numpy python module 00214 @type numpy: module 00215 """ 00216 try: 00217 if self.header is None: 00218 self.header = std_msgs.msg._Header.Header() 00219 end = 0 00220 _x = self 00221 start = end 00222 end += 12 00223 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00224 start = end 00225 end += 4 00226 (length,) = _struct_I.unpack(str[start:end]) 00227 start = end 00228 end += length 00229 self.header.frame_id = str[start:end] 00230 _x = self 00231 start = end 00232 end += 16 00233 (_x.battery_voltage_1, _x.battery_voltage_2, _x.status, _x.cpu_load, _x.compass_enabled, _x.chksum_error, _x.flying, _x.motors_on, _x.flightMode, _x.up_time,) = _struct_4h4b2h.unpack(str[start:end]) 00234 return self 00235 except struct.error as e: 00236 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00237 00238 _struct_I = roslib.message.struct_I 00239 _struct_3I = struct.Struct("<3I") 00240 _struct_4h4b2h = struct.Struct("<4h4b2h")