exact-time-message-filter-callback-helper

  • :super propertied-object
  • :slots deligate topic

:init

   topic-info &key deligate-object

  • topic-info := (topic message-type)
    deligate-object := exact-time-message-filter

:callback

   msg

  • just call :add-message method of deligate object

exact-time-message-filter

  • :super propertied-object
  • :slots callback-helpers buffers buffer-length

Exact time message filter synchronizes incoming channels by the timestamps contained in their headers, and outputs them in the form of a single callback that takes the same number of channels. This filter requres messages to have exactly the same timestamp in order to match. Your callback is only called if a message has been received on all specified channels with the same exact timestamp.

topic := ((topic message-type) (topic message-type) ...)

    ;; sample
    (defclass image-caminfo-synchronizer
      :super exact-time-message-filter)

    (defmethod image-caminfo-synchronizer
      (:callback (image caminfo)
        (print (list image caminfo))
        (print (send-all (list image caminfo) :header :stamp))
        ))
    (ros::roseus "hoge")
    (ros::roseus-add-msgs "sensor_msgs")
    ;; test
    (setq hoge (instance image-caminfo-synchronizer :init
             (list (list "/multisense/left/image_rect_color" sensor_msgs::Image)
               (list "/multisense/left/camera_info" sensor_msgs::CameraInfo))))
    (ros::spin)

:init

   topics &key ((:buffer-length abuffer-length) 50)

  • Create exact-time-message-filter instance

:add-message

   topic-name message

  • add message to buffer and call callback if possible

:call-callback-if-possible

   stamp

  • call synchronized callback if messages can be found
    with the same timestamp

make-camera-from-ros-camera-info

   msg

  • Make camera model from ros sensor_msgs::CameraInfo message

make-msg-from-3dpointcloud

   points-list &key color-list
   (frame /sensor_frame)

  • Make sensor_msgs::PointCloud from list of 3d point

vector->rgba

   cv &optional (alpha 1.0)

  • Convert vector to std_msgs::ColorRGBA

cylinder->marker-msg

   cyl header &key ((:color col) (float-vector 1.0 0 0))
   ((:alpha a) 1.0)
   ((:id idx) 0)
   ns
   lifetime

  • Convert cylinder object to visualization_msgs::Marker

cube->marker-msg

   cb header &key ((:color col) (float-vector 1.0 0 0))
   ((:alpha a) 1.0)
   ((:id idx) 0)
   ns
   lifetime

  • Convert cube object to visualization_msgs::Marker

sphere->marker-msg

   sp header &key ((:color col) (float-vector 1.0 0 0))
   ((:alpha a) 1.0)
   ((:id idx) 0)
   ns
   lifetime

  • Convert shpere object to visualization_msgs::Marker

line->marker-msg

   li header &key ((:color col) (float-vector 1 0 0))
   ((:alpha a) 1.0)
   ((:id idx) 0)
   ((:scale sc) 10.0)
   ns
   lifetime

  • Convert line object to visualization_msgs::Marker

line-list->marker-msg

   li header &key ((:color col) (float-vector 1 0 0))
   ((:alpha a) 1.0)
   ((:id idx) 0)
   ((:scale sc) 10.0)
   ns
   lifetime

  • Convert list of line object to visualization_msgs::Marker

faces->marker-msg

   faces header &key ((:color col) (float-vector 1 0 0))
   ((:id idx) 0)
   ns
   lifetime

  • Convert face objects to visualization_msgs::Marker

object->marker-msg

   obj header &key coords
   ((:color col) (float-vector 1 1 1))
   ((:alpha a) 1.0)
   ((:id idx) 0)
   ns
   lifetime
   rainbow

  • Convert euslisp body object to visualization_msgs::Marker

wireframe->marker-msg

   wf header &rest args

  • Convert euslisp object to visualization_msgs::Marker as wireframe

text->marker-msg

   str c header &key ((:color col) (float-vector 1 1 1))
   ((:alpha a) 1.0)
   ((:id idx) 0)
   ((:scale sc) 100.0)
   ns
   lifetime

  • Convert text to visualization_msgs::Marker

coords->marker-msg

   coords header &key (size 100)
   (width 10)
   (id 0)
   ns
   lifetime

  • Convert coordinates to visualization_msgs::Marker

mesh->marker-msg

   cds mesh_resource header &key ((:color col) (float-vector 1 1 1))
   ((:scale sc) 1000)
   ((:id idx) 0)
   ((:mesh_use_embedded_materials use_embedded) t)
   (alpha 1.0)
   ns
   lifetime

  • Convert mesh resources to visualization_msgs::Marker

pointcloud->marker-msg

   pc header &key ((:color col) (float-vector 1.0 0 0))
   ((:alpha a) 1.0)
   (use-color)
   (point-width 0.01)
   (point-height 0.01)
   ((:id idx) 0)
   ns
   lifetime

  • Convert pointcloud data to visualization_msgs::Marker

eusobj->marker-msg

   eusgeom header &rest args &key (wireframe)
   &allow-other-keys

  • Convert any euslisp object to visualization_msgs::Marker

arrow->marker-msg

   arg header &key ((:color col) (float-vector 1.0 0 0))
   ((:alpha a) 1.0)
   ((:id idx) 0)
   ((:scale sc) nil)
   ns
   lifetime

  • Convert arrow object to visualization_msgs::Marker

marker-msg->shape

   msg &rest args

  • Convert visualization_msgs::Marker to euslisp object

marker-msg->shape/cube

   msg

  • Convert visualization_msgs::Marker to euslisp cube object

marker-msg->shape/cylinder

   msg

  • Convert visualization_msgs::Marker to euslisp cylinder object

marker-msg->shape/sphere

   msg

  • Convert visualization_msgs::Marker to euslisp sphere object

marker-msg->shape/cube_list

   msg &key ((:pointcloud pt))

  • Convert visualization_msgs::Marker to eusliss list of cube objects

make-ros-msg-from-eus-pointcloud

   pcloud &key (with-color :rgb)
   (with-normal t)
   (frame /sensor_frame)

  • Convert from pointcloud in eus to sensor_msgs::PointCloud2 in ros

make-eus-pointcloud-from-ros-msg

   msg &key (pcloud)
   (remove-nan)

  • Convert from sensor_msgs::PointCloud2 in ros to pointcloud in eus

dump-pointcloud-to-pcd-file

   fname pcloud &key (rgb :rgb)
   (binary)
   (scale 0.001)

  • Write pointcloud data to pcd file

read-pcd-file

   fname &key (scale 1000.0)

  • Write read pcd file and construct pointcloud object

call-empty-service

   srvname &key (wait nil)

  • Call empty service

one-shot-subscribe

   topic-name mclass &key (timeout)
   (after-stamp)
   (unsubscribe t)

  • Subscribe message, just for once

one-shot-publish

   topic-name msg &key (wait 500)
   (after-stamp)
   (unadvertise t)

  • Publish message just for once

ros::set-dynamic-reconfigure-param

   srv name type value

  • set dynamic_reconfugre parameter.

print-ros-msg msg &optional (rp (find-package ROS)) (ro ros::object) (nest 0) (padding )

make-camera-from-ros-camera-info-aux pwidth pheight p frame-coords &rest args

make-eus-pointcloud-from-ros-msg1 sensor_msgs_pointcloud

read-header-symbol str sym