3 parse a MAVLink protocol XML file and generate an Objective-C implementation 5 Copyright John Boiles 2013 6 Released under GNU GPL version 3 or later 8 from __future__
import print_function
11 from .
import mavparse, mavtemplate
16 '''generate MVMavlink header and implementation''' 17 f = open(os.path.join(directory,
"MVMavlink.h"), mode=
'w')
21 // MAVLink communications protocol built from ${basename}.xml 23 // Created on ${parse_time} by mavgen_objc.py 24 // http://qgroundcontrol.org/mavlink 28 ${{message_definition_files:#import "MV${name_camel_case}Messages.h" 34 @protocol MVMavlinkDelegate <NSObject> 37 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. 39 @param mavlink The MVMavlink object calling this method 40 @param message The id<MVMessage> class containing the parsed message 42 - (void)mavlink:(MVMavlink *)mavlink didGetMessage:(id<MVMessage>)message; 45 Method called on the delegate when data should be sent. 47 @param mavlink The MVMavlink object calling this method 48 @param data NSData object containing the bytes to be sent 50 - (BOOL)mavlink:(MVMavlink *)mavlink shouldWriteData:(NSData *)data; 55 Class for parsing and sending instances of id<MVMessage> 57 @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. 59 @interface MVMavlink : NSObject 60 @property (weak, nonatomic) id<MVMavlinkDelegate> delegate; 63 Parse byte data received from a MAVLink byte stream. 65 @param data NSData containing the received bytes 67 - (void)parseData:(NSData *)data; 70 Compile MVMessage object into a bytes and pass to the delegate for sending. 72 @param message Object conforming to the MVMessage protocol that represents the data to be sent 73 @return YES if message sending was successful 75 - (BOOL)sendMessage:(id<MVMessage>)message; 80 f = open(os.path.join(directory,
"MVMavlink.m"), mode=
'w')
84 // MAVLink communications protocol built from ${basename}.xml 86 // Created by mavgen_objc.py 87 // http://qgroundcontrol.org/mavlink 92 @implementation MVMavlink 94 - (void)parseData:(NSData *)data { 95 mavlink_message_t msg; 96 mavlink_status_t status; 97 char *bytes = (char *)[data bytes]; 99 for (NSInteger i = 0; i < [data length]; ++i) { 100 if (mavlink_parse_char(MAVLINK_COMM_0, bytes[i], &msg, &status)) { 102 id<MVMessage> message = [MVMessage messageWithCMessage:msg]; 103 [_delegate mavlink:self didGetMessage:message]; 108 - (BOOL)sendMessage:(id<MVMessage>)message { 109 return [_delegate mavlink:self shouldWriteData:[message data]]; 117 '''Generate base MVMessage header and implementation''' 118 f = open(os.path.join(directory,
'MVMessage.h'), mode=
'w')
122 // MAVLink communications protocol built from ${basename}.xml 124 // Created by mavgen_objc.py 125 // http://qgroundcontrol.org/mavlink 130 @protocol MVMessage <NSObject> 131 - (id)initWithCMessage:(mavlink_message_t)message; 133 @property (readonly, nonatomic) mavlink_message_t message; 136 @interface MVMessage : NSObject <MVMessage> { 137 mavlink_message_t _message; 141 Create an MVMessage subclass from a mavlink_message_t. 143 @param message Struct containing the details of the message 144 @result MVMessage or subclass representing the message 146 + (id<MVMessage>)messageWithCMessage:(mavlink_message_t)message; 148 //! System ID of the sender of the message. 151 //! Component ID of the sender of the message. 152 - (uint8_t)componentId; 154 //! Message ID of this message. 155 - (uint8_t)messageId; 160 f = open(os.path.join(directory,
'MVMessage.m'), mode=
'w')
164 // MAVLink communications protocol built from ${basename}.xml 166 // Created by mavgen_objc.py 167 // http://qgroundcontrol.org/mavlink 170 #import "MVMessage.h" 171 ${{message_definition_files:#import "MV${name_camel_case}Messages.h" 174 @implementation MVMessage 176 @synthesize message=_message; 178 + (id)messageWithCMessage:(mavlink_message_t)message { 179 static NSDictionary *messageIdToClass = nil; 180 if (!messageIdToClass) { 181 messageIdToClass = @{ 182 ${{message: @${id} : [MVMessage${name_camel_case} class], 187 Class messageClass = messageIdToClass[@(message.msgid)]; 188 // Store unknown messages to MVMessage 190 messageClass = [MVMessage class]; 193 return [[messageClass alloc] initWithCMessage:message]; 196 - (id)initWithCMessage:(mavlink_message_t)message { 197 if ((self = [super init])) { 198 self->_message = message; 204 uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; 206 NSInteger length = mavlink_msg_to_send_buffer(buffer, &self->_message); 208 return [NSData dataWithBytes:buffer length:length]; 211 - (uint8_t)systemId { 212 return self->_message.sysid; 215 - (uint8_t)componentId { 216 return self->_message.compid; 219 - (uint8_t)messageId { 220 return self->_message.msgid; 223 - (NSString *)description { 224 return [NSString stringWithFormat:@"%@, systemId=%d, componentId=%d", [self class], self.systemId, self.componentId]; 232 '''generate headerfile containing includes for all messages''' 236 // MV${basename_camel_case}Messages.h 237 // MAVLink communications protocol built from ${basename}.xml 239 // Created by mavgen_objc.py 240 // http://qgroundcontrol.org/mavlink 243 ${{message:#import "MVMessage${name_camel_case}.h" 249 '''generate per-message header and implementation file''' 250 f = open(os.path.join(directory,
'MVMessage%s.h' % m.name_camel_case), mode=
'w')
253 // MVMessage${name_camel_case}.h 254 // MAVLink communications protocol built from ${basename}.xml 256 // Created by mavgen_objc.py 257 // http://qgroundcontrol.org/mavlink 260 #import "MVMessage.h" 263 Class that represents a ${name} Mavlink message. 265 @discussion ${description} 267 @interface MVMessage${name_camel_case} : MVMessage 269 - (id)initWithSystemId:(uint8_t)systemId componentId:(uint8_t)componentId${{arg_fields: ${name_lower_camel_case}:(${arg_type}${array_prefix})${name_lower_camel_case}}}; 271 ${{fields://! ${description} 272 - (${return_type})${name_lower_camel_case}${get_arg_objc}; 278 f = open(os.path.join(directory,
'MVMessage%s.m' % m.name_camel_case), mode=
'w')
281 // MVMessage${name_camel_case}.m 282 // MAVLink communications protocol built from ${basename}.xml 284 // Created by mavgen_objc.py 285 // http://qgroundcontrol.org/mavlink 288 #import "MVMessage${name_camel_case}.h" 290 @implementation MVMessage${name_camel_case} 292 - (id)initWithSystemId:(uint8_t)systemId componentId:(uint8_t)componentId${{arg_fields: ${name_lower_camel_case}:(${arg_type}${array_prefix})${name_lower_camel_case}}} { 293 if ((self = [super init])) { 294 mavlink_msg_${name_lower}_pack(systemId, componentId, &(self->_message)${{arg_fields:, ${name_lower_camel_case}}}); 299 ${{fields:- (${return_type})${name_lower_camel_case}${get_arg_objc} { 300 ${return_method_implementation} 304 - (NSString *)description { 305 return [NSString stringWithFormat:@"%@${{fields:, ${name_lower_camel_case}=${print_format}}}", [super description]${{fields:, ${get_message}}}]; 313 """generate a CamelCase string from an underscore_string.""" 314 components = string.split(
'_')
316 for component
in components:
317 string += component[0].upper() + component[1:]
321 """generate a lower-cased camelCase string from an underscore_string. 322 For example: my_variable_name -> myVariableName""" 323 components = string.split(
'_')
324 string = components[0]
325 for component
in components[1:]:
326 string += component[0].upper() + component[1:]
332 template_dict[
'parse_time'] = xml_list[0].parse_time
333 template_dict[
'message'] = []
334 template_dict[
'message_definition_files'] = []
336 print(
"Generating Objective-C implementation in directory %s" % basename)
337 mavparse.mkdir_p(basename)
340 template_dict[
'message'].extend(xml.message)
342 template_dict[
'message_definition_files'].append({
'name_camel_case': basename_camel_case})
343 if not template_dict.get(
'basename',
None):
344 template_dict[
'basename'] = xml.basename
346 template_dict[
'basename'] = template_dict[
'basename'] +
', ' + xml.basename
349 template_dict[
'message'] = sorted(template_dict[
'message'], key =
lambda message : message.id)
352 for message
in template_dict[
'message']:
359 '''generate files for one XML file''' 361 directory = os.path.join(basename, xml.basename)
363 print(
"Generating Objective-C implementation in directory %s" % directory)
364 mavparse.mkdir_p(directory)
369 for m
in xml.message:
370 m.basename = xml.basename
371 m.parse_time = xml.parse_time
375 f.get_message =
"[self %s]" % f.name_lower_camel_case
376 f.return_method_implementation =
'' 378 f.array_return_arg =
'' 382 f.return_type = f.enum
385 f.return_type = f.type
387 if f.print_format
is None:
388 if f.array_length != 0:
389 f.print_format =
"%@" 390 elif f.type.startswith(
'uint64_t'):
391 f.print_format =
"%lld" 392 elif f.type.startswith(
'uint')
or f.type.startswith(
'int'):
393 f.print_format =
"%d" 394 elif f.type.startswith(
'float'):
395 f.print_format =
"%f" 396 elif f.type.startswith(
'char'):
397 f.print_format =
"%c" 399 print(
"print_format unsupported for type %s" % f.type)
400 if f.array_length != 0:
401 f.get_message =
'@"[array of %s[%d]]"' % (f.type, f.array_length)
402 f.array_prefix =
' *' 403 f.array_return_arg =
'%s, %u, ' % (f.name, f.array_length)
404 f.return_type =
'uint16_t' 405 f.get_arg =
', %s' % (f.name)
406 f.get_arg_objc =
':(%s *)%s' % (f.type, f.name)
409 f.return_type =
'NSString *' 411 f.get_message =
"[self %s]" % f.name_lower_camel_case
412 f.return_method_implementation = \
413 """char string[%(array_length)d]; 414 mavlink_msg_%(message_name_lower)s_get_%(name)s(&(self->_message), (char *)&string); 415 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}
417 if not f.return_method_implementation:
418 f.return_method_implementation = \
419 """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}
421 for m
in xml.message:
425 m.arg_fields.append(f)
428 for m
in xml.message:
433 '''generate complete MAVLink Objective-C implemenation'''
def camel_case_from_underscores(string)
def generate_base_message(directory, xml)
def generate_message_definitions(basename, xml)
def lower_camel_case_from_underscores(string)
def generate_message(directory, m)
def generate_shared(basename, xml_list)
def generate_message_definitions_h(directory, xml)
def generate_mavlink(directory, xml)
def generate(basename, xml_list)