50 import roslib.packages
51 import roslib.gentools
52 from roslib.msgs
import MsgSpec
53 from roslib.srvs
import SrvSpec
56 from cStringIO
import StringIO
58 from io
import StringIO
65 return t
in [
'int8',
'uint8',
'int16',
'uint16']
68 return is_fixnum(t)
or t
in [
'byte',
'char',
'int32',
'uint32',
'int64',
'uint64']
71 return t
in [
'int8',
'int16',
'int32',
'int64']
74 return t
in [
'uint8',
'uint16',
'uint32',
'uint64']
83 return t
in [
'float16',
'float32',
'float64']
86 return t
in [
'time',
'duration']
94 return '(cl:vector %s)'%elt_type
99 if f.base_type ==
'Header':
100 return (
'std_msgs',
'Header')
102 return f.base_type.split(
'/')
107 return '%s-msg:%s'%(pkg, msg)
123 raise ValueError(
'%s is not a recognized primitive type'%t)
130 initform =
'(cl:make-instance \'%s)'%
msg_type(f)
133 len = f.array_len
or 0
134 return '(cl:make-array %s :element-type \'%s :initial-element %s)'%(len, elt_type, initform)
150 raise ValueError(
'%s is not a recognized primitive type'%t)
152 NUM_BYTES = {
'int8': 1,
'int16': 2,
'int32': 4,
'int64': 8,
153 'uint8': 1,
'uint16': 2,
'uint32': 4,
'uint64': 8}
168 def write(self, s, indent=True, newline=True):
204 self.writer.inc_indent(self.
inc)
206 self.writer.block_next_indent()
209 self.writer.dec_indent(self.
inc)
214 "Writes the beginning of the file: a comment saying it's auto-generated and the in-package form" 216 s.write(
'; Auto-generated. Do not edit!\n\n\n', newline=
False)
217 suffix =
'srv' if is_service
else 'msg' 218 s.write(
'(cl:in-package %s-%s)\n\n\n'%(spec.package, suffix), newline=
False)
222 s.write(
';//! \\htmlinclude %s.msg.html\n'%spec.actual_name, newline=
False)
225 "Write the definition of a slot corresponding to a single message field" 227 s.write(
'(%s'%field.name)
229 s.write(
':reader %s'%field.name)
230 s.write(
':initarg :%s'%field.name)
232 i = 0
if field.is_array
else 1
237 suffix =
'srv' if spec.component_type ==
'service' else 'msg' 238 for field
in spec.parsed_fields():
240 s.write(
'(cl:ensure-generic-function \'%s-val :lambda-list \'(m))' % field.name)
241 s.write(
'(cl:defmethod %s-val ((m %s))'%(field.name,
message_class(spec)))
243 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))
244 s.write(
'(%s m))'%field.name)
249 "Writes the defclass that defines the message type" 252 suffix =
'srv' if spec.component_type ==
'service' else 'msg' 253 s.write(
'(cl:defclass %s (roslisp-msg-protocol:ros-message)'%cl)
256 with
Indent(s, inc=1, indent_first=
False):
257 for field
in spec.parsed_fields():
259 s.write(
')', indent=
False)
262 s.write(
'(cl:defclass %s (%s)'%(new_cl, cl))
266 s.write(
'(cl:defmethod cl:initialize-instance :after ((m %s) cl:&rest args)'%cl)
268 s.write(
'(cl:declare (cl:ignorable args))')
269 s.write(
'(cl:unless (cl:typep m \'%s)'%new_cl)
271 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))
277 Return the CLOS class name for this message type 279 return '<%s>'%spec.actual_name
282 return spec.actual_name
287 var =
'__ros_arr_len' if is_array
else '__ros_str_len' 289 s.write(
'(cl:let ((%s (cl:length %s)))'%(var, v))
291 for x
in range(0, 32, 8):
292 s.write(
'(cl:write-byte (cl:ldb (cl:byte 8 %s) %s) ostream)'%(x, var))
293 s.write(
')', indent=
False)
297 for x
in range(0, num_bytes*8, 8):
298 s.write(
'(cl:write-byte (cl:ldb (cl:byte 8 %s) %s) ostream)'%(x, v))
301 num_bits = num_bytes*8
302 s.write(
'(cl:let* ((signed %s) (unsigned (cl:if (cl:< signed 0) (cl:+ signed %s) signed)))'%(v, 2**num_bits))
311 v =
'(cl:slot-value %s \'%s)'%(var, f.name)
if lookup_slot
else var
312 if f.base_type ==
'string':
314 s.write(
'(cl:map cl:nil #\'(cl:lambda (c) (cl:write-byte (cl:char-code c) ostream)) %s)'%v)
315 elif f.base_type ==
'float32':
316 s.write(
'(cl:let ((bits %s))'%
'(roslisp-utils:encode-single-float-bits %s)'%v)
320 elif f.base_type ==
'float64':
321 s.write(
'(cl:let ((bits %s))'%
'(roslisp-utils:encode-double-float-bits %s)'%v)
325 elif f.base_type ==
'bool':
326 s.write(
'(cl:write-byte (cl:ldb (cl:byte 8 0) (cl:if %s 1 0)) ostream)'%v)
327 elif f.base_type
in [
'byte',
'char']:
328 s.write(
'(cl:write-byte (cl:ldb (cl:byte 8 0) %s) ostream)'%v)
329 elif f.base_type
in [
'duration',
'time']:
330 s.write(
'(cl:let ((__sec (cl:floor %s))'%v)
331 s.write(
' (__nsec (cl:round (cl:* 1e9 (cl:- %s (cl:floor %s))))))'%(v,v))
341 raise ValueError(
'Unknown type: %s', f.base_type)
344 slot =
'(cl:slot-value msg \'%s)'%f.name
348 s.write(
'(cl:map cl:nil #\'(cl:lambda (ele) ')
350 s.block_next_indent()
359 to_write = slot
if lookup_slot
else var
360 s.write(
'(roslisp-msg-protocol:serialize %s ostream)'%to_write)
368 Write the serialize method 370 s.write(
'(cl:defmethod roslisp-msg-protocol:serialize ((msg %s) ostream)'%
message_class(spec))
372 s.write(
'"Serializes a message object of type \'%s"'%
message_class(spec))
373 for f
in spec.parsed_fields():
380 var =
'__ros_arr_len' if is_array
else '__ros_str_len' 381 s.write(
'(cl:let ((%s 0))'%var)
383 for x
in range(0, 32, 8):
384 s.write(
'(cl:setf (cl:ldb (cl:byte 8 %s) %s) (cl:read-byte istream))'%(x, var))
387 for x
in range(0, num_bytes*8, 8):
388 s.write(
'(cl:setf (cl:ldb (cl:byte 8 %s) %s) (cl:read-byte istream))'%(x, v))
391 s.write(
'(cl:let ((unsigned 0))')
392 num_bits = 8*num_bytes
395 s.write(
'(cl:setf %s (cl:if (cl:< unsigned %s) unsigned (cl:- unsigned %s))))'%(v, 2**(num_bits-1), 2**num_bits))
400 if f.base_type ==
'string':
403 s.write(
'(cl:setf %s (cl:make-string __ros_str_len))'%v)
404 s.write(
'(cl:dotimes (__ros_str_idx __ros_str_len msg)')
406 s.write(
'(cl:setf (cl:char %s __ros_str_idx) (cl:code-char (cl:read-byte istream)))))'%v)
407 elif f.base_type ==
'float32':
408 s.write(
'(cl:let ((bits 0))')
411 s.write(
'(cl:setf %s (roslisp-utils:decode-single-float-bits bits)))'%v)
412 elif f.base_type ==
'float64':
413 s.write(
'(cl:let ((bits 0))')
416 s.write(
'(cl:setf %s (roslisp-utils:decode-double-float-bits bits)))'%v)
417 elif f.base_type ==
'bool':
418 s.write(
'(cl:setf %s (cl:not (cl:zerop (cl:read-byte istream))))'%v)
419 elif f.base_type
in [
'byte',
'char']:
420 s.write(
'(cl:setf (cl:ldb (cl:byte 8 0) %s) (cl:read-byte istream))'%v)
421 elif f.base_type
in [
'duration',
'time']:
422 s.write(
'(cl:let ((__sec 0) (__nsec 0))')
426 s.write(
'(cl:setf %s (cl:+ (cl:coerce __sec \'cl:double-float) (cl:/ __nsec 1e9))))'%v)
432 raise ValueError(
'%s unknown'%f.base_type)
436 slot =
'(cl:slot-value msg \'%s)'%f.name
441 length =
'__ros_arr_len' 443 length =
'%s'%f.array_len
445 s.write(
'(cl:setf %s (cl:make-array %s))'%(slot, length))
446 s.write(
'(cl:let ((vals %s))'%slot)
447 var =
'(cl:aref vals i)' 449 s.write(
'(cl:dotimes (i %s)'%length)
457 s.write(
'(cl:setf %s (cl:make-instance \'%s))'%(var,
msg_type(f)))
458 s.write(
'(roslisp-msg-protocol:deserialize %s istream)'%var)
468 Write the deserialize method 470 s.write(
'(cl:defmethod roslisp-msg-protocol:deserialize ((msg %s) istream)'%
message_class(spec))
472 s.write(
'"Deserializes a message object of type \'%s"'%
message_class(spec))
473 for f
in spec.parsed_fields():
479 "Write the _package.lisp file" 480 s.write(
'(cl:defpackage %s-msg'%pkg,
False)
485 for spec
in roslib.msgs.get_pkg_msg_specs(pkg)[0]:
486 (p, msg_type) = spec[0].split(
'/')
487 msg_class =
'<%s>'%msg_type
488 s.write(
'"%s"'%msg_class.upper())
489 s.write(
'"%s"'%msg_type.upper())
493 "Write the _package.lisp file for a service directory" 494 s.write(
'(cl:defpackage %s-srv'%pkg,
False)
499 for spec
in roslib.srvs.get_pkg_srv_specs(pkg)[0]:
500 (_, srv_type) = spec[0].split(
'/')
501 s.write(
'"%s"'%srv_type.upper())
502 s.write(
'"<%s-REQUEST>"'%srv_type.upper())
503 s.write(
'"%s-REQUEST"'%srv_type.upper())
504 s.write(
'"<%s-RESPONSE>"'%srv_type.upper())
505 s.write(
'"%s-RESPONSE"'%srv_type.upper())
511 s.write(
':depends-on (:roslisp-msg-protocol :roslisp-utils ')
512 with
Indent(s, inc=13, indent_first=
False):
513 for d
in sorted(deps):
517 s.write(
':components ((:file "_package")')
519 for (full_name, _)
in msgs:
520 (_, name) = full_name.split(
'/')
521 s.write(
'(:file "%s" :depends-on ("_package_%s"))'%(name, name))
522 s.write(
'(:file "_package_%s" :depends-on ("_package"))'%name)
528 s.write(
'(cl:in-package :asdf)')
530 s.write(
'(defsystem "%s-srv"'%pkg)
531 services = roslib.srvs.get_pkg_srv_specs(pkg)[0]
535 for (_, spec)
in services:
536 for f
in spec.request.parsed_fields():
540 for f
in spec.response.parsed_fields():
549 s.write(
'(cl:in-package :asdf)')
551 s.write(
'(defsystem "%s-msg"'%pkg)
552 msgs = roslib.msgs.get_pkg_msg_specs(pkg)[0]
556 for (_, spec)
in msgs:
557 for f
in spec.parsed_fields():
566 "Write the package exports for this message/service" 567 is_srv = isinstance(spec, SrvSpec)
568 suffix =
'srv' if is_srv
else 'msg' 569 s.write(
'(cl:in-package %s-%s)'%(spec.package, suffix), indent=
False)
570 s.write(
'(cl:export \'(')
572 fields = spec.request.parsed_fields()[:]
573 fields.extend(spec.response.parsed_fields())
575 fields = spec.parsed_fields()
577 with
Indent(s, inc=10, indent_first=
False):
579 accessor =
'%s-val'%f.name
580 s.write(
'%s'%accessor.upper())
581 s.write(
'%s'%f.name.upper())
587 s.write(
'(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql \'%s)))'%c)
589 s.write(
'"Returns string type for a %s object of type \'%s"'%(spec.component_type, c))
590 s.write(
'"%s")'%spec.full_name)
595 gendeps_dict = roslib.gentools.get_dependencies(parent, spec.package,
597 md5sum = roslib.gentools.compute_md5(gendeps_dict)
599 s.write(
'(cl:defmethod roslisp-msg-protocol:md5sum ((type (cl:eql \'%s)))'%c)
602 s.write(
'"Returns md5sum for a message object of type \'%s"'%c)
603 s.write(
'"%s")'%md5sum)
607 s.write(
'(cl:defmethod roslisp-msg-protocol:message-definition ((type (cl:eql \'%s)))'%c)
609 s.write(
'"Returns full string definition for message of type \'%s"'%c)
610 s.write(
'(cl:format cl:nil "')
611 gendeps_dict = roslib.gentools.get_dependencies(spec, spec.package, compute_files=
False)
612 definition = roslib.gentools.compute_full_text(gendeps_dict)
613 lines = definition.split(
'\n')
615 l = line.replace(
'\\',
'\\\\')
616 l = l.replace(
'"',
'\\"')
617 s.write(
'%s~%%'%l, indent=
False)
618 s.write(
'~%', indent=
False)
619 s.write(
'"))', indent=
False)
622 if f.base_type
in [
'int8',
'uint8']:
624 elif f.base_type
in [
'int16',
'uint16']:
626 elif f.base_type
in [
'int32',
'uint32',
'float32']:
628 elif f.base_type
in [
'int64',
'uint64',
'float64',
'duration',
'time']:
630 elif f.base_type ==
'string':
631 s.write(
'4 (cl:length %s)'%var)
632 elif f.base_type
in [
'bool',
'byte',
'char']:
635 raise ValueError(
'Unknown: %s', f.base_type)
639 s.write(
'(cl:defmethod roslisp-msg-protocol:serialization-length ((msg %s))'%c)
643 for field
in spec.parsed_fields():
644 slot =
'(cl:slot-value msg \'%s)'%field.name
646 l =
'0' if field.array_len
else '4' 647 s.write(
'%s (cl:reduce #\'cl:+ %s :key #\'(cl:lambda (ele) (cl:declare (cl:ignorable ele)) (cl:+ '%(l, slot))
649 s.block_next_indent()
656 s.write(
'(roslisp-msg-protocol:serialization-length %s)'%var)
659 s.write(
')))',
False)
665 s.write(
'(cl:defmethod roslisp-msg-protocol:ros-message-to-list ((msg %s))'%c)
667 s.write(
'"Converts a ROS message object to a list"')
670 for f
in spec.parsed_fields():
671 s.write(
'(cl:cons \':%s (%s msg))'%(f.name, f.name))
677 s.write(
'(cl:defmethod roslisp-msg-protocol:symbol-codes ((msg-type (cl:eql \'%s)))'%cls)
679 s.write(
' "Constants for message type \'%s"'%cls)
681 with
Indent(s, indent_first=
False):
682 for c
in spec.constants:
683 s.write(
'(:%s . %s)'%(c.name.upper(), c.val))
689 spec.component_type=
'service' 704 spec.actual_name=spec.short_name
705 s.write(
'(cl:defmethod roslisp-msg-protocol:service-request-type ((msg (cl:eql \'%s)))'%spec.short_name)
708 s.write(
'(cl:defmethod roslisp-msg-protocol:service-response-type ((msg (cl:eql \'%s)))'%spec.short_name)
711 s.write(
'(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql \'%s)))'%spec.short_name)
713 s.write(
'"Returns string type for a service object of type \'%s"'%
message_class(spec))
714 s.write(
'"%s")'%spec.full_name)
721 @param msg_path: The path to the .msg file 724 (package_dir, package) = roslib.packages.get_dir_pkg(msg_path)
725 (_, spec) = roslib.msgs.load_from_file(msg_path, package)
726 spec.actual_name=spec.short_name
727 spec.component_type=
'message' 748 output_dir =
'%s/msg_gen/lisp'%package_dir
749 if (
not os.path.exists(output_dir)):
753 os.makedirs(output_dir)
757 with open(
'%s/%s.lisp'%(output_dir, spec.short_name),
'w')
as f:
758 f.write(io.getvalue() +
"\n")
769 with open(
'%s/_package_%s.lisp'%(output_dir, spec.short_name),
'w')
as f:
770 f.write(io.getvalue())
782 with open(
'%s/_package.lisp'%output_dir,
'w')
as f:
783 f.write(io.getvalue())
795 with open(
'%s/%s-msg.asd'%(output_dir, package),
'w')
as f:
796 f.write(io.getvalue())
801 "Generate code from .srv file" 802 (pkg_dir, pkg) = roslib.packages.get_dir_pkg(srv_path)
803 (_, spec) = roslib.srvs.load_from_file(srv_path, pkg)
804 output_dir =
'%s/srv_gen/lisp'%pkg_dir
805 if (
not os.path.exists(output_dir)):
809 os.makedirs(output_dir)
820 spec.request.actual_name=
'%s-request'%spec.short_name
821 spec.response.actual_name=
'%s-response'%spec.short_name
827 with open(
'%s/%s.lisp'%(output_dir, spec.short_name),
'w')
as f:
828 f.write(io.getvalue())
839 with open(
'%s/_package_%s.lisp'%(output_dir, spec.short_name),
'w')
as f:
840 f.write(io.getvalue())
850 with open(
'%s/_package.lisp'%output_dir,
'w')
as f:
851 f.write(io.getvalue())
861 with open(
'%s/%s-srv.asd'%(output_dir, pkg),
'w')
as f:
862 f.write(io.getvalue())
868 if __name__ ==
"__main__":
869 roslib.msgs.set_verbose(
False)
870 if sys.argv[1].endswith(
'.msg'):
872 elif sys.argv[1].endswith(
'.srv'):
875 raise ValueError(
'Invalid filename %s'%sys.argv[1])
def generate_srv(srv_path)
def write_accessor_exports(s, spec)
def write_srv_component(s, spec, parent)
def write(self, s, indent=True, newline=True)
def generate_msg(msg_path)
def write_defclass(s, spec)
def write_srv_exports(s, pkg)
def __init__(self, w, inc=2, indent_first=True)
def write_html_include(s, spec, is_srv=False)
def write_constants(s, spec)
def write_deserialize_length(s, is_array=False)
def write_list_converter(s, spec)
def write_serialize_builtin(s, f, var='msg', lookup_slot=True)
def write_deserialize_field(s, f, pkg)
def write_deserialize_bits_signed(s, v, num_bytes)
def write_deprecated_readers(s, spec)
def write_serialize_bits(s, v, num_bytes)
def is_fixnum(t)
Built in types.
def write_begin(s, spec, path, is_service=False)
def write_deserialize_builtin(s, f, v)
def write_slot_definition(s, field)
def dec_indent(self, dec=2)
def write_serialization_length(s, spec)
def inc_indent(self, inc=2)
def write_ros_datatype(s, spec)
def write_message_definition(s, spec)
def new_message_class(spec)
def __exit__(self, type, val, traceback)
def write_deserialize(s, spec)
def write_srv_asd(s, pkg)
def write_asd_deps(s, deps, msgs)
def write_serialize(s, spec)
def write_deserialize_bits(s, v, num_bytes)
def block_next_indent(self)
def write_md5sum(s, spec, parent=None)
def write_serialize_field(s, f)
def write_serialize_bits_signed(s, v, num_bytes)
def write_builtin_length(s, f, var='msg')
def write_serialize_length(s, v, is_array=False)
def write_class_exports(s, pkg)
def write_service_specific_methods(s, spec)