Only released in EOL distros:  

Package Summary

This package wraps Tango Ros Streamer application

  • Maintainer status: developed
  • Maintainer: Ruben Smits <ruben AT intermodalics DOT eu>, Perrine Aguiar <perrine AT intermodalics DOT eu>
  • Author:
  • License: Apache
  • Source: git https://github.com/Intermodalics/tango_ros.git (branch: master)

Package Summary

This package wraps Tango Ros Streamer application

  • Maintainer status: developed
  • Maintainer: Ruben Smits <ruben AT intermodalics DOT eu>, Perrine Aguiar <perrine AT intermodalics DOT eu>
  • Author:
  • License: Apache
  • Source: git https://github.com/Intermodalics/tango_ros.git (branch: master)

App summary

Tango ROS Streamer is an android application and ROS node for Tango-enabled devices. Its main purpose is to provide Tango sensor data to the ROS ecosystem in order to easily use the Tango functionalities on robots.

Installation

The app has been developed and tested with ROS indigo on Ubuntu 14.04, and kinetic on Ubuntu 16.04.

Tutorials

  1. Visualise Tango data in Rviz

    Step by step tutorial to visualise Tango data published by the TangoRosStreamer application in Rviz.

  2. Use Tango localization

    Tutorial showing how to use the different localization modes provided by TangoRosStreamer.

  3. Use the tango ROS node in your own app

    Tutorial to integrate the tango ROS node of TangoRosStreamer in your own app.

Create a new tutorial:

Known Usages

ROS API

tango

This node is the core of the application, it is responsible for streaming Tango data to ROS.

Published Topics

android/imu (sensor_msgs/Imu)
  • IMU message from the Android sensors.
tango/camera/color_1/camera_info (sensor_msgs/CameraInfo)
  • Camera info of the Tango device color camera.
tango/camera/color_1/image_raw (sensor_msgs/Image)
  • Image of the Tango device color camera.
tango/camera/color_1/image_rect (sensor_msgs/Image)
  • Rectified image of the Tango device color camera.
tango/camera/fisheye_1/camera_info (sensor_msgs/CameraInfo)
  • Camera info of the Tango device fisheye camera. The fisheye camera data is not available on devices with API level > 23. This topic is therefore not advertised for these devices.
tango/camera/fisheye_1/image_raw (sensor_msgs/Image)
  • Image of the Tango device fisheye camera. The fisheye camera data is not available on devices with API level > 23. This topic is therefore not advertised for these devices.
tango/camera/fisheye_1/image_rect (sensor_msgs/Image)
  • Rectified image of the Tango device fisheye camera. The fisheye camera data is not available on devices with API level > 23. This topic is therefore not advertised for these devices.
tango/laser_scan (sensor_msgs/LaserScan)
  • Laser scan message created from the Tango point cloud, expressed in laser frame.
tango/point_cloud (sensor_msgs/PointCloud2)
  • Point cloud of the Tango device depth sensor, expressed in camera_depth frame.
tango/reconstruction/mesh_marker (visualization_msgs/MarkerArray) tango/reconstruction/occupancy_grid (nav_msgs/OccupancyGrid) tango/static_occupancy_grid (nav_msgs/OccupancyGrid)
  • Static occupancy grid after loading it with the tango/load_occupancy_grid service.
tango/status (std_msgs/Int8)
  • Current status of the Tango service. 0: UNKNOWN, 1: SERVICE_NOT_CONNECTED, 2: NO_FIRST_VALID_POSE, 3: SERVICE_CONNECTED.
tango/transform/area_description_T_start_of_service (geometry_msgs/TransformStamped)
  • Current transform between area_description and start_of_service frames.
tango/transform/start_of_service_T_device (geometry_msgs/TransformStamped)
  • Current transform between start_of_service and device frames.

Services

tango/connect (tango_ros_messages/TangoConnect)
  • Doc here. Service to disconnect/connect to the Tango service. 0: DISCONNECT, 1: CONNECT, 2: RECONNECT (disconnect and connect cycle).
tango/get_map_name (tango_ros_messages/GetMapName)
  • Doc here. Get the name of a map given its uuid.
tango/get_map_uuids (tango_ros_messages/GetMapUuids)
  • Doc here. Get uuid and name lists of all maps available.
tango/load_occupancy_grid (tango_ros_messages/LoadOccupancyGrid)
  • Doc here. Load an occupancy grid from disk (path set via the tango/occupancy_grid_directory parameter) and publish it on the /tango/static_occupancy_grid topic. If the yaml file of the occupancy grid contains a uuid field and it is not empty, then the origin of the occupancy grid is expressed wrt the AREA_DESCRIPTION frame. Otherwise, its origin is expressed wrt the START_OF_SERVICE frame. Also, in the case where a localization map is loaded (/tango/localization_map_uuid parameter set before connecting to Tango) and its uuid corresponds to the uuid field of the occupancy grid yaml file, then the occupancy grid is aligned with the localization map.
tango/save_map (tango_ros_messages/SaveMap)
  • Doc here. Save the current localization map and/or the occupancy grid with the given name. 1: SAVE_LOCALIZATION_MAP, 2: SAVE_OCCUPANCY_GRID. The localization map saved is internal to Tango and can not be accessed directly. To be able to save it the /tango/create_new_map parameter needs to be true. The occupancy grid is saved to disk (path set via the tango/occupancy_grid_directory parameter) as a pair of files: a pgm file encoding the occupancy data and a yaml file describing the metadata. This is compatible with the existing ROS node map_server. If the occupancy grid is saved together with the localization map or while a localization map is already loaded (/tango/localization_map_uuid parameter was set before connecting to Tango), the origin of the occupancy grid is saved wrt the AREA_DESCRIPTION frame and the uuid of the localization map is saved in the occupancy grid yaml file. This way, the occupancy grid will be aligned with the localization map if loaded later. Otherwise, it is saved wrt the START_OF_SERVICE frame and the uuid field is left empty in the yaml file. In this case the occupancy grid will not be aligned with the localization map when loaded later.
tango/set_parameters (dynamic_reconfigure/Reconfigure)
  • Dynamic reconfigure service to change runtime parameters.

Parameters

tango/area_description_frame_id (string, default: area_description) tango/create_new_map (bool, default: false)
  • True to create a new map. If true, tango/localization_mode is not used.
tango/enable_3dr_mesh (bool, default: true)
  • True to enable extraction of mesh using the Tango 3D reconstruction API. To allow Tango 3D reconstruction, enable_color_camera and enable_depth also need to be true.
tango/enable_3dr_occupancy_grid (bool, default: true)
  • True to enable extraction of occupancy grid using the Tango 3D reconstruction API. To allow Tango 3D reconstruction, enable_color_camera and enable_depth also need to be true.
tango/enable_color_camera (bool, default: true)
  • True to enable color camera. If false, Tango will not connect to the color camera of the device, which can save battery, but topics that need color image will not be advertised (color camera, mesh, occupancy_grid). Also, note that this parameter has effect only for devices with Android API level > 23. For devices with lower API levels, the color camera is always enable.
tango/enable_depth (bool, default: true)
  • True to enable depth camera. If false, Tango will not connect to the depth camera of the device, which can save battery, but topics that need depth data will not be advertised (pointcloud, laser, mesh, occupancy_grid).
tango/laser_scan_max_height (double, default: 1)
  • Maximum height of the tango laser scan in meter
tango/laser_scan_min_height (double, default: -1)
  • Minimum height of the tango laser scan in meter
tango/localization_map_uuid (string, default: "")
  • Uuid of the map to use for localization. Used only if tango/localization_mode is set to 3.
tango/localization_mode (int, default: 2)
  • Localization method to use. 1: ODOMETRY (only VIO, no map required), 2: ONLINE_SLAM (VIO + drift correction, no map required), 3: LOCALIZATION (localization in map). To know more about the localization modes, read Use Tango localization.
tango/occupancy_grid_directory (string, default: /sdcard/tango_ros_streamer/occupancy_grids/)
  • Path to the directory where occupancy grids are saved/loaded.
tango/publish_pose_on_tf (bool, default: true)
  • True to publish transforms on /tf
tango/reconstruction/floorplan_max_error (double, default: 0.0)
  • Used by the Tango 3D reconstruction API. According to its documentation: "Upper bound on geometric error in meters during polygon simplification. Set to zero to disable simplification.".
tango/reconstruction/max_voxel_weight (int, default: 16383)
  • Used by the Tango 3D reconstruction API. According to its documentation: "The maximum voxel weight for the integration filter. Defaults to 16383. Roughly corresponds to the number of observations. A higher value gives better geometric quality and stability; a lower value gives more responsiveness to dynamic objects.".
tango/reconstruction/min_num_vertices (int, default: 1)
  • Used by the Tango 3D reconstruction API. According to its documentation: "Minimum number of vertices that every connected component in the mesh should consist of. Defaults to 1. Smaller components (typically noise) will be deleted.".
tango/reconstruction/occupancy_grid_threshold (int, default: 180)
  • Threshold to decide if a pixel value should correspond to a free or occupied cell when converting the image of Tango 3D reconstruction to an occupancy grid. Should be between 0 and 255: pixel value <= threshold --> cell is free, pixel value > threshold --> cell is occupied.
tango/reconstruction/resolution_3d (double, default: 0.05) tango/reconstruction/update_method (int, default: 0) tango/reconstruction/use_space_clearing (bool, default: false)
  • Used by the Tango 3D reconstruction API. According to its documentation: "When true, will clear away free space along the depth observations. Default is false. If enabled, 3D reconstruction will create higher quality meshes at a cost to performance.".
tango/start_of_service_frame_id (string, default: start_of_service) tango/use_tf_static (bool, default: true)
  • True to use /tf_static latched static transform broadcaster. If set to false static transforms are published on the /tf topic.
tango/android_api_level (int, default: 0)
  • API level of the Tango device running the node. It should be set only if the node is running on an Android device. In this case it should be set by the Android application running the node, before connecting to the Tango service.

Provided tf Transforms

area_descriptionstart_of_service
  • Transform between area_description and start_of_service frames. This transform is available only if tango/localization_mode is set to 2 or 3. Tango is updating this transform quite slowly (~10 Hz), which can cause some applications that need high rate for odometry (e.g. navigation) to not work properly. As a workaround, this transform is published as a static transform even though it changes over time.
start_of_servicedevice
  • Transform between start of service frame (first device pose after starting the Tango service) and current device frame.
devicecamera_depth
  • Depth camera pose expressed in the device frame (static transform)
camera_depthlaser
  • Laser pose expressed in the depth camera frame (static transform)
devicecamera_fisheye
  • Fisheye camera pose expressed in the device frame (static transform)
devicecamera_color
  • Color camera pose expressed in the device frame (static transform)
deviceimu
  • IMU pose expressed in the device frame (static transform)

Note that all image topics are published via image_transport. Therefore, for each image topic, a compressed version of the image is available together with its compression parameters.

Also note that the service tango/connect seems to not work properly on Tango Tablet Development Kit.

Report a bug

Use GitHub to report bugs or submit feature requests. [View active issues]

Wiki: tango_ros_streamer (last edited 2017-12-08 09:29:36 by PerrineAguiar)