Simple Tutorial
Contents
This guide assumes that you have already built the project successfully and are now ready to run the program on some datasets. If you have not compiled the program yet please follow the Installation Guide (ROS1 and ROS2) guide. The first that we will download is a dataset to run the program on. In this tutorial we will run on the EuRoC MAV Dataset [4] which provides monochrome stereo images at 20Hz with a MEMS ADIS16448 IMU at 200Hz.
All configuration information for the system is exposed to the user in the configuration file, and can be overridden in the launch file. We will create a launch file that will launch our MSCKF estimation node and feed the ROS bag into the system. One can take a look in the launch folder for more examples. For OpenVINS we need to define a series of files:
estimator_config.yaml
- Contains OpenVINS specific configuration files. Each of these can be overridden in the launch file.kalibr_imu_chain.yaml
- IMU noise parameters and topic information based on the sensor in the dataset. This should be the same as Kalibr's (see IMU Noise Calibration (Offline)).kalibr_imucam_chain.yaml
- Camera to IMU transformation and camera intrinsics. This should be the same as Kalibr's (see Camera Intrinsic Calibration (Offline)).
ROS 1 Tutorial
The ROS1 system uses the roslaunch system to manage and launch nodes. These files can launch multiple nodes, and each node can their own set of parameters set. Consider the below launch file. We can see the main parameter that is being passed into the estimator is the config_path
file which has all configuration for this specific dataset. Additionally, we can see that we are launching the run_subscribe_msckf
ROS 1 node, and are going to be overriding the use_stereo
and max_cameras
with the specificed values. ROS parameters always have priority, and you should see in the console that they have been successfully overridden.
<launch> <!-- what config we are going to run (should match folder name) --> <arg name="verbosity" default="INFO" /> <!-- ALL, DEBUG, INFO, WARNING, ERROR, SILENT --> <arg name="config" default="euroc_mav" /> <!-- euroc_mav, tum_vi, rpng_aruco --> <arg name="config_path" default="$(find ov_msckf)/../config/$(arg config)/estimator_config.yaml" /> <!-- MASTER NODE! --> <node name="run_subscribe_msckf" pkg="ov_msckf" type="run_subscribe_msckf" output="screen"> <param name="verbosity" type="string" value="$(arg verbosity)" /> <param name="config_path" type="string" value="$(arg config_path)" /> <param name="use_stereo" type="bool" value="true" /> <param name="max_cameras" type="int" value="2" /> </node> </launch>
Since the configuration file for the EurocMav dataset has already been created, we can simply do the following. Note it is good practice to run a roscore
that stays active so that you do not need to relaunch rviz or other packages.
roscore # term 0 source devel/setup.bash # term 1 roslaunch ov_msckf subscribe.launch config:=euroc_mav
In another two terminals we can run the following. For RVIZ, one can open the ov_msckf/launch/display.rviz
configuration file. You should see the system publishing features and a state estimate.
rviz -d ov_msckf/launch/display.rviz # term 2 rosbag play V1_01_easy.bag # term 3
ROS 2 Tutorial
For ROS 2, launch files and nodes have become a bit more combersom due to the removal of a centralized communication method. This both allows for more distributed systems, but causes a bit more on the developer to perform integration. The launch system is described in this design article. Consider the following launch file which does the same as the ROS 1 launch file above.
from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, LogInfo, OpaqueFunction from launch.conditions import IfCondition from launch.substitutions import LaunchConfiguration, TextSubstitution from launch_ros.actions import Node from ament_index_python.packages import get_package_share_directory, get_package_prefix import os import sys launch_args = [ DeclareLaunchArgument(name='namespace', default_value='', description='namespace'), DeclareLaunchArgument(name='config', default_value='euroc_mav', description='euroc_mav, tum_vi, rpng_aruco...'), DeclareLaunchArgument(name='verbosity', default_value='INFO', description='ALL, DEBUG, INFO, WARNING, ERROR, SILENT'), DeclareLaunchArgument(name='use_stereo', default_value='true', description=''), DeclareLaunchArgument(name='max_cameras', default_value='2', description='') ] def launch_setup(context): configs_dir=os.path.join(get_package_share_directory('ov_msckf'),'config') available_configs = os.listdir(configs_dir) config = LaunchConfiguration('config').perform(context) if not config in available_configs: return[LogInfo(msg='ERROR: unknown config: \'{}\' - Available configs are: {} - not starting OpenVINS'.format(config,', '.join(available_configs)))] config_path = os.path.join(get_package_share_directory('ov_msckf'),'config',config,'estimator_config.yaml') node1 = Node(package = 'ov_msckf', executable = 'run_subscribe_msckf', namespace = LaunchConfiguration('namespace'), parameters =[{'verbosity': LaunchConfiguration('verbosity')}, {'use_stereo': LaunchConfiguration('use_stereo')}, {'max_cameras': LaunchConfiguration('max_cameras')}, {'config_path': config_path}]) return [node1] def generate_launch_description(): opfunc = OpaqueFunction(function = launch_setup) ld = LaunchDescription(launch_args) ld.add_action(opfunc) return ld
We can see that first the launch_setup
function defines the nodes that we will be launching from this file. Then the LaunchDescription
is created given the launch arguments and the node is added to it and returned to ROS. We can the launch it using the following:
source install/setup.bash ros2 launch ov_msckf subscribe.launch.py config:=euroc_mav
We can then use the ROS2 rosbag file. First make sure you have installed the rosbag2 and all its backends. If you downloaded the bag above you should already have a valid bag format. Otherwise, you will need to convert it following ROS1 to ROS2 Bag Conversion Guide . A "bag" is now defined by a db3 sqlite database and config yaml file in a folder. In another terminal we can run the following:
ros2 bag play V1_01_easy