/usr/share/common-lisp/ros/sensor_msgs/msg/PointCloud.lisp is in cl-sensor-msgs 1.12.5-2.
This file is owned by root:root, with mode 0o644.
The actual contents of the file can be viewed below.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 | ; Auto-generated. Do not edit!
(cl:in-package sensor_msgs-msg)
;//! \htmlinclude PointCloud.msg.html
(cl:defclass <PointCloud> (roslisp-msg-protocol:ros-message)
((header
:reader header
:initarg :header
:type std_msgs-msg:Header
:initform (cl:make-instance 'std_msgs-msg:Header))
(points
:reader points
:initarg :points
:type (cl:vector geometry_msgs-msg:Point32)
:initform (cl:make-array 0 :element-type 'geometry_msgs-msg:Point32 :initial-element (cl:make-instance 'geometry_msgs-msg:Point32)))
(channels
:reader channels
:initarg :channels
:type (cl:vector sensor_msgs-msg:ChannelFloat32)
:initform (cl:make-array 0 :element-type 'sensor_msgs-msg:ChannelFloat32 :initial-element (cl:make-instance 'sensor_msgs-msg:ChannelFloat32))))
)
(cl:defclass PointCloud (<PointCloud>)
())
(cl:defmethod cl:initialize-instance :after ((m <PointCloud>) cl:&rest args)
(cl:declare (cl:ignorable args))
(cl:unless (cl:typep m 'PointCloud)
(roslisp-msg-protocol:msg-deprecation-warning "using old message class name sensor_msgs-msg:<PointCloud> is deprecated: use sensor_msgs-msg:PointCloud instead.")))
(cl:ensure-generic-function 'header-val :lambda-list '(m))
(cl:defmethod header-val ((m <PointCloud>))
(roslisp-msg-protocol:msg-deprecation-warning "Using old-style slot reader sensor_msgs-msg:header-val is deprecated. Use sensor_msgs-msg:header instead.")
(header m))
(cl:ensure-generic-function 'points-val :lambda-list '(m))
(cl:defmethod points-val ((m <PointCloud>))
(roslisp-msg-protocol:msg-deprecation-warning "Using old-style slot reader sensor_msgs-msg:points-val is deprecated. Use sensor_msgs-msg:points instead.")
(points m))
(cl:ensure-generic-function 'channels-val :lambda-list '(m))
(cl:defmethod channels-val ((m <PointCloud>))
(roslisp-msg-protocol:msg-deprecation-warning "Using old-style slot reader sensor_msgs-msg:channels-val is deprecated. Use sensor_msgs-msg:channels instead.")
(channels m))
(cl:defmethod roslisp-msg-protocol:serialize ((msg <PointCloud>) ostream)
"Serializes a message object of type '<PointCloud>"
(roslisp-msg-protocol:serialize (cl:slot-value msg 'header) ostream)
(cl:let ((__ros_arr_len (cl:length (cl:slot-value msg 'points))))
(cl:write-byte (cl:ldb (cl:byte 8 0) __ros_arr_len) ostream)
(cl:write-byte (cl:ldb (cl:byte 8 8) __ros_arr_len) ostream)
(cl:write-byte (cl:ldb (cl:byte 8 16) __ros_arr_len) ostream)
(cl:write-byte (cl:ldb (cl:byte 8 24) __ros_arr_len) ostream))
(cl:map cl:nil #'(cl:lambda (ele) (roslisp-msg-protocol:serialize ele ostream))
(cl:slot-value msg 'points))
(cl:let ((__ros_arr_len (cl:length (cl:slot-value msg 'channels))))
(cl:write-byte (cl:ldb (cl:byte 8 0) __ros_arr_len) ostream)
(cl:write-byte (cl:ldb (cl:byte 8 8) __ros_arr_len) ostream)
(cl:write-byte (cl:ldb (cl:byte 8 16) __ros_arr_len) ostream)
(cl:write-byte (cl:ldb (cl:byte 8 24) __ros_arr_len) ostream))
(cl:map cl:nil #'(cl:lambda (ele) (roslisp-msg-protocol:serialize ele ostream))
(cl:slot-value msg 'channels))
)
(cl:defmethod roslisp-msg-protocol:deserialize ((msg <PointCloud>) istream)
"Deserializes a message object of type '<PointCloud>"
(roslisp-msg-protocol:deserialize (cl:slot-value msg 'header) istream)
(cl:let ((__ros_arr_len 0))
(cl:setf (cl:ldb (cl:byte 8 0) __ros_arr_len) (cl:read-byte istream))
(cl:setf (cl:ldb (cl:byte 8 8) __ros_arr_len) (cl:read-byte istream))
(cl:setf (cl:ldb (cl:byte 8 16) __ros_arr_len) (cl:read-byte istream))
(cl:setf (cl:ldb (cl:byte 8 24) __ros_arr_len) (cl:read-byte istream))
(cl:setf (cl:slot-value msg 'points) (cl:make-array __ros_arr_len))
(cl:let ((vals (cl:slot-value msg 'points)))
(cl:dotimes (i __ros_arr_len)
(cl:setf (cl:aref vals i) (cl:make-instance 'geometry_msgs-msg:Point32))
(roslisp-msg-protocol:deserialize (cl:aref vals i) istream))))
(cl:let ((__ros_arr_len 0))
(cl:setf (cl:ldb (cl:byte 8 0) __ros_arr_len) (cl:read-byte istream))
(cl:setf (cl:ldb (cl:byte 8 8) __ros_arr_len) (cl:read-byte istream))
(cl:setf (cl:ldb (cl:byte 8 16) __ros_arr_len) (cl:read-byte istream))
(cl:setf (cl:ldb (cl:byte 8 24) __ros_arr_len) (cl:read-byte istream))
(cl:setf (cl:slot-value msg 'channels) (cl:make-array __ros_arr_len))
(cl:let ((vals (cl:slot-value msg 'channels)))
(cl:dotimes (i __ros_arr_len)
(cl:setf (cl:aref vals i) (cl:make-instance 'sensor_msgs-msg:ChannelFloat32))
(roslisp-msg-protocol:deserialize (cl:aref vals i) istream))))
msg
)
(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql '<PointCloud>)))
"Returns string type for a message object of type '<PointCloud>"
"sensor_msgs/PointCloud")
(cl:defmethod roslisp-msg-protocol:ros-datatype ((msg (cl:eql 'PointCloud)))
"Returns string type for a message object of type 'PointCloud"
"sensor_msgs/PointCloud")
(cl:defmethod roslisp-msg-protocol:md5sum ((type (cl:eql '<PointCloud>)))
"Returns md5sum for a message object of type '<PointCloud>"
"d8e9c3f5afbdd8a130fd1d2763945fca")
(cl:defmethod roslisp-msg-protocol:md5sum ((type (cl:eql 'PointCloud)))
"Returns md5sum for a message object of type 'PointCloud"
"d8e9c3f5afbdd8a130fd1d2763945fca")
(cl:defmethod roslisp-msg-protocol:message-definition ((type (cl:eql '<PointCloud>)))
"Returns full string definition for message of type '<PointCloud>"
(cl:format cl:nil "# This message holds a collection of 3d points, plus optional additional~%# information about each point.~%~%# Time of sensor data acquisition, coordinate frame ID.~%Header header~%~%# Array of 3d points. Each Point32 should be interpreted as a 3d point~%# in the frame given in the header.~%geometry_msgs/Point32[] points~%~%# Each channel should have the same number of elements as points array,~%# and the data in each channel should correspond 1:1 with each point.~%# Channel names in common practice are listed in ChannelFloat32.msg.~%ChannelFloat32[] channels~%~%================================================================================~%MSG: std_msgs/Header~%# Standard metadata for higher-level stamped data types.~%# This is generally used to communicate timestamped data ~%# in a particular coordinate frame.~%# ~%# sequence ID: consecutively increasing ID ~%uint32 seq~%#Two-integer timestamp that is expressed as:~%# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')~%# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')~%# time-handling sugar is provided by the client library~%time stamp~%#Frame this data is associated with~%# 0: no frame~%# 1: global frame~%string frame_id~%~%================================================================================~%MSG: geometry_msgs/Point32~%# This contains the position of a point in free space(with 32 bits of precision).~%# It is recommeded to use Point wherever possible instead of Point32. ~%# ~%# This recommendation is to promote interoperability. ~%#~%# This message is designed to take up less space when sending~%# lots of points at once, as in the case of a PointCloud. ~%~%float32 x~%float32 y~%float32 z~%================================================================================~%MSG: sensor_msgs/ChannelFloat32~%# This message is used by the PointCloud message to hold optional data~%# associated with each point in the cloud. The length of the values~%# array should be the same as the length of the points array in the~%# PointCloud, and each value should be associated with the corresponding~%# point.~%~%# Channel names in existing practice include:~%# \"u\", \"v\" - row and column (respectively) in the left stereo image.~%# This is opposite to usual conventions but remains for~%# historical reasons. The newer PointCloud2 message has no~%# such problem.~%# \"rgb\" - For point clouds produced by color stereo cameras. uint8~%# (R,G,B) values packed into the least significant 24 bits,~%# in order.~%# \"intensity\" - laser or pixel intensity.~%# \"distance\"~%~%# The channel name should give semantics of the channel (e.g.~%# \"intensity\" instead of \"value\").~%string name~%~%# The values array should be 1-1 with the elements of the associated~%# PointCloud.~%float32[] values~%~%~%"))
(cl:defmethod roslisp-msg-protocol:message-definition ((type (cl:eql 'PointCloud)))
"Returns full string definition for message of type 'PointCloud"
(cl:format cl:nil "# This message holds a collection of 3d points, plus optional additional~%# information about each point.~%~%# Time of sensor data acquisition, coordinate frame ID.~%Header header~%~%# Array of 3d points. Each Point32 should be interpreted as a 3d point~%# in the frame given in the header.~%geometry_msgs/Point32[] points~%~%# Each channel should have the same number of elements as points array,~%# and the data in each channel should correspond 1:1 with each point.~%# Channel names in common practice are listed in ChannelFloat32.msg.~%ChannelFloat32[] channels~%~%================================================================================~%MSG: std_msgs/Header~%# Standard metadata for higher-level stamped data types.~%# This is generally used to communicate timestamped data ~%# in a particular coordinate frame.~%# ~%# sequence ID: consecutively increasing ID ~%uint32 seq~%#Two-integer timestamp that is expressed as:~%# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')~%# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')~%# time-handling sugar is provided by the client library~%time stamp~%#Frame this data is associated with~%# 0: no frame~%# 1: global frame~%string frame_id~%~%================================================================================~%MSG: geometry_msgs/Point32~%# This contains the position of a point in free space(with 32 bits of precision).~%# It is recommeded to use Point wherever possible instead of Point32. ~%# ~%# This recommendation is to promote interoperability. ~%#~%# This message is designed to take up less space when sending~%# lots of points at once, as in the case of a PointCloud. ~%~%float32 x~%float32 y~%float32 z~%================================================================================~%MSG: sensor_msgs/ChannelFloat32~%# This message is used by the PointCloud message to hold optional data~%# associated with each point in the cloud. The length of the values~%# array should be the same as the length of the points array in the~%# PointCloud, and each value should be associated with the corresponding~%# point.~%~%# Channel names in existing practice include:~%# \"u\", \"v\" - row and column (respectively) in the left stereo image.~%# This is opposite to usual conventions but remains for~%# historical reasons. The newer PointCloud2 message has no~%# such problem.~%# \"rgb\" - For point clouds produced by color stereo cameras. uint8~%# (R,G,B) values packed into the least significant 24 bits,~%# in order.~%# \"intensity\" - laser or pixel intensity.~%# \"distance\"~%~%# The channel name should give semantics of the channel (e.g.~%# \"intensity\" instead of \"value\").~%string name~%~%# The values array should be 1-1 with the elements of the associated~%# PointCloud.~%float32[] values~%~%~%"))
(cl:defmethod roslisp-msg-protocol:serialization-length ((msg <PointCloud>))
(cl:+ 0
(roslisp-msg-protocol:serialization-length (cl:slot-value msg 'header))
4 (cl:reduce #'cl:+ (cl:slot-value msg 'points) :key #'(cl:lambda (ele) (cl:declare (cl:ignorable ele)) (cl:+ (roslisp-msg-protocol:serialization-length ele))))
4 (cl:reduce #'cl:+ (cl:slot-value msg 'channels) :key #'(cl:lambda (ele) (cl:declare (cl:ignorable ele)) (cl:+ (roslisp-msg-protocol:serialization-length ele))))
))
(cl:defmethod roslisp-msg-protocol:ros-message-to-list ((msg <PointCloud>))
"Converts a ROS message object to a list"
(cl:list 'PointCloud
(cl:cons ':header (header msg))
(cl:cons ':points (points msg))
(cl:cons ':channels (channels msg))
))
|