VOXL Open-VINS server
The voxl-open-vins-server
service is used for multi-camera visual inertial odometry (VIO) and tracking. The process generates VIO data that is then pased over to the autopilot to be used as odometry data.
This documentaion will assume that there are some steps that have already be taken. The assumptions are:
- extrinsics file is already create and camera quaternions are believed to be correct.
- Assuming that we are working with between two and three camera tracking.
- Using Voxl SDK 1.4.0 on a VOXL 2
- All Tracking cameras are showing correct video feed in voxl-portal
Table of contents
Forwarnings for New Installs
If you are working on a non-development drone please be sure to backup important configuration files and intrinsics. Be sure to collect and store the contents of the following directories on the VOXL2:
/etc/modalai
/data/modalai
SDK >= 1.3.1
- on VOXL2, edit
/etc/apt/sources.list.d/modalai.list
, change to thedev
repo - run
apt update && apt upgrade
- edit
/data/modalai/sku.txt
and add a-E1
suffix to the string. save the file, e.g. MRB-D0005-4-V3-C12-E1 - Run
voxl-configure-mpa
and accept ‘Y’ to start the update
Installation will take about 2-3 minutes.
1. Disable qvio server so that there are not two VIO sources.
voxl-configure-qvio disable
2. Next navigate to `/etc/modalai/` directory.
3. Open and edit the `voxl-open-vins-server.conf` file.
4. If you are running VOXL SDK 1.4.0 then you will need to set `"en_ext_feature_tracker": false,`
5. Save and close the file.
6. Restart the service, via the VOXL 2 terminal, using the command `systemctl restart voxl-open-vins-server`.
# TroubleShooting
1. I don't have a `voxl-open-vins-server.conf`:
You will need to run the following command to generate and configure voxl-open-vins-server:
```
voxl-configure-open-vins <your camera configuration>
```
For example `voxl-configure-open-vins tracking_fd` will configure OpenVINS for a two camera tracking setup for front and down tracking cameras. The config file for voxl-open-vins-server will be created in the `/etc/modalai/` directory.
## Config Files
There are three main files that need to be properly configured for `voxl-open-vins-server` to function correctly:
- extrinsics.conf
- vio_cams.conf
- voxl-open-vins-server.conf
`voxl-open-vins-server.conf` is the main file that we will be looking at and editing to get stable flight. The `vio_cams.conf` file designates what tracking camera pipes to collect the video feed from, applying tracking to only the pipes listed. Lastly, `The extrinsic.conf` file should already be configured with the correct quaternions.
### extrinsics.conf
Understanding or learning how to create the extrinsic's file please read the extrinsics page [here](/configure-extrinsics/).
### VIO_cam.conf
The file should looke something like this:
{ “cams”: [{ “enable”: true, “name”: “tracking_front”, “pipe_for_preview”: “tracking_front”, “pipe_for_tracking”: “tracking_front”, “is_occluded_on_ground”: false, “imu”: “imu_apps”, “cal_file”: “opencv_tracking_front_intrinsics.yml” },{ “enable”: true, “name”: “tracking_down”, “pipe_for_preview”: “tracking_down”, “pipe_for_tracking”: “tracking_down”, “is_occluded_on_ground”: true, “imu”: “imu_apps”, “cal_file”: “opencv_tracking_down_intrinsics.yml” },{ “enable”: false, “name”: “tracking_rear”, “pipe_for_preview”: “tracking_rear”, “pipe_for_tracking”: “tracking_rear”, “is_occluded_on_ground”: false, “imu”: “imu_apps”, “cal_file”: “opencv_tracking_rear_intrinsics.yml” }] } ``` The above config is setup for a two camera tracking system. If we wanted to change to a triple camera tracking system then we would set the "enable": true,
for the last cam in the list.
Another thing that we may want to change is the "pipe_for_tracking": "tracking_front"
, we can use the basic tracking camera feed. However, if we want to use a different pipe then we can change to the parameter to "tracking_front_misp_norm"
or "tracking _front_misp_grey"
. This change depends on what camera feed shows the best results for your application.
Lastly, the parameter "is_occluded_on_ground"
this parameter designates if the tracking camera is covered while landed this could be the ground or a wall. Open-vins will not use this camera untill the drone is high enough to consider the camera unobscured.
voxl-open-vins-server.conf
Voxl-open-vins-server has a large Number of parameters that are pretty well documented in the header of the voxl-open-vins-server.conf
file. Here is a short list of parameters that could be changed and the resutls of changing them.
"en_auto_reset"
: Allowed OpenVINS to restart when OpenVINS algorithm detects a divergence or low feature count.
When you want a bit more stability in a feature rich environment you could increase the "max_slam_features"
, "max_slam_in_update"
, and "max_msckf_in_update"
.
"max_slam_features"
: The maximum number of estimated feature that can be generated in the frame."max_slam_in_update"
: Number of feature points that each camera can generate (totalmax_slam_features
)."max_msckf_in_update"
: Max number of feature points that OpenVINS will be using and sending out for VIO data.
When you have equipment that is in the way of the tracking cameras this can be used to let OpenVINS know that you want to mask the images.
"use_mask"
(Mask the images so that features are not picked up in masked areas)
If you are not using the AR0144 camera for tracking and instead are using the OV7251 tracking cameras there are two things to note. First is that only 2 camera tracking is available to the ov7251 and the parameter Histogram_method will need to be changed.
"histogram_method"
(Depending on what cameras you are using this will change. AR0144 set to 1, OV7251 set to 2)
Drones that need a differentcamera to be the takeoff camera than the defualt will want to change the parameter for "takeoff_cam"
.
"takeoff_cam"
: Tells OpenVINS which camera to use for takeoff, this should be a camera where"is_occluded_on_ground"
is false. This number corresponds with the camera_ID in voxl-camera-server.conf."takeoff_threshold"
(This parameter designates the height to start tracking features on the other none takeoff cameras)"en_force_init"
(Forces initalization of OpenVINS useful for situations when teh drone is not on stable ground)"en_force_ned_2_flu"
(Changes the orientation system from NED to FLU)"en_vio_always_on"
(This is set to true when hand testing and false when flight testing. This should not be set to true while flight testing)"en_ext_feature_tracker"
( Specific to VOXL SDK<=1.4.0, tells OpenVINS to us the internal tracking over external)
Testing
Hand Testing
This is the starting point that we want to work with to make sure that the extrinsics are configured correctly. Here are the steps that you will need to go through to get started hand testing. If you are working from a fresh SDK flash then you can skip ahead to the actual hand testing steps.
Software Steps:
- ADB shell or SSH into the VOXL 2
- Navigate to the
/etc/modalai
directory. - Open and edit
voxl-open-vins-server.conf
file. - In the
voxl-open-vins-server.conf
file, edit the parameteren_vio_always_on : true
. - Save and close the file.
- Restart the service, via the VOXL 2 terminal, using the command
systemctl restart voxl-open-vins-server
.
Hand Testing Steps:
- Open voxl-portal and navigate to the VIO tab.
- Select the ov_extended (Uses the voxl’s orientation) or vvhub_wrt_local (Uses Drone Body frame for orientaion).
- Now begin lifting up the drone and you should see it move in the VIO tab.
- Now to make sure tracking is working properly, roll, pitch, yaw the drone to make sure the odometry data is replicating what you are doing.
- Now move the drone around in the 3-dimmensional space making sure that the distance readings are accurate as well.
There are two other alternatives to the VIO tab. The ov_overlay locaked in the cameras tab > ov_overlay or using voxl-inspect-pose -l
in the VOXL 2 terminal. Additionally for Orientaion, you can use QGC as see below to ensure that pitch, roll, and yaw are correct.
- Lastly, check to make sure that in QGC, the drone is “Ready to Fly” in Position mode.
- If everything looks correct then you should be good to move into flight testing. If not then try double checking your
extrinsics.conf
file is correct. Alternatively you can do one camera tracking but changing the vio_cam.conf file and seeing if the extrinsics is correct for that single camera.
Flight testing
You should make sure that hand testing is done before flying the Drone to avoid fly-aways due to bad extrinsics or incorrect parameters.
- ADB shell or SSH into the VOXL 2
- Navigate to the
/etc/modalai
directory. - Open and edit
voxl-open-vins-server.conf
file. - In the
voxl-open-vins-server.conf
file, edit the parameteren_vio_always_on : false
. (Very important that when flying this parameter is set to false otherwise small flight vibrations on the IMU will cause a fly-away) - Save and close the file.
- Restart the service, via the VOXL 2 terminal, using the command
systemctl restart voxl-open-vins-server
. - Open QGC and connect to the VOXL 2.
- QGC should give the message “Ready to Fly”.
- Make sure the Drone is in Position Flight mode and start flying.
- Make sure to go through a few test like roll, pitch, yaw, and hover is one place for a few seconds to make sure tracking is not lost.
- At this point you should be good to continue flying with OpenVINS.