mavgen_objc.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 '''
3 parse a MAVLink protocol XML file and generate an Objective-C implementation
4 
5 Copyright John Boiles 2013
6 Released under GNU GPL version 3 or later
7 '''
8 from __future__ import print_function
9 
10 import os
11 from . import mavparse, mavtemplate
12 
14 
15 def generate_mavlink(directory, xml):
16  '''generate MVMavlink header and implementation'''
17  f = open(os.path.join(directory, "MVMavlink.h"), mode='w')
18  t.write(f,'''
19 //
20 // MVMavlink.h
21 // MAVLink communications protocol built from ${basename}.xml
22 //
23 // Created on ${parse_time} by mavgen_objc.py
24 // http://qgroundcontrol.org/mavlink
25 //
26 
27 #import "MVMessage.h"
28 ${{message_definition_files:#import "MV${name_camel_case}Messages.h"
29 }}
30 
31 @class MVMavlink;
32 @protocol MVMessage;
33 
34 @protocol MVMavlinkDelegate <NSObject>
35 
36 /*!
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.
38 
39  @param mavlink The MVMavlink object calling this method
40  @param message The id<MVMessage> class containing the parsed message
41  */
42 - (void)mavlink:(MVMavlink *)mavlink didGetMessage:(id<MVMessage>)message;
43 
44 /*!
45  Method called on the delegate when data should be sent.
46 
47  @param mavlink The MVMavlink object calling this method
48  @param data NSData object containing the bytes to be sent
49  */
50 - (BOOL)mavlink:(MVMavlink *)mavlink shouldWriteData:(NSData *)data;
51 
52 @end
53 
54 /*!
55  Class for parsing and sending instances of id<MVMessage>
56 
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.
58  */
59 @interface MVMavlink : NSObject
60 @property (weak, nonatomic) id<MVMavlinkDelegate> delegate;
61 
62 /*!
63  Parse byte data received from a MAVLink byte stream.
64 
65  @param data NSData containing the received bytes
66  */
67 - (void)parseData:(NSData *)data;
68 
69 /*!
70  Compile MVMessage object into a bytes and pass to the delegate for sending.
71 
72  @param message Object conforming to the MVMessage protocol that represents the data to be sent
73  @return YES if message sending was successful
74  */
75 - (BOOL)sendMessage:(id<MVMessage>)message;
76 
77 @end
78 ''', xml)
79  f.close()
80  f = open(os.path.join(directory, "MVMavlink.m"), mode='w')
81  t.write(f,'''
82 //
83 // MVMavlink.m
84 // MAVLink communications protocol built from ${basename}.xml
85 //
86 // Created by mavgen_objc.py
87 // http://qgroundcontrol.org/mavlink
88 //
89 
90 #import "MVMavlink.h"
91 
92 @implementation MVMavlink
93 
94 - (void)parseData:(NSData *)data {
95  mavlink_message_t msg;
96  mavlink_status_t status;
97  char *bytes = (char *)[data bytes];
98 
99  for (NSInteger i = 0; i < [data length]; ++i) {
100  if (mavlink_parse_char(MAVLINK_COMM_0, bytes[i], &msg, &status)) {
101  // Packet received
102  id<MVMessage> message = [MVMessage messageWithCMessage:msg];
103  [_delegate mavlink:self didGetMessage:message];
104  }
105  }
106 }
107 
108 - (BOOL)sendMessage:(id<MVMessage>)message {
109  return [_delegate mavlink:self shouldWriteData:[message data]];
110 }
111 
112 @end
113 ''', xml)
114  f.close()
115 
116 def generate_base_message(directory, xml):
117  '''Generate base MVMessage header and implementation'''
118  f = open(os.path.join(directory, 'MVMessage.h'), mode='w')
119  t.write(f, '''
120 //
121 // MVMessage.h
122 // MAVLink communications protocol built from ${basename}.xml
123 //
124 // Created by mavgen_objc.py
125 // http://qgroundcontrol.org/mavlink
126 //
127 
128 #import "mavlink.h"
129 
130 @protocol MVMessage <NSObject>
131 - (id)initWithCMessage:(mavlink_message_t)message;
132 - (NSData *)data;
133 @property (readonly, nonatomic) mavlink_message_t message;
134 @end
135 
136 @interface MVMessage : NSObject <MVMessage> {
137  mavlink_message_t _message;
138 }
139 
140 /*!
141  Create an MVMessage subclass from a mavlink_message_t.
142 
143  @param message Struct containing the details of the message
144  @result MVMessage or subclass representing the message
145  */
146 + (id<MVMessage>)messageWithCMessage:(mavlink_message_t)message;
147 
148 //! System ID of the sender of the message.
149 - (uint8_t)systemId;
150 
151 //! Component ID of the sender of the message.
152 - (uint8_t)componentId;
153 
154 //! Message ID of this message.
155 - (uint8_t)messageId;
156 
157 @end
158 ''', xml)
159  f.close()
160  f = open(os.path.join(directory, 'MVMessage.m'), mode='w')
161  t.write(f, '''
162 //
163 // MVMessage.m
164 // MAVLink communications protocol built from ${basename}.xml
165 //
166 // Created by mavgen_objc.py
167 // http://qgroundcontrol.org/mavlink
168 //
169 
170 #import "MVMessage.h"
171 ${{message_definition_files:#import "MV${name_camel_case}Messages.h"
172 }}
173 
174 @implementation MVMessage
175 
176 @synthesize message=_message;
177 
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],
183 }}
184  };
185  }
186 
187  Class messageClass = messageIdToClass[@(message.msgid)];
188  // Store unknown messages to MVMessage
189  if (!messageClass) {
190  messageClass = [MVMessage class];
191  }
192 
193  return [[messageClass alloc] initWithCMessage:message];
194 }
195 
196 - (id)initWithCMessage:(mavlink_message_t)message {
197  if ((self = [super init])) {
198  self->_message = message;
199  }
200  return self;
201 }
202 
203 - (NSData *)data {
204  uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
205 
206  NSInteger length = mavlink_msg_to_send_buffer(buffer, &self->_message);
207 
208  return [NSData dataWithBytes:buffer length:length];
209 }
210 
211 - (uint8_t)systemId {
212  return self->_message.sysid;
213 }
214 
215 - (uint8_t)componentId {
216  return self->_message.compid;
217 }
218 
219 - (uint8_t)messageId {
220  return self->_message.msgid;
221 }
222 
223 - (NSString *)description {
224  return [NSString stringWithFormat:@"%@, systemId=%d, componentId=%d", [self class], self.systemId, self.componentId];
225 }
226 
227 @end
228 ''', xml)
229  f.close()
230 
231 def generate_message_definitions_h(directory, xml):
232  '''generate headerfile containing includes for all messages'''
233  f = open(os.path.join(directory, "MV" + camel_case_from_underscores(xml.basename) + "Messages.h"), mode='w')
234  t.write(f, '''
235 //
236 // MV${basename_camel_case}Messages.h
237 // MAVLink communications protocol built from ${basename}.xml
238 //
239 // Created by mavgen_objc.py
240 // http://qgroundcontrol.org/mavlink
241 //
242 
243 ${{message:#import "MVMessage${name_camel_case}.h"
244 }}
245 ''', xml)
246  f.close()
247 
248 def generate_message(directory, m):
249  '''generate per-message header and implementation file'''
250  f = open(os.path.join(directory, 'MVMessage%s.h' % m.name_camel_case), mode='w')
251  t.write(f, '''
252 //
253 // MVMessage${name_camel_case}.h
254 // MAVLink communications protocol built from ${basename}.xml
255 //
256 // Created by mavgen_objc.py
257 // http://qgroundcontrol.org/mavlink
258 //
259 
260 #import "MVMessage.h"
261 
262 /*!
263  Class that represents a ${name} Mavlink message.
264 
265  @discussion ${description}
266  */
267 @interface MVMessage${name_camel_case} : MVMessage
268 
269 - (id)initWithSystemId:(uint8_t)systemId componentId:(uint8_t)componentId${{arg_fields: ${name_lower_camel_case}:(${arg_type}${array_prefix})${name_lower_camel_case}}};
270 
271 ${{fields://! ${description}
272 - (${return_type})${name_lower_camel_case}${get_arg_objc};
273 
274 }}
275 @end
276 ''', m)
277  f.close()
278  f = open(os.path.join(directory, 'MVMessage%s.m' % m.name_camel_case), mode='w')
279  t.write(f, '''
280 //
281 // MVMessage${name_camel_case}.m
282 // MAVLink communications protocol built from ${basename}.xml
283 //
284 // Created by mavgen_objc.py
285 // http://qgroundcontrol.org/mavlink
286 //
287 
288 #import "MVMessage${name_camel_case}.h"
289 
290 @implementation MVMessage${name_camel_case}
291 
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}}});
295  }
296  return self;
297 }
298 
299 ${{fields:- (${return_type})${name_lower_camel_case}${get_arg_objc} {
300  ${return_method_implementation}
301 }
302 
303 }}
304 - (NSString *)description {
305  return [NSString stringWithFormat:@"%@${{fields:, ${name_lower_camel_case}=${print_format}}}", [super description]${{fields:, ${get_message}}}];
306 }
307 
308 @end
309 ''', m)
310  f.close()
311 
313  """generate a CamelCase string from an underscore_string."""
314  components = string.split('_')
315  string = ''
316  for component in components:
317  string += component[0].upper() + component[1:]
318  return string
319 
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:]
327  return string
328 
329 def generate_shared(basename, xml_list):
330  # Create a dictionary to hold all the values we want to use in the templates
331  template_dict = {}
332  template_dict['parse_time'] = xml_list[0].parse_time
333  template_dict['message'] = []
334  template_dict['message_definition_files'] = []
335 
336  print("Generating Objective-C implementation in directory %s" % basename)
337  mavparse.mkdir_p(basename)
338 
339  for xml in xml_list:
340  template_dict['message'].extend(xml.message)
341  basename_camel_case = camel_case_from_underscores(xml.basename)
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
345  else:
346  template_dict['basename'] = template_dict['basename'] + ', ' + xml.basename
347 
348  # Sort messages by ID
349  template_dict['message'] = sorted(template_dict['message'], key = lambda message : message.id)
350 
351  # Add name_camel_case to each message object
352  for message in template_dict['message']:
353  message.name_camel_case = camel_case_from_underscores(message.name_lower)
354 
355  generate_mavlink(basename, template_dict)
356  generate_base_message(basename, template_dict)
357 
358 def generate_message_definitions(basename, xml):
359  '''generate files for one XML file'''
360 
361  directory = os.path.join(basename, xml.basename)
362 
363  print("Generating Objective-C implementation in directory %s" % directory)
364  mavparse.mkdir_p(directory)
365 
366  xml.basename_camel_case = camel_case_from_underscores(xml.basename)
367 
368  # Add some extra field attributes for convenience
369  for m in xml.message:
370  m.basename = xml.basename
371  m.parse_time = xml.parse_time
372  m.name_camel_case = camel_case_from_underscores(m.name_lower)
373  for f in m.fields:
374  f.name_lower_camel_case = lower_camel_case_from_underscores(f.name);
375  f.get_message = "[self %s]" % f.name_lower_camel_case
376  f.return_method_implementation = ''
377  f.array_prefix = ''
378  f.array_return_arg = ''
379  f.get_arg = ''
380  f.get_arg_objc = ''
381  if f.enum:
382  f.return_type = f.enum
383  f.arg_type = f.enum
384  else:
385  f.return_type = f.type
386  f.arg_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"
398  else:
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)
407  if f.type == 'char':
408  # Special handling for strings (assumes all char arrays are strings)
409  f.return_type = 'NSString *'
410  f.get_arg_objc = ''
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}
416 
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}
420 
421  for m in xml.message:
422  m.arg_fields = []
423  for f in m.fields:
424  if not f.omit_arg:
425  m.arg_fields.append(f)
426 
427  generate_message_definitions_h(directory, xml)
428  for m in xml.message:
429  generate_message(directory, m)
430 
431 
432 def generate(basename, xml_list):
433  '''generate complete MAVLink Objective-C implemenation'''
434 
435  generate_shared(basename, xml_list)
436  for xml in xml_list:
437  generate_message_definitions(basename, xml)


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02