00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043 from __future__ import with_statement
00044
00045 import roslib; roslib.load_manifest('roslisp')
00046
00047 import sys
00048 import os
00049 import traceback
00050 import re
00051
00052 import roslib.msgs
00053 import roslib.srvs
00054 import roslib.packages
00055 import roslib.gentools
00056 from roslib.msgs import MsgSpec
00057 from roslib.srvs import SrvSpec
00058
00059 from cStringIO import StringIO
00060
00061
00062
00063
00064
00065 def is_fixnum(t):
00066 return t in ['int8', 'uint8', 'int16', 'uint16']
00067
00068 def is_integer(t):
00069 return is_fixnum(t) or t in ['byte', 'char', 'int32', 'uint32', 'int64', 'uint64']
00070
00071 def is_signed_int(t):
00072 return t in ['int8', 'int16', 'int32', 'int64']
00073
00074 def is_unsigned_int(t):
00075 return t in ['uint8', 'uint16', 'uint32', 'uint64']
00076
00077 def is_bool(t):
00078 return t == 'bool'
00079
00080 def is_string(t):
00081 return t == 'string'
00082
00083 def is_float(t):
00084 return t in ['float16', 'float32', 'float64']
00085
00086 def is_time(t):
00087 return t in ['time', 'duration']
00088
00089 def field_type(f):
00090 if f.is_builtin:
00091 elt_type = lisp_type(f.base_type)
00092 else:
00093 elt_type = msg_type(f)
00094 if f.is_array:
00095 return '(cl:vector %s)'%elt_type
00096 else:
00097 return elt_type
00098
00099 def parse_msg_type(f):
00100 if f.base_type == 'Header':
00101 return ('std_msgs', 'Header')
00102 else:
00103 return f.base_type.split('/')
00104
00105
00106 def msg_type(f):
00107 (pkg, msg) = parse_msg_type(f)
00108 return '%s-msg:%s'%(pkg, msg)
00109
00110 def lisp_type(t):
00111 if is_fixnum(t):
00112 return 'cl:fixnum'
00113 elif is_integer(t):
00114 return 'cl:integer'
00115 elif is_bool(t):
00116 return 'cl:boolean'
00117 elif is_float(t):
00118 return 'cl:float'
00119 elif is_time(t):
00120 return 'cl:real'
00121 elif is_string(t):
00122 return 'cl:string'
00123 else:
00124 raise ValueError('%s is not a recognized primitive type'%t)
00125
00126 def field_initform(f):
00127 if f.is_builtin:
00128 initform = lisp_initform(f.base_type)
00129 elt_type = lisp_type(f.base_type)
00130 else:
00131 initform = '(cl:make-instance \'%s)'%msg_type(f)
00132 elt_type = msg_type(f)
00133 if f.is_array:
00134 len = f.array_len or 0
00135 return '(cl:make-array %s :element-type \'%s :initial-element %s)'%(len, elt_type, initform)
00136 else:
00137 return initform
00138
00139 def lisp_initform(t):
00140 if is_integer(t):
00141 return '0'
00142 elif is_bool(t):
00143 return 'cl:nil'
00144 elif is_float(t):
00145 return '0.0'
00146 elif is_time(t):
00147 return 0
00148 elif is_string(t):
00149 return '\"\"'
00150 else:
00151 raise ValueError('%s is not a recognized primitive type'%t)
00152
00153 NUM_BYTES = {'int8': 1, 'int16': 2, 'int32': 4, 'int64': 8,
00154 'uint8': 1, 'uint16': 2, 'uint32': 4, 'uint64': 8}
00155
00156
00157
00158
00159
00160
00161
00162 class IndentedWriter():
00163
00164 def __init__(self, s):
00165 self.str = s
00166 self.indentation = 0
00167 self.block_indent = False
00168
00169 def write(self, s, indent=True, newline=True):
00170 if not indent:
00171 newline = False
00172 if self.block_indent:
00173 self.block_indent = False
00174 else:
00175 if newline:
00176 self.str.write('\n')
00177 if indent:
00178 for i in xrange(self.indentation):
00179 self.str.write(' ')
00180 self.str.write(s)
00181
00182 def newline(self):
00183 self.str.write('\n')
00184
00185 def inc_indent(self, inc=2):
00186 self.indentation += inc
00187
00188 def dec_indent(self, dec=2):
00189 self.indentation -= dec
00190
00191 def reset_indent(self):
00192 self.indentation = 0
00193
00194 def block_next_indent(self):
00195 self.block_indent = True
00196
00197 class Indent():
00198
00199 def __init__(self, w, inc=2, indent_first=True):
00200 self.writer = w
00201 self.inc = inc
00202 self.indent_first = indent_first
00203
00204 def __enter__(self):
00205 self.writer.inc_indent(self.inc)
00206 if not self.indent_first:
00207 self.writer.block_next_indent()
00208
00209 def __exit__(self, type, val, traceback):
00210 self.writer.dec_indent(self.inc)
00211
00212
00213
00214 def write_begin(s, spec, path, is_service=False):
00215 "Writes the beginning of the file: a comment saying it's auto-generated and the in-package form"
00216
00217 s.write('; Auto-generated. Do not edit!\n\n\n', newline=False)
00218 suffix = 'srv' if is_service else 'msg'
00219 s.write('(cl:in-package %s-%s)\n\n\n'%(spec.package, suffix), newline=False)
00220
00221 def write_html_include(s, spec, is_srv=False):
00222
00223 s.write(';//! \\htmlinclude %s.msg.html\n'%spec.actual_name, newline=False)
00224
00225 def write_slot_definition(s, field):
00226 "Write the definition of a slot corresponding to a single message field"
00227
00228 s.write('(%s'%field.name)
00229 with Indent(s, 1):
00230 s.write(':reader %s'%field.name)
00231 s.write(':initarg :%s'%field.name)
00232 s.write(':type %s'%field_type(field))
00233 i = 0 if field.is_array else 1
00234 with Indent(s, i):
00235 s.write(':initform %s)'%field_initform(field))
00236
00237 def write_deprecated_readers(s, spec):
00238 suffix = 'srv' if spec.component_type == 'service' else 'msg'
00239 for field in spec.parsed_fields():
00240 s.newline()
00241 s.write('(cl:ensure-generic-function \'%s-val :lambda-list \'(m))' % field.name)
00242 s.write('(cl:defmethod %s-val ((m %s))'%(field.name, message_class(spec)))
00243 with Indent(s):
00244 s.write('(roslisp-msg-protocol:msg-deprecation-warning "Using old-style slot reader %s-%s:%s-val is deprecated. Use %s-%s:%s instead.")'%(spec.package, suffix, field.name, spec.package, suffix, field.name))
00245 s.write('(%s m))'%field.name)
00246
00247
00248
00249 def write_defclass(s, spec):
00250 "Writes the defclass that defines the message type"
00251 cl = message_class(spec)
00252 new_cl = new_message_class(spec)
00253 suffix = 'srv' if spec.component_type == 'service' else 'msg'
00254 s.write('(cl:defclass %s (roslisp-msg-protocol:ros-message)'%cl)
00255 with Indent(s):
00256 s.write('(')
00257 with Indent(s, inc=1, indent_first=False):
00258 for field in spec.parsed_fields():
00259 write_slot_definition(s, field)
00260 s.write(')', indent=False)
00261 s.write(')')
00262 s.newline()
00263 s.write('(cl:defclass %s (%s)'%(new_cl, cl))
00264 with Indent(s):
00265 s.write('())')
00266 s.newline()
00267 s.write('(cl:defmethod cl:initialize-instance :after ((m %s) cl:&rest args)'%cl)
00268 with Indent(s):
00269 s.write('(cl:declare (cl:ignorable args))')
00270 s.write('(cl:unless (cl:typep m \'%s)'%new_cl)
00271 with Indent(s):
00272 s.write('(roslisp-msg-protocol:msg-deprecation-warning "using old message class name %s-%s:%s is deprecated: use %s-%s:%s instead.")))'%(spec.package, suffix, cl, spec.package, suffix, new_cl))
00273
00274
00275
00276 def message_class(spec):
00277 """
00278 Return the CLOS class name for this message type
00279 """
00280 return '<%s>'%spec.actual_name
00281
00282 def new_message_class(spec):
00283 return spec.actual_name
00284
00285
00286 def write_serialize_length(s, v, is_array=False):
00287
00288 var = '__ros_arr_len' if is_array else '__ros_str_len'
00289
00290 s.write('(cl:let ((%s (cl:length %s)))'%(var, v))
00291 with Indent(s):
00292 for x in range(0, 32, 8):
00293 s.write('(cl:write-byte (cl:ldb (cl:byte 8 %s) %s) ostream)'%(x, var))
00294 s.write(')', indent=False)
00295
00296
00297 def write_serialize_bits(s, v, num_bytes):
00298 for x in range(0, num_bytes*8, 8):
00299 s.write('(cl:write-byte (cl:ldb (cl:byte 8 %s) %s) ostream)'%(x, v))
00300
00301 def write_serialize_bits_signed(s, v, num_bytes):
00302 num_bits = num_bytes*8
00303 s.write('(cl:let* ((signed %s) (unsigned (cl:if (cl:< signed 0) (cl:+ signed %s) signed)))'%(v, 2**num_bits))
00304 with Indent(s):
00305 write_serialize_bits(s, 'unsigned', num_bytes)
00306 s.write(')')
00307
00308
00309
00310
00311 def write_serialize_builtin(s, f, var='msg', lookup_slot=True):
00312 v = '(cl:slot-value %s \'%s)'%(var, f.name) if lookup_slot else var
00313 if f.base_type == 'string':
00314 write_serialize_length(s, v)
00315 s.write('(cl:map cl:nil #\'(cl:lambda (c) (cl:write-byte (cl:char-code c) ostream)) %s)'%v)
00316 elif f.base_type == 'float32':
00317 s.write('(cl:let ((bits %s))'%'(roslisp-utils:encode-single-float-bits %s)'%v)
00318 with Indent(s):
00319 write_serialize_bits(s, 'bits', 4)
00320 s.write(')', False)
00321 elif f.base_type == 'float64':
00322 s.write('(cl:let ((bits %s))'%'(roslisp-utils:encode-double-float-bits %s)'%v)
00323 with Indent(s):
00324 write_serialize_bits(s, 'bits', 8)
00325 s.write(')', False)
00326 elif f.base_type == 'bool':
00327 s.write('(cl:write-byte (cl:ldb (cl:byte 8 0) (cl:if %s 1 0)) ostream)'%v)
00328 elif f.base_type in ['byte', 'char']:
00329 s.write('(cl:write-byte (cl:ldb (cl:byte 8 0) %s) ostream)'%v)
00330 elif f.base_type in ['duration', 'time']:
00331 s.write('(cl:let ((__sec (cl:floor %s))'%v)
00332 s.write(' (__nsec (cl:round (cl:* 1e9 (cl:- %s (cl:floor %s))))))'%(v,v))
00333 with Indent(s):
00334 write_serialize_bits(s, '__sec', 4)
00335 write_serialize_bits(s, '__nsec', 4)
00336 s.write(')', False)
00337 elif is_signed_int(f.base_type):
00338 write_serialize_bits_signed(s, v, NUM_BYTES[f.base_type])
00339 elif is_unsigned_int(f.base_type):
00340 write_serialize_bits(s, v, NUM_BYTES[f.base_type])
00341 else:
00342 raise ValueError('Unknown type: %s', f.base_type)
00343
00344 def write_serialize_field(s, f):
00345 slot = '(cl:slot-value msg \'%s)'%f.name
00346 if f.is_array:
00347 if not f.array_len:
00348 write_serialize_length(s, slot, True)
00349 s.write('(cl:map cl:nil #\'(cl:lambda (ele) ')
00350 var = 'ele'
00351 s.block_next_indent()
00352 lookup_slot = False
00353 else:
00354 var='msg'
00355 lookup_slot = True
00356
00357 if f.is_builtin:
00358 write_serialize_builtin(s, f, var, lookup_slot=lookup_slot)
00359 else:
00360 to_write = slot if lookup_slot else var
00361 s.write('(roslisp-msg-protocol:serialize %s ostream)'%to_write)
00362
00363 if f.is_array:
00364 s.write(')', False)
00365 s.write(' %s)'%slot)
00366
00367 def write_serialize(s, spec):
00368 """
00369 Write the serialize method
00370 """
00371 s.write('(cl:defmethod roslisp-msg-protocol:serialize ((msg %s) ostream)'%message_class(spec))
00372 with Indent(s):
00373 s.write('"Serializes a message object of type \'%s"'%message_class(spec))
00374 for f in spec.parsed_fields():
00375 write_serialize_field(s, f)
00376 s.write(')')
00377
00378
00379
00380 def write_deserialize_length(s, is_array=False):
00381 var = '__ros_arr_len' if is_array else '__ros_str_len'
00382 s.write('(cl:let ((%s 0))'%var)
00383 with Indent(s):
00384 for x in range(0, 32, 8):
00385 s.write('(cl:setf (cl:ldb (cl:byte 8 %s) %s) (cl:read-byte istream))'%(x, var))
00386
00387 def write_deserialize_bits(s, v, num_bytes):
00388 for x in range(0, num_bytes*8, 8):
00389 s.write('(cl:setf (cl:ldb (cl:byte 8 %s) %s) (cl:read-byte istream))'%(x, v))
00390
00391 def write_deserialize_bits_signed(s, v, num_bytes):
00392 s.write('(cl:let ((unsigned 0))')
00393 num_bits = 8*num_bytes
00394 with Indent(s):
00395 write_deserialize_bits(s, 'unsigned', num_bytes)
00396 s.write('(cl:setf %s (cl:if (cl:< unsigned %s) unsigned (cl:- unsigned %s))))'%(v, 2**(num_bits-1), 2**num_bits))
00397
00398
00399
00400 def write_deserialize_builtin(s, f, v):
00401 if f.base_type == 'string':
00402 write_deserialize_length(s)
00403 with Indent(s):
00404 s.write('(cl:setf %s (cl:make-string __ros_str_len))'%v)
00405 s.write('(cl:dotimes (__ros_str_idx __ros_str_len msg)')
00406 with Indent(s):
00407 s.write('(cl:setf (cl:char %s __ros_str_idx) (cl:code-char (cl:read-byte istream)))))'%v)
00408 elif f.base_type == 'float32':
00409 s.write('(cl:let ((bits 0))')
00410 with Indent(s):
00411 write_deserialize_bits(s, 'bits', 4)
00412 s.write('(cl:setf %s (roslisp-utils:decode-single-float-bits bits)))'%v)
00413 elif f.base_type == 'float64':
00414 s.write('(cl:let ((bits 0))')
00415 with Indent(s):
00416 write_deserialize_bits(s, 'bits', 8)
00417 s.write('(cl:setf %s (roslisp-utils:decode-double-float-bits bits)))'%v)
00418 elif f.base_type == 'bool':
00419 s.write('(cl:setf %s (cl:not (cl:zerop (cl:read-byte istream))))'%v)
00420 elif f.base_type in ['byte', 'char']:
00421 s.write('(cl:setf (cl:ldb (cl:byte 8 0) %s) (cl:read-byte istream))'%v)
00422 elif f.base_type in ['duration', 'time']:
00423 s.write('(cl:let ((__sec 0) (__nsec 0))')
00424 with Indent(s):
00425 write_deserialize_bits(s, '__sec', 4)
00426 write_deserialize_bits(s, '__nsec', 4)
00427 s.write('(cl:setf %s (cl:+ (cl:coerce __sec \'cl:double-float) (cl:/ __nsec 1e9))))'%v)
00428 elif is_signed_int(f.base_type):
00429 write_deserialize_bits_signed(s, v, NUM_BYTES[f.base_type])
00430 elif is_unsigned_int(f.base_type):
00431 write_deserialize_bits(s, v, NUM_BYTES[f.base_type])
00432 else:
00433 raise ValueError('%s unknown'%f.base_type)
00434
00435
00436 def write_deserialize_field(s, f, pkg):
00437 slot = '(cl:slot-value msg \'%s)'%f.name
00438 var = slot
00439 if f.is_array:
00440 if not f.array_len:
00441 write_deserialize_length(s, True)
00442 length = '__ros_arr_len'
00443 else:
00444 length = '%s'%f.array_len
00445
00446 s.write('(cl:setf %s (cl:make-array %s))'%(slot, length))
00447 s.write('(cl:let ((vals %s))'%slot)
00448 var = '(cl:aref vals i)'
00449 with Indent(s):
00450 s.write('(cl:dotimes (i %s)'%length)
00451
00452 if f.is_builtin:
00453 with Indent(s):
00454 write_deserialize_builtin(s, f, var)
00455 else:
00456 if f.is_array:
00457 with Indent(s):
00458 s.write('(cl:setf %s (cl:make-instance \'%s))'%(var, msg_type(f)))
00459 s.write('(roslisp-msg-protocol:deserialize %s istream)'%var)
00460
00461 if f.is_array:
00462 s.write('))', False)
00463 if not f.array_len:
00464 s.write(')', False)
00465
00466
00467 def write_deserialize(s, spec):
00468 """
00469 Write the deserialize method
00470 """
00471 s.write('(cl:defmethod roslisp-msg-protocol:deserialize ((msg %s) istream)'%message_class(spec))
00472 with Indent(s):
00473 s.write('"Deserializes a message object of type \'%s"'%message_class(spec))
00474 for f in spec.parsed_fields():
00475 write_deserialize_field(s, f, spec.package)
00476 s.write('msg')
00477 s.write(')')
00478
00479 def write_class_exports(s, pkg):
00480 "Write the _package.lisp file"
00481 s.write('(cl:defpackage %s-msg'%pkg, False)
00482 with Indent(s):
00483 s.write('(:use )')
00484 s.write('(:export')
00485 with Indent(s, inc=1):
00486 for spec in roslib.msgs.get_pkg_msg_specs(pkg)[0]:
00487 (p, msg_type) = spec[0].split('/')
00488 msg_class = '<%s>'%msg_type
00489 s.write('"%s"'%msg_class.upper())
00490 s.write('"%s"'%msg_type.upper())
00491 s.write('))\n\n')
00492
00493 def write_srv_exports(s, pkg):
00494 "Write the _package.lisp file for a service directory"
00495 s.write('(cl:defpackage %s-srv'%pkg, False)
00496 with Indent(s):
00497 s.write('(:use )')
00498 s.write('(:export')
00499 with Indent(s, inc=1):
00500 for spec in roslib.srvs.get_pkg_srv_specs(pkg)[0]:
00501 (_, srv_type) = spec[0].split('/')
00502 s.write('"%s"'%srv_type.upper())
00503 s.write('"<%s-REQUEST>"'%srv_type.upper())
00504 s.write('"%s-REQUEST"'%srv_type.upper())
00505 s.write('"<%s-RESPONSE>"'%srv_type.upper())
00506 s.write('"%s-RESPONSE"'%srv_type.upper())
00507 s.write('))\n\n')
00508
00509
00510 def write_asd_deps(s, deps, msgs):
00511 with Indent(s):
00512 s.write(':depends-on (:roslisp-msg-protocol :roslisp-utils ')
00513 with Indent(s, inc=13, indent_first=False):
00514 for d in sorted(deps):
00515 s.write(':%s-msg'%d)
00516 s.write(')')
00517 with Indent(s):
00518 s.write(':components ((:file "_package")')
00519 with Indent(s):
00520 for (full_name, _) in msgs:
00521 (_, name) = full_name.split('/')
00522 s.write('(:file "%s" :depends-on ("_package_%s"))'%(name, name))
00523 s.write('(:file "_package_%s" :depends-on ("_package"))'%name)
00524 s.write('))')
00525
00526
00527
00528 def write_srv_asd(s, pkg):
00529 s.write('(cl:in-package :asdf)')
00530 s.newline()
00531 s.write('(defsystem "%s-srv"'%pkg)
00532 services = roslib.srvs.get_pkg_srv_specs(pkg)[0]
00533
00534
00535 deps = set()
00536 for (_, spec) in services:
00537 for f in spec.request.parsed_fields():
00538 if not f.is_builtin:
00539 (p, _) = parse_msg_type(f)
00540 deps.add(p)
00541 for f in spec.response.parsed_fields():
00542 if not f.is_builtin:
00543 (p, _) = parse_msg_type(f)
00544 deps.add(p)
00545
00546 write_asd_deps(s, deps, services)
00547
00548
00549 def write_asd(s, pkg):
00550 s.write('(cl:in-package :asdf)')
00551 s.newline()
00552 s.write('(defsystem "%s-msg"'%pkg)
00553 msgs = roslib.msgs.get_pkg_msg_specs(pkg)[0]
00554
00555
00556 deps = set()
00557 for (_, spec) in msgs:
00558 for f in spec.parsed_fields():
00559 if not f.is_builtin:
00560 (p, _) = parse_msg_type(f)
00561 deps.add(p)
00562 if pkg in deps:
00563 deps.remove(pkg)
00564 write_asd_deps(s, deps, msgs)
00565
00566 def write_accessor_exports(s, spec):
00567 "Write the package exports for this message/service"
00568 is_srv = isinstance(spec, SrvSpec)
00569 suffix = 'srv' if is_srv else 'msg'
00570 s.write('(cl:in-package %s-%s)'%(spec.package, suffix), indent=False)
00571 s.write('(cl:export \'(')
00572 if is_srv:
00573 fields = spec.request.parsed_fields()[:]
00574 fields.extend(spec.response.parsed_fields())
00575 else:
00576 fields = spec.parsed_fields()
00577
00578 with Indent(s, inc=10, indent_first=False):
00579 for f in fields:
00580 accessor = '%s-val'%f.name
00581 s.write('%s'%accessor.upper())
00582 s.write('%s'%f.name.upper())
00583 s.write('))')
00584
00585
00586 def write_ros_datatype(s, spec):
00587 for c in (message_class(spec), new_message_class(spec)):
00588 s.write('(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql \'%s)))'%c)
00589 with Indent(s):
00590 s.write('"Returns string type for a %s object of type \'%s"'%(spec.component_type, c))
00591 s.write('"%s")'%spec.full_name)
00592
00593 def write_md5sum(s, spec, parent=None):
00594 if parent is None:
00595 parent = spec
00596 gendeps_dict = roslib.gentools.get_dependencies(parent, spec.package,
00597 compute_files=False)
00598 md5sum = roslib.gentools.compute_md5(gendeps_dict)
00599 for c in (message_class(spec), new_message_class(spec)):
00600 s.write('(cl:defmethod roslisp-msg-protocol:md5sum ((type (cl:eql \'%s)))'%c)
00601 with Indent(s):
00602
00603 s.write('"Returns md5sum for a message object of type \'%s"'%c)
00604 s.write('"%s")'%md5sum)
00605
00606 def write_message_definition(s, spec):
00607 for c in (message_class(spec), new_message_class(spec)):
00608 s.write('(cl:defmethod roslisp-msg-protocol:message-definition ((type (cl:eql \'%s)))'%c)
00609 with Indent(s):
00610 s.write('"Returns full string definition for message of type \'%s"'%c)
00611 s.write('(cl:format cl:nil "')
00612 gendeps_dict = roslib.gentools.get_dependencies(spec, spec.package, compute_files=False)
00613 definition = roslib.gentools.compute_full_text(gendeps_dict)
00614 lines = definition.split('\n')
00615 for line in lines:
00616 l = line.replace('\\', '\\\\')
00617 l = l.replace('"', '\\"')
00618 s.write('%s~%%'%l, indent=False)
00619 s.write('~%', indent=False)
00620 s.write('"))', indent=False)
00621
00622 def write_builtin_length(s, f, var='msg'):
00623 if f.base_type in ['int8', 'uint8']:
00624 s.write('1')
00625 elif f.base_type in ['int16', 'uint16']:
00626 s.write('2')
00627 elif f.base_type in ['int32', 'uint32', 'float32']:
00628 s.write('4')
00629 elif f.base_type in ['int64', 'uint64', 'float64', 'duration', 'time']:
00630 s.write('8')
00631 elif f.base_type == 'string':
00632 s.write('4 (cl:length %s)'%var)
00633 elif f.base_type in ['bool', 'byte', 'char']:
00634 s.write('1')
00635 else:
00636 raise ValueError('Unknown: %s', f.base_type)
00637
00638 def write_serialization_length(s, spec):
00639 c = message_class(spec)
00640 s.write('(cl:defmethod roslisp-msg-protocol:serialization-length ((msg %s))'%c)
00641 with Indent(s):
00642 s.write('(cl:+ 0')
00643 with Indent(s, 3):
00644 for field in spec.parsed_fields():
00645 slot = '(cl:slot-value msg \'%s)'%field.name
00646 if field.is_array:
00647 l = '0' if field.array_len else '4'
00648 s.write('%s (cl:reduce #\'cl:+ %s :key #\'(cl:lambda (ele) (cl:declare (cl:ignorable ele)) (cl:+ '%(l, slot))
00649 var = 'ele'
00650 s.block_next_indent()
00651 else:
00652 var = slot
00653
00654 if field.is_builtin:
00655 write_builtin_length(s, field, var)
00656 else:
00657 s.write('(roslisp-msg-protocol:serialization-length %s)'%var)
00658
00659 if field.is_array:
00660 s.write(')))', False)
00661 s.write('))')
00662
00663
00664 def write_list_converter(s, spec):
00665 c = message_class(spec)
00666 s.write('(cl:defmethod roslisp-msg-protocol:ros-message-to-list ((msg %s))'%c)
00667 with Indent(s):
00668 s.write('"Converts a ROS message object to a list"')
00669 s.write('(cl:list \'%s'%new_message_class(spec))
00670 with Indent(s):
00671 for f in spec.parsed_fields():
00672 s.write('(cl:cons \':%s (%s msg))'%(f.name, f.name))
00673 s.write('))')
00674
00675 def write_constants(s, spec):
00676 if spec.constants:
00677 for cls in (message_class(spec), new_message_class(spec)):
00678 s.write('(cl:defmethod roslisp-msg-protocol:symbol-codes ((msg-type (cl:eql \'%s)))'%cls)
00679 with Indent(s):
00680 s.write(' "Constants for message type \'%s"'%cls)
00681 s.write('\'(')
00682 with Indent(s, indent_first=False):
00683 for c in spec.constants:
00684 s.write('(:%s . %s)'%(c.name.upper(), c.val))
00685 s.write(')', False)
00686 s.write(')')
00687
00688
00689 def write_srv_component(s, spec, parent):
00690 spec.component_type='service'
00691 write_html_include(s, spec)
00692 write_defclass(s, spec)
00693 write_deprecated_readers(s, spec)
00694 write_constants(s, spec)
00695 write_serialize(s, spec)
00696 write_deserialize(s, spec)
00697 write_ros_datatype(s, spec)
00698 write_md5sum(s, spec, parent)
00699 write_message_definition(s, spec)
00700 write_serialization_length(s, spec)
00701 write_list_converter(s, spec)
00702
00703
00704 def write_service_specific_methods(s, spec):
00705 spec.actual_name=spec.short_name
00706 s.write('(cl:defmethod roslisp-msg-protocol:service-request-type ((msg (cl:eql \'%s)))'%spec.short_name)
00707 with Indent(s):
00708 s.write('\'%s)'%new_message_class(spec.request))
00709 s.write('(cl:defmethod roslisp-msg-protocol:service-response-type ((msg (cl:eql \'%s)))'%spec.short_name)
00710 with Indent(s):
00711 s.write('\'%s)'%new_message_class(spec.response))
00712 s.write('(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql \'%s)))'%spec.short_name)
00713 with Indent(s):
00714 s.write('"Returns string type for a service object of type \'%s"'%message_class(spec))
00715 s.write('"%s")'%spec.full_name)
00716
00717
00718 def generate_msg(msg_path):
00719 """
00720 Generate a message
00721
00722 @param msg_path: The path to the .msg file
00723 @type msg_path: str
00724 """
00725 (package_dir, package) = roslib.packages.get_dir_pkg(msg_path)
00726 (_, spec) = roslib.msgs.load_from_file(msg_path, package)
00727 spec.actual_name=spec.short_name
00728 spec.component_type='message'
00729
00730
00731
00732
00733
00734 io = StringIO()
00735 s = IndentedWriter(io)
00736 write_begin(s, spec, msg_path)
00737 write_html_include(s, spec)
00738 write_defclass(s, spec)
00739 write_deprecated_readers(s, spec)
00740 write_constants(s, spec)
00741 write_serialize(s, spec)
00742 write_deserialize(s, spec)
00743 write_ros_datatype(s, spec)
00744 write_md5sum(s, spec)
00745 write_message_definition(s, spec)
00746 write_serialization_length(s, spec)
00747 write_list_converter(s, spec)
00748
00749 output_dir = '%s/msg_gen/lisp'%package_dir
00750 if (not os.path.exists(output_dir)):
00751
00752
00753 try:
00754 os.makedirs(output_dir)
00755 except OSError, e:
00756 pass
00757
00758 with open('%s/%s.lisp'%(output_dir, spec.short_name), 'w') as f:
00759 print >> f, io.getvalue()
00760 io.close()
00761
00762
00763
00764
00765
00766
00767 io = StringIO()
00768 s = IndentedWriter(io)
00769 write_accessor_exports(s, spec)
00770 with open('%s/_package_%s.lisp'%(output_dir, spec.short_name), 'w') as f:
00771 f.write(io.getvalue())
00772 io.close()
00773
00774
00775
00776
00777
00778
00779
00780 io = StringIO()
00781 s = IndentedWriter(io)
00782 write_class_exports(s, package)
00783 with open('%s/_package.lisp'%output_dir, 'w') as f:
00784 f.write(io.getvalue())
00785 io.close()
00786
00787
00788
00789
00790
00791
00792
00793 io = StringIO()
00794 s = IndentedWriter(io)
00795 write_asd(s, package)
00796 with open('%s/%s-msg.asd'%(output_dir, package), 'w') as f:
00797 f.write(io.getvalue())
00798 io.close()
00799
00800
00801 def generate_srv(srv_path):
00802 "Generate code from .srv file"
00803 (pkg_dir, pkg) = roslib.packages.get_dir_pkg(srv_path)
00804 (_, spec) = roslib.srvs.load_from_file(srv_path, pkg)
00805 output_dir = '%s/srv_gen/lisp'%pkg_dir
00806 if (not os.path.exists(output_dir)):
00807
00808
00809 try:
00810 os.makedirs(output_dir)
00811 except OSError, e:
00812 pass
00813
00814
00815
00816
00817
00818 io = StringIO()
00819 s = IndentedWriter(io)
00820 write_begin(s, spec, srv_path, True)
00821 spec.request.actual_name='%s-request'%spec.short_name
00822 spec.response.actual_name='%s-response'%spec.short_name
00823 write_srv_component(s, spec.request, spec)
00824 s.newline()
00825 write_srv_component(s, spec.response, spec)
00826 write_service_specific_methods(s, spec)
00827
00828 with open('%s/%s.lisp'%(output_dir, spec.short_name), 'w') as f:
00829 print >> f, io.getvalue()
00830 io.close()
00831
00832
00833
00834
00835
00836
00837 io = StringIO()
00838 s = IndentedWriter(io)
00839 write_accessor_exports(s, spec)
00840 with open('%s/_package_%s.lisp'%(output_dir, spec.short_name), 'w') as f:
00841 f.write(io.getvalue())
00842 io.close()
00843
00844
00845
00846
00847
00848 io = StringIO()
00849 s = IndentedWriter(io)
00850 write_srv_exports(s, pkg)
00851 with open('%s/_package.lisp'%output_dir, 'w') as f:
00852 f.write(io.getvalue())
00853 io.close()
00854
00855
00856
00857
00858
00859 io = StringIO()
00860 s = IndentedWriter(io)
00861 write_srv_asd(s, pkg)
00862 with open('%s/%s-srv.asd'%(output_dir, pkg), 'w') as f:
00863 f.write(io.getvalue())
00864 io.close()
00865
00866
00867
00868
00869 if __name__ == "__main__":
00870 roslib.msgs.set_verbose(False)
00871 if sys.argv[1].endswith('.msg'):
00872 generate_msg(sys.argv[1])
00873 elif sys.argv[1].endswith('.srv'):
00874 generate_srv(sys.argv[1])
00875 else:
00876 raise ValueError('Invalid filename %s'%sys.argv[1])