VIPER ROS API

VIPER is based on ROS, therefore it has ROS API that is described by various input and output topics.

Note

All topics are provided without a namespace. When you are using your VIPER, please take its namespace into account.

VIPER architecture

_images/viper_ros_architecture.png

VIPER Core

The following topics are available on every VIPER.

Published Topics

left/image_raw (sensor_msgs/Image)
Left image of the camera. It comes in sensor_msgs::image_encodings::RGB8 format.
right/image_raw (sensor_msgs/Image)
Right image of the camera. It comes in sensor_msgs::image_encodings::RGB8 format.
image_raw (sensor_msgs/Image)
Image that contains both left and right images. It comes in sensor_msgs::image_encodings::RGB8 format.
left/camera_info (sensor_msgs/CameraInfo)
Camera calibration parameters for left camera.
right/camera_info (sensor_msgs/CameraInfo)
Camera calibration parameters for right camera.
left/image_rect (sensor_msgs/Image)
Left rectified image of the camera. It comes in sensor_msgs::image_encodings::RGB8 format.
right/image_rect (sensor_msgs/Image)
Right rectified image of the camera. It comes in sensor_msgs::image_encodings::RGB8 format.
stereo/image_rect (sensor_msgs/Image)
Image that contains both left and right rectified images. It comes in sensor_msgs::image_encodings::RGB8 format.
disparity (stereo_msgs/DisparityImage)
Disparity image is an image that contains a shift value for each pixel in the left rectified image with respect to the right rectified image of the same scene, while both images have been taken at the same time. Image data come in sensor_msgs::image_encodings::TYPE_32FC1 format.
points2 (sensor_msgs/PointCloud2)
Point cloud is a 3D data structure that contains x, y, z coordinates (in meters) for each pixel in left rectified image, and describes a 3D scene.
imu (sensor_msgs/Imu)
This is a message to hold data from an IMU (Inertial Measurement Unit).

Subscribed Topics

No external topics are required.

Services

No services are available for the user.

Provided tf Transforms

Internal VIPER transforms, that describe the geometry of our stereo camera.

_images/tf_diagram.png

cvm_ground_link link is used to describe the ground when it is different from VIPER’s center. When this link is configured and set as a target frame for the Obstacle Detector App, the application detects obstacles that are parallel to the ground.

Required tf Transforms

_images/tf_diagram2.png

Transform from a robot to the camera base is necessary when VIPER is used together with a robot. It is configurable via cvm_description dynamic parameters.

FollowMe App

FollowMe is a VIPER application that tracks bounding box of the given human between frames and provides distance to the target.

Published Topics

follow_me/status (std_msgs/String)

If subscribed to, FollowMe status will be published continually. The following are possible:

  • FollowMe is disabled;
  • Waiting for another target;
  • Tracking target;
  • Tracker lost the target: x s time out.
follow_me/bounding_boxes (cvm_msgs/BoundingBoxes)
Publishes bounding boxes of all humans visible in the current left rectified image left/image_rect, if FollowMe is enabled.
follow_me/target_bounding_box (cvm_msgs/BoundingBox)
If FollowMe is enabled and the target has been set, publishes current bounding box of the target being tracked.
follow_me/target_position (geometry_msgs/PointStamped)
If FollowMe is enabled and the target has been set, publishes position x, y, z (in meters) to the human being tracked with respect to the left camera optical frame.

Subscribed Topics

follow_me/enable (std_msgs/Bool)
If true is published to this topic, FollowMe will be enabled, otherwise it will be disabled.
follow_me/set_target (cvm_msgs/BoundingBox)
Bounding box selected from follow_me/bounding_boxes. If FollowMe is enabled, the app will start tracking the selected human.

FollowAruco App

FollowAruco is a VIPER application that tracks Aruco markers and provides distance to the target with a selected ID.

Published Topics

follow_aruco/status (std_msgs/String)

If subscribed to, FollowAruco status will be published continually. The following are possible:

  • FollowAruco is disabled;
  • Tracking marker nr. x.
follow_aruco/target_position (geometry_msgs/PointStamped)
If FollowAruco is enabled, publishes position x, y, z (in meters) to the marker being tracked with respect to the left camera optical frame.
follow_aruco/detection_image (sensor_msgs/Image)
If FollowAruco is enabled, publishes left rectified image with all detected Aruco markers. The target is marked by a red bounding box, others are marked by a green bounding box.

Subscribed Topics

follow_aruco/enable (std_msgs/Bool)
If true is published to this topic, FollowAruco will be enabled, otherwise it will be disabled.

Obstacle Detector App

Obstacle Detector is a VIPER application that imitates laser scan by processing point cloud produced by the camera. Output can be used as an input for a robot path planner.

Published Topics

laser_scan (sensor_msgs/LaserScan)
Single scan constructed from point cloud using given Obstacle Detector configuration.