mavgen_objc.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 '''
00003 parse a MAVLink protocol XML file and generate an Objective-C implementation
00004 
00005 Copyright John Boiles 2013
00006 Released under GNU GPL version 3 or later
00007 '''
00008 
00009 import os
00010 from . import mavparse, mavtemplate
00011 
00012 t = mavtemplate.MAVTemplate()
00013 
00014 def generate_mavlink(directory, xml):
00015     '''generate MVMavlink header and implementation'''
00016     f = open(os.path.join(directory, "MVMavlink.h"), mode='w')
00017     t.write(f,'''
00018 //
00019 //  MVMavlink.h
00020 //  MAVLink communications protocol built from ${basename}.xml
00021 //
00022 //  Created on ${parse_time} by mavgen_objc.py
00023 //  http://qgroundcontrol.org/mavlink
00024 //
00025 
00026 #import "MVMessage.h"
00027 ${{message_definition_files:#import "MV${name_camel_case}Messages.h"
00028 }}
00029 
00030 @class MVMavlink;
00031 @protocol MVMessage;
00032 
00033 @protocol MVMavlinkDelegate <NSObject>
00034 
00035 /*!
00036  Method called on the delegate when a full message has been received. Note that this may be called multiple times when parseData: is called, if the data passed to parseData: contains multiple messages.
00037 
00038  @param mavlink The MVMavlink object calling this method
00039  @param message The id<MVMessage> class containing the parsed message
00040  */
00041 - (void)mavlink:(MVMavlink *)mavlink didGetMessage:(id<MVMessage>)message;
00042 
00043 /*!
00044  Method called on the delegate when data should be sent.
00045 
00046  @param mavlink The MVMavlink object calling this method
00047  @param data NSData object containing the bytes to be sent
00048  */
00049 - (BOOL)mavlink:(MVMavlink *)mavlink shouldWriteData:(NSData *)data;
00050 
00051 @end
00052 
00053 /*!
00054  Class for parsing and sending instances of id<MVMessage>
00055 
00056  @discussion MVMavlink receives a stream of bytes via the parseData: method and calls the delegate method mavlink:didGetMessage: each time a message is fully parsed. Users of MVMavlink can call parseData: anytime they get new data, even if that data does not contain a complete message.
00057  */
00058 @interface MVMavlink : NSObject
00059 @property (weak, nonatomic) id<MVMavlinkDelegate> delegate;
00060 
00061 /*!
00062  Parse byte data received from a MAVLink byte stream.
00063 
00064  @param data NSData containing the received bytes
00065  */
00066 - (void)parseData:(NSData *)data;
00067 
00068 /*!
00069  Compile MVMessage object into a bytes and pass to the delegate for sending.
00070 
00071  @param message Object conforming to the MVMessage protocol that represents the data to be sent
00072  @return YES if message sending was successful
00073  */
00074 - (BOOL)sendMessage:(id<MVMessage>)message;
00075 
00076 @end
00077 ''', xml)
00078     f.close()
00079     f = open(os.path.join(directory, "MVMavlink.m"), mode='w')
00080     t.write(f,'''
00081 //
00082 //  MVMavlink.m
00083 //  MAVLink communications protocol built from ${basename}.xml
00084 //
00085 //  Created by mavgen_objc.py
00086 //  http://qgroundcontrol.org/mavlink
00087 //
00088 
00089 #import "MVMavlink.h"
00090 
00091 @implementation MVMavlink
00092 
00093 - (void)parseData:(NSData *)data {
00094   mavlink_message_t msg;
00095   mavlink_status_t status;
00096   char *bytes = (char *)[data bytes];
00097 
00098   for (NSInteger i = 0; i < [data length]; ++i) {
00099     if (mavlink_parse_char(MAVLINK_COMM_0, bytes[i], &msg, &status)) {
00100       // Packet received
00101       id<MVMessage> message = [MVMessage messageWithCMessage:msg];
00102       [_delegate mavlink:self didGetMessage:message];
00103     }
00104   }
00105 }
00106 
00107 - (BOOL)sendMessage:(id<MVMessage>)message {
00108   return [_delegate mavlink:self shouldWriteData:[message data]];
00109 }
00110 
00111 @end
00112 ''', xml)
00113     f.close()
00114 
00115 def generate_base_message(directory, xml):
00116     '''Generate base MVMessage header and implementation'''
00117     f = open(os.path.join(directory, 'MVMessage.h'), mode='w')
00118     t.write(f, '''
00119 //
00120 //  MVMessage.h
00121 //  MAVLink communications protocol built from ${basename}.xml
00122 //
00123 //  Created by mavgen_objc.py
00124 //  http://qgroundcontrol.org/mavlink
00125 //
00126 
00127 #import "mavlink.h"
00128 
00129 @protocol MVMessage <NSObject>
00130 - (id)initWithCMessage:(mavlink_message_t)message;
00131 - (NSData *)data;
00132 @property (readonly, nonatomic) mavlink_message_t message;
00133 @end
00134 
00135 @interface MVMessage : NSObject <MVMessage> {
00136   mavlink_message_t _message;
00137 }
00138 
00139 /*!
00140  Create an MVMessage subclass from a mavlink_message_t.
00141 
00142  @param message Struct containing the details of the message
00143  @result MVMessage or subclass representing the message
00144  */
00145 + (id<MVMessage>)messageWithCMessage:(mavlink_message_t)message;
00146 
00147 //! System ID of the sender of the message.
00148 - (uint8_t)systemId;
00149 
00150 //! Component ID of the sender of the message.
00151 - (uint8_t)componentId;
00152 
00153 //! Message ID of this message.
00154 - (uint8_t)messageId;
00155 
00156 @end
00157 ''', xml)
00158     f.close()
00159     f = open(os.path.join(directory, 'MVMessage.m'), mode='w')
00160     t.write(f, '''
00161 //
00162 //  MVMessage.m
00163 //  MAVLink communications protocol built from ${basename}.xml
00164 //
00165 //  Created by mavgen_objc.py
00166 //  http://qgroundcontrol.org/mavlink
00167 //
00168 
00169 #import "MVMessage.h"
00170 ${{message_definition_files:#import "MV${name_camel_case}Messages.h"
00171 }}
00172 
00173 @implementation MVMessage
00174 
00175 @synthesize message=_message;
00176 
00177 + (id)messageWithCMessage:(mavlink_message_t)message {
00178   static NSDictionary *messageIdToClass = nil;
00179   if (!messageIdToClass) {
00180     messageIdToClass = @{
00181 ${{message:      @${id} : [MVMessage${name_camel_case} class],
00182 }}
00183     };
00184   }
00185 
00186   Class messageClass = messageIdToClass[@(message.msgid)];
00187   // Store unknown messages to MVMessage
00188   if (!messageClass) {
00189     messageClass = [MVMessage class];
00190   }
00191 
00192   return [[messageClass alloc] initWithCMessage:message];
00193 }
00194 
00195 - (id)initWithCMessage:(mavlink_message_t)message {
00196   if ((self = [super init])) {
00197     self->_message = message;
00198   }
00199   return self;
00200 }
00201 
00202 - (NSData *)data {
00203   uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
00204 
00205   NSInteger length = mavlink_msg_to_send_buffer(buffer, &self->_message);
00206 
00207   return [NSData dataWithBytes:buffer length:length];
00208 }
00209 
00210 - (uint8_t)systemId {
00211   return self->_message.sysid;
00212 }
00213 
00214 - (uint8_t)componentId {
00215   return self->_message.compid;
00216 }
00217 
00218 - (uint8_t)messageId {
00219   return self->_message.msgid;
00220 }
00221 
00222 - (NSString *)description {
00223   return [NSString stringWithFormat:@"%@, systemId=%d, componentId=%d", [self class], self.systemId, self.componentId];
00224 }
00225 
00226 @end
00227 ''', xml)
00228     f.close()
00229 
00230 def generate_message_definitions_h(directory, xml):
00231     '''generate headerfile containing includes for all messages'''
00232     f = open(os.path.join(directory, "MV" + camel_case_from_underscores(xml.basename) + "Messages.h"), mode='w')
00233     t.write(f, '''
00234 //
00235 //  MV${basename_camel_case}Messages.h
00236 //  MAVLink communications protocol built from ${basename}.xml
00237 //
00238 //  Created by mavgen_objc.py
00239 //  http://qgroundcontrol.org/mavlink
00240 //
00241 
00242 ${{message:#import "MVMessage${name_camel_case}.h"
00243 }}
00244 ''', xml)
00245     f.close()
00246 
00247 def generate_message(directory, m):
00248     '''generate per-message header and implementation file'''
00249     f = open(os.path.join(directory, 'MVMessage%s.h' % m.name_camel_case), mode='w')
00250     t.write(f, '''
00251 //
00252 //  MVMessage${name_camel_case}.h
00253 //  MAVLink communications protocol built from ${basename}.xml
00254 //
00255 //  Created by mavgen_objc.py
00256 //  http://qgroundcontrol.org/mavlink
00257 //
00258 
00259 #import "MVMessage.h"
00260 
00261 /*!
00262  Class that represents a ${name} Mavlink message.
00263 
00264  @discussion ${description}
00265  */
00266 @interface MVMessage${name_camel_case} : MVMessage
00267 
00268 - (id)initWithSystemId:(uint8_t)systemId componentId:(uint8_t)componentId${{arg_fields: ${name_lower_camel_case}:(${arg_type}${array_prefix})${name_lower_camel_case}}};
00269 
00270 ${{fields://! ${description}
00271 - (${return_type})${name_lower_camel_case}${get_arg_objc};
00272 
00273 }}
00274 @end
00275 ''', m)
00276     f.close()
00277     f = open(os.path.join(directory, 'MVMessage%s.m' % m.name_camel_case), mode='w')
00278     t.write(f, '''
00279 //
00280 //  MVMessage${name_camel_case}.m
00281 //  MAVLink communications protocol built from ${basename}.xml
00282 //
00283 //  Created by mavgen_objc.py
00284 //  http://qgroundcontrol.org/mavlink
00285 //
00286 
00287 #import "MVMessage${name_camel_case}.h"
00288 
00289 @implementation MVMessage${name_camel_case}
00290 
00291 - (id)initWithSystemId:(uint8_t)systemId componentId:(uint8_t)componentId${{arg_fields: ${name_lower_camel_case}:(${arg_type}${array_prefix})${name_lower_camel_case}}} {
00292   if ((self = [super init])) {
00293     mavlink_msg_${name_lower}_pack(systemId, componentId, &(self->_message)${{arg_fields:, ${name_lower_camel_case}}});
00294   }
00295   return self;
00296 }
00297 
00298 ${{fields:- (${return_type})${name_lower_camel_case}${get_arg_objc} {
00299   ${return_method_implementation}
00300 }
00301 
00302 }}
00303 - (NSString *)description {
00304   return [NSString stringWithFormat:@"%@${{fields:, ${name_lower_camel_case}=${print_format}}}", [super description]${{fields:, ${get_message}}}];
00305 }
00306 
00307 @end
00308 ''', m)
00309     f.close()
00310 
00311 def camel_case_from_underscores(string):
00312     """generate a CamelCase string from an underscore_string."""
00313     components = string.split('_')
00314     string = ''
00315     for component in components:
00316         string += component[0].upper() + component[1:]
00317     return string
00318 
00319 def lower_camel_case_from_underscores(string):
00320     """generate a lower-cased camelCase string from an underscore_string.
00321     For example: my_variable_name -> myVariableName"""
00322     components = string.split('_')
00323     string = components[0]
00324     for component in components[1:]:
00325         string += component[0].upper() + component[1:]
00326     return string
00327 
00328 def generate_shared(basename, xml_list):
00329     # Create a dictionary to hold all the values we want to use in the templates
00330     template_dict = {}
00331     template_dict['parse_time'] = xml_list[0].parse_time
00332     template_dict['message'] = []
00333     template_dict['message_definition_files'] = []
00334 
00335     print("Generating Objective-C implementation in directory %s" % basename)
00336     mavparse.mkdir_p(basename)
00337 
00338     for xml in xml_list:
00339         template_dict['message'].extend(xml.message)
00340         basename_camel_case = camel_case_from_underscores(xml.basename)
00341         template_dict['message_definition_files'].append({'name_camel_case': basename_camel_case})
00342         if not template_dict.get('basename', None):
00343             template_dict['basename'] = xml.basename
00344         else:
00345             template_dict['basename'] = template_dict['basename'] + ', ' + xml.basename
00346 
00347     # Sort messages by ID
00348     template_dict['message'] = sorted(template_dict['message'], key = lambda message : message.id)
00349 
00350     # Add name_camel_case to each message object 
00351     for message in template_dict['message']:
00352         message.name_camel_case = camel_case_from_underscores(message.name_lower)
00353 
00354     generate_mavlink(basename, template_dict)
00355     generate_base_message(basename, template_dict)
00356 
00357 def generate_message_definitions(basename, xml):
00358     '''generate files for one XML file'''
00359 
00360     directory = os.path.join(basename, xml.basename)
00361 
00362     print("Generating Objective-C implementation in directory %s" % directory)
00363     mavparse.mkdir_p(directory)
00364 
00365     xml.basename_camel_case = camel_case_from_underscores(xml.basename)
00366 
00367     # Add some extra field attributes for convenience
00368     for m in xml.message:
00369         m.basename = xml.basename
00370         m.parse_time = xml.parse_time
00371         m.name_camel_case = camel_case_from_underscores(m.name_lower)
00372         for f in m.fields:
00373             f.name_lower_camel_case = lower_camel_case_from_underscores(f.name);
00374             f.get_message = "[self %s]" % f.name_lower_camel_case
00375             f.return_method_implementation = ''
00376             f.array_prefix = ''
00377             f.array_return_arg = ''
00378             f.get_arg = ''
00379             f.get_arg_objc = ''
00380             if f.enum:
00381                 f.return_type = f.enum
00382                 f.arg_type = f.enum
00383             else:
00384                 f.return_type = f.type
00385                 f.arg_type = f.type
00386             if f.print_format is None:
00387                 if f.array_length != 0:
00388                     f.print_format = "%@"
00389                 elif f.type.startswith('uint64_t'):
00390                     f.print_format = "%lld"
00391                 elif f.type.startswith('uint') or f.type.startswith('int'):
00392                     f.print_format = "%d"
00393                 elif f.type.startswith('float'):
00394                     f.print_format = "%f"
00395                 elif f.type.startswith('char'):
00396                     f.print_format = "%c"
00397                 else:
00398                     print("print_format unsupported for type %s" % f.type)
00399             if f.array_length != 0:
00400                 f.get_message = '@"[array of %s[%d]]"' % (f.type, f.array_length)
00401                 f.array_prefix = ' *'
00402                 f.array_return_arg = '%s, %u, ' % (f.name, f.array_length)
00403                 f.return_type = 'uint16_t'
00404                 f.get_arg = ', %s' % (f.name)
00405                 f.get_arg_objc = ':(%s *)%s' % (f.type, f.name)
00406                 if f.type == 'char':
00407                     # Special handling for strings (assumes all char arrays are strings)
00408                     f.return_type = 'NSString *'
00409                     f.get_arg_objc = ''
00410                     f.get_message = "[self %s]" % f.name_lower_camel_case
00411                     f.return_method_implementation = \
00412 """char string[%(array_length)d];
00413   mavlink_msg_%(message_name_lower)s_get_%(name)s(&(self->_message), (char *)&string);
00414   return [[NSString alloc] initWithBytes:string length:%(array_length)d encoding:NSASCIIStringEncoding];""" % {'array_length': f.array_length, 'message_name_lower': m.name_lower, 'name': f.name}
00415 
00416             if not f.return_method_implementation:
00417                 f.return_method_implementation = \
00418 """return mavlink_msg_%(message_name_lower)s_get_%(name)s(&(self->_message)%(get_arg)s);""" % {'message_name_lower': m.name_lower, 'name': f.name, 'get_arg': f.get_arg}
00419 
00420     for m in xml.message:
00421         m.arg_fields = []
00422         for f in m.fields:
00423             if not f.omit_arg:
00424                 m.arg_fields.append(f)
00425  
00426     generate_message_definitions_h(directory, xml)
00427     for m in xml.message:
00428         generate_message(directory, m)
00429 
00430 
00431 def generate(basename, xml_list):
00432     '''generate complete MAVLink Objective-C implemenation'''
00433 
00434     generate_shared(basename, xml_list)
00435     for xml in xml_list:
00436         generate_message_definitions(basename, xml)


mavlink
Author(s): Lorenz Meier
autogenerated on Thu Jun 6 2019 19:01:57