Trifo Ironsides

The Trifo Ironsides (Visual Inertial Computing Module) has two global shutter image sensors with fixed-focal fisheye lenses (133 degree horizontal field-of-view) capturing 640x480 resolution color images at 60 fps, and an InvenSense IMU reporting inertial measurements at 200 fps. The Trifo Ironsides comes with the PerceptIn Robotics Vision System (PIRVS) SDK providing the proprietary algorithm of odometry and mapping for various robotics and vision applications.

  • https://static.wixstatic.com/media/5c9d59_7ec390699c604224a1e9fd7129335125~mv2.jpg?dn=imgserver.jpg

Getting started

Get the PIRVS SDK and ROS package

  • You can request the PIRVS SDK from Trifo

  • You can download the PIRVS ROS package on Github: Ironsides Github

PIRVS ROS package supports Ubuntu 16.04 x64 running ROS Kinetic.

  • Install ROS (Kinetic)Install ROS

  • Create a ROS workspace
     $ mkdir -p ~/catkin_ws/src
     $ cd ~/catkin_ws/
     $ catkin_make
     $ source ~/catkin_ws/devel/setup.bash
  • Import and make our code
    • Place pirvs_ros folder in ~/catkin_ws/src
    • Run the pirvs_ros_init.py script to import the PIRVS SDK to the ROS workspace
       $ cd ~/catkin_ws/src/pirvs_ros/init
       $ python pirvs_ros_init.py [PIRVS SDK folder] [calib_raw JSON] [calib_rectified JSON]
    • make
       $ cd ~/catkin_ws
       $ catkin_make

Published topics

Stereo_camera_node

  • /pirvs_cam_raw/StereoImage/left

    • Left camera raw image (8bit, BGR)
  • /pirvs_cam_raw/StereoImage/left/cameraInfo

    • Left camera calibration data
  • /pirvs_cam_raw/StereoImage/right

    • Right camera raw image (8bit, BGR)
  • /pirvs_cam_raw/StereoImage/right/cameraInfo

    • Right camera calibration data
  • /pirvs_cam_raw/IMU/data_raw

    • IMU raw data

Depth_camera_node

  • /pirvs_cam_depth/StereoImage/rect_left

    • Left camera rectified image (Grayscale)
  • /pirvs_cam_depth/StereoImage/rect_right

    • Right camera rectified image (Grayscale)
  • /pirvs_cam_depth/StereoImage/depth

    • Depth map image registered on left image (16bits, in millimeters)
  • /pirvs_cam_depth/IMU/data_raw

    • IMU raw data

Slam_node

  • /pirvs_slam/StereoImage/left

    • Left camera raw image (Grayscale)
  • /pirvs_slam/StereoImage/right

    • Right camera raw image (Grayscale)
  • /pirvs_slam/Pose

    • Camera pose
  • /pirvs_slam/PointCloud

    • 3D Map points
  • /pirvs_slam/odom

    • 3D position and orientation relative to init_frame

Run the package

Before runing the PIRVS ROS package, make sure the Ironsides is connected to your computer though USB3.0 port and is set to the desired mode.

Roslaunch

The ROS launch files can be found in "/pirvs_ros/launch"

  • Raw sensor : "raw_camera.launch" shows the live stream of the stereo camera. The images are in BGR8 format.

      # Switch Ironsides to raw_mode
      $ roslaunch pirvs_ros raw_camera.launch
  • The windows below should pop up.
    • https://static.wixstatic.com/media/5c9d59_df3e1c3fc44c4151a93291b33e505dfa~mv2.jpg?dn=raw.jpg

  • Depth : "depth_camera.launch" shows the rectified images from both sensors

      # Switch Ironsides to depth_mode
      $ roslaunch pirvs_ros depth_camera.launch
  • The windows below should pop up.
    • https://static.wixstatic.com/media/5c9d59_adf9841485e5466f83bfb4a7fb4c398e~mv2.jpg?dn=rect.jpg

  • SLAM : "slam.launch" publishes the real-time 6-dof position tracking of the Ironsides device. To run SLAM with RVIZ visualization, use "display.launch".

      # Switch Ironsides to raw_mode
      $ roslaunch pirvs_ros display.launch
    • The pose of the Ironsides device and the 3d points are shown in RVIZ.
      • https://static.wixstatic.com/media/5c9d59_8bb7fa542c3447d1814edb85174e2d8b~mv2.gif?dn=slam.gif

Run Nodes

You can use the following command to run each node. It will only publish topics without display.

  • stereo_camera_node
     # Switch Ironsides to raw_mode
     $ rosrun pirvs_ros stereo_camera_node [cam_calib_left YAML] [cam_calib_left YAML]
  • depth_camera_node
     # Switch Ironsides to depth_mode
     $ rosrun pirvs_ros depth_camera_node
  • slam_node:
     # Switch Ironsides to raw_mode
     $ rosrun pirvs_ros slam_node [calib.json] [vocab.json]

Report an issue

GitHub Issue

Wiki: trifo (last edited 2018-09-28 18:21:17 by wli009)