A ROS driver for the Insta360 cameras. This driver is tested on Ubuntu 20.04 with ROS Noetic. The driver has also been verified on the Insta360 X2 and X3 cameras.
To use this driver, you need to first have Insta360 SDK. Please apply for the SDK from the Insta360 website.
cd ~/catkin_ws/src
git clone https://github.com/ai4ce/insta360_ros_driver
cd ..
Then, the Insta360 libraries need to be installed as follows:
- add the
camera
andstream
header files inside theinclude
directory - add the
libCameraSDK.so
library under thelib
directory.
Afterwards, install the other required dependencies and build
rosdep install --from-paths src --ignore-src -r -y
catkin build
Before continuing, make sure the camera is set to dual-lens mode
The Insta360 requires sudo privilege to be accessed via USB. To compensate for this, a udev configuration can be automatically created that will only request for sudo once. The camera can thus be setup initially via:
rosrun insta360_ros_driver setup.sh
This creates a symlink based on the vendor ID of Insta360 cameras. The symlink, in this case /dev/insta
is used to grant permissions to the usb port used by the camera.
This driver directly publishes the video feed in YUV format, since that is the camera's native setting. Alongside this, the driver also publishes the camera feed as standard BGR images to the /front_camera_image/compressed
and /back_camera_image/compressed
topics. Note that the compressed images have some amount of latency (~50 ms) compared to the raw output.
The camera can be brought up with the following launch file
roslaunch insta360_ros_driver bringup.launch
This publishes the raw yuv and compressed images as the following topics
- /insta_image_yuv
- /front_camera_image/compressed
- /back_camera_image/compressed
The launch file has the following optional arguments:
- compress (default="true")
Enables the /live_processing
which publishes the compressed front and back images. When set to false, only the raw YUV image is published
- undistort (default="false")
When set to true, the /live_processing
node will also use the specified intrinsic matrix, found in config/config.yaml
to undistort the images in real-time. Note that this process can reduce the frame rate and/or increase latency. It is therefore recommended to keep it as 'false' and perform undistortion in post-processing, as will be shown in the next section.
- debug (default="false")
When set to true, additional diagnostic windows are created. These show the publishing frequency and image size. Note that xterm is required for this functionality, and can be installed using the following command.
sudo apt-get install xterm
While the camera driver is active (via the bringup launch file above), data can be recorded to a bag file using
roslaunch insta360_ros_driver bag_record.launch
The bag file save locations are specified within config/config.yaml
The launch file contains one optional argument:
- bag_type (default="compressed", options="["raw", "compressed", "undistorted"])
This specifies which directory to save the bag_files to, as specified in config/config.yaml
When set to "raw", it will only record the /insta_image_yuv
topic. Note that when specifying the bag_type
to be "undistorted", undistort:=true
must be set for bringup.launch
The Raw YUV image appears as follows:
Given a bag file containing raw YUV image data, the images can be split to front and back and also compressed using the following launch file.
roslaunch insta360_ros_driver bag_compress.launch
This launch file reads all the bag files specified in the raw_bag_folder
within the config/config.yaml
file and outputs bag files containing split and compressed images into the compressed_bag_folder
directory. The compressed images are within the /front_camera_image/compressed
and /back_camera_image/compressed
topics.
After compression and splitting, the images appear as follows:
Given a bag file containing compressed front and back images, these images can be undistorted using the following launch file.
roslaunch insta360_ros_driver bag_undistort.launch
This launch file reads all the bag files specified in the compressed_bag_folder
within the config/config.yaml
file and outputs bag files undistorted images into the undistorted_bag_folder
directory. The images are undistorted using the intrinsics specified inside the config/config.yaml
file and are within the /front_camera_image/compressed
and /back_camera_image/compressed
topics.
After undistortion, the images appear as follows:
The compressed and undistorted bag files can be previewed using RViz via the following launch file.
roslaunch insta360_ros_driver bag_preview.launch
The launch file has the following argument:
- bag_file (default="~/bag/undistorted/record.bag")
This is the filepath of the bag file that will be previewed. Please make sure to change this accordingly.
When launched, an RViz window will be created showing both front and back images, as was previously demonstrated in earlier sections of the documentation