# Basalt VIO Node

BasaltVIO host node is used for host-side stereo-inertial visual odometry. It takes synchronized left and right camera frames
together with IMU data, and outputs estimated motion as
[TransformData](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/transform_data.md) plus a passthrough
[ImgFrame](https://docs.luxonis.com/software-v3/depthai/depthai-components/messages/img_frame.md) stream.

## How to place it

#### Python

```python
with dai.Pipeline() as pipeline:
    vio = pipeline.create(dai.node.BasaltVIO)
```

#### C++

```cpp
dai::Pipeline pipeline;
auto vio = pipeline.create<dai::node::BasaltVIO>();
```

## Inputs and Outputs

## Usage

#### Python

```python
with dai.Pipeline() as pipeline:
    left = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_B, sensorFps=60)
    right = pipeline.create(dai.node.Camera).build(dai.CameraBoardSocket.CAM_C, sensorFps=60)
    imu = pipeline.create(dai.node.IMU)
    vio = pipeline.create(dai.node.BasaltVIO)

    imu.enableIMUSensor(
        [dai.IMUSensor.ACCELEROMETER_RAW, dai.IMUSensor.GYROSCOPE_RAW],
        200,
    )
    imu.setBatchReportThreshold(1)
    imu.setMaxBatchReports(10)

    left.requestOutput((640, 400)).link(vio.left)
    right.requestOutput((640, 400)).link(vio.right)
    imu.out.link(vio.imu)

    transformQueue = vio.transform.createOutputQueue()
    passthroughQueue = vio.passthrough.createOutputQueue()
```

#### C++

```cpp
dai::Pipeline pipeline;
auto left = pipeline.create<dai::node::Camera>()->build(dai::CameraBoardSocket::CAM_B, std::nullopt, 60);
auto right = pipeline.create<dai::node::Camera>()->build(dai::CameraBoardSocket::CAM_C, std::nullopt, 60);
auto imu = pipeline.create<dai::node::IMU>();
auto vio = pipeline.create<dai::node::BasaltVIO>();

imu->enableIMUSensor({dai::IMUSensor::ACCELEROMETER_RAW, dai::IMUSensor::GYROSCOPE_RAW}, 200);
imu->setBatchReportThreshold(1);
imu->setMaxBatchReports(10);

left->requestOutput(std::make_pair(640, 400))->link(vio->left);
right->requestOutput(std::make_pair(640, 400))->link(vio->right);
imu->out.link(vio->imu);

auto transformQueue = vio->transform.createOutputQueue();
auto passthroughQueue = vio->passthrough.createOutputQueue();
```

## Examples of functionality

 * [Basalt VIO](https://docs.luxonis.com/software-v3/depthai/examples/rvc2/vslam/basalt_vio.md)
 * [Basalt VIO RTAB-Map SLAM](https://docs.luxonis.com/software-v3/depthai/examples/rvc2/vslam/basalt_vio_rtab.md)

## Reference

### dai::node::BasaltVIO

Kind: class

Basalt Visual Inertial Odometry node. Performs VIO on stereo images and IMU data.

#### dai::node::BasaltVIO::VioConfig

Kind: struct

##### std::string optical_flow_type

Kind: variable

##### int optical_flow_detection_grid_size

Kind: variable

##### int optical_flow_detection_num_points_cell

Kind: variable

##### int optical_flow_detection_min_threshold

Kind: variable

##### int optical_flow_detection_max_threshold

Kind: variable

##### bool optical_flow_detection_nonoverlap

Kind: variable

##### float optical_flow_max_recovered_dist2

Kind: variable

##### int optical_flow_pattern

Kind: variable

##### int optical_flow_max_iterations

Kind: variable

##### int optical_flow_levels

Kind: variable

##### float optical_flow_epipolar_error

Kind: variable

##### int optical_flow_skip_frames

Kind: variable

##### MatchingGuessType optical_flow_matching_guess_type

Kind: variable

##### float optical_flow_matching_default_depth

Kind: variable

##### float optical_flow_image_safe_radius

Kind: variable

##### bool optical_flow_recall_enable

Kind: variable

##### bool optical_flow_recall_all_cams

Kind: variable

##### bool optical_flow_recall_num_points_cell

Kind: variable

##### bool optical_flow_recall_over_tracking

Kind: variable

##### bool optical_flow_recall_update_patch_viewpoint

Kind: variable

##### float optical_flow_recall_max_patch_dist

Kind: variable

##### std::vector< float > optical_flow_recall_max_patch_norms

Kind: variable

##### LinearizationType vio_linearization_type

Kind: variable

##### bool vio_sqrt_marg

Kind: variable

##### int vio_max_states

Kind: variable

##### int vio_max_kfs

Kind: variable

##### int vio_min_frames_after_kf

Kind: variable

##### float vio_new_kf_keypoints_thresh

Kind: variable

##### bool vio_debug

Kind: variable

##### bool vio_extended_logging

Kind: variable

##### int vio_max_iterations

Kind: variable

##### double vio_obs_std_dev

Kind: variable

##### double vio_obs_huber_thresh

Kind: variable

##### double vio_min_triangulation_dist

Kind: variable

##### bool vio_enforce_realtime

Kind: variable

##### bool vio_use_lm

Kind: variable

##### double vio_lm_lambda_initial

Kind: variable

##### double vio_lm_lambda_min

Kind: variable

##### double vio_lm_lambda_max

Kind: variable

##### bool vio_scale_jacobian

Kind: variable

##### double vio_init_pose_weight

Kind: variable

##### double vio_init_ba_weight

Kind: variable

##### double vio_init_bg_weight

Kind: variable

##### bool vio_marg_lost_landmarks

Kind: variable

##### bool vio_fix_long_term_keyframes

Kind: variable

##### double vio_kf_marg_feature_ratio

Kind: variable

##### KeyframeMargCriteria vio_kf_marg_criteria

Kind: variable

##### double mapper_obs_std_dev

Kind: variable

##### double mapper_obs_huber_thresh

Kind: variable

##### int mapper_detection_num_points

Kind: variable

##### double mapper_num_frames_to_match

Kind: variable

##### double mapper_frames_to_match_threshold

Kind: variable

##### double mapper_min_matches

Kind: variable

##### double mapper_ransac_threshold

Kind: variable

##### double mapper_min_track_length

Kind: variable

##### double mapper_max_hamming_distance

Kind: variable

##### double mapper_second_best_test_ratio

Kind: variable

##### int mapper_bow_num_bits

Kind: variable

##### double mapper_min_triangulation_dist

Kind: variable

##### bool mapper_no_factor_weights

Kind: variable

##### bool mapper_use_factors

Kind: variable

##### bool mapper_use_lm

Kind: variable

##### double mapper_lm_lambda_min

Kind: variable

##### double mapper_lm_lambda_max

Kind: variable

#### LinearizationType

Kind: enum

##### ABS_QR

Kind: enum_value

##### ABS_SC

Kind: enum_value

##### REL_SC

Kind: enum_value

#### MatchingGuessType

Kind: enum

##### SAME_PIXEL

Kind: enum_value

##### REPROJ_FIX_DEPTH

Kind: enum_value

##### REPROJ_AVG_DEPTH

Kind: enum_value

#### KeyframeMargCriteria

Kind: enum

##### KF_MARG_DEFAULT

Kind: enum_value

##### KF_MARG_FORWARD_VECTOR

Kind: enum_value

#### Subnode < node::Sync > sync

Kind: variable

#### InputMap & inputs

Kind: variable

#### std::string leftInputName

Kind: variable

#### std::string rightInputName

Kind: variable

#### Input & left

Kind: variable

Input left image on which VIO is performed.

#### Input & right

Kind: variable

Input right image on which VIO is performed.

#### Input imu

Kind: variable

Input IMU data.

#### Output transform

Kind: variable

Output transform data.

#### Output passthrough

Kind: variable

Output passthrough of left image.

#### BasaltVIO()

Kind: function

#### ~BasaltVIO()

Kind: function

#### void buildInternal()

Kind: function

#### void setImuUpdateRate(int rate)

Kind: function

#### void setConfigPath(const std::string & path)

Kind: function

#### void setConfig(const VioConfig & config)

Kind: function

#### void setUseSpecTranslation(bool use)

Kind: function

#### void setLocalTransform(const std::shared_ptr< TransformData > & transform)

Kind: function

#### void setImuExtrinsics(const std::shared_ptr< TransformData > & imuExtr)

Kind: function

#### void setAccelBias(const std::vector< double > & accelBias)

Kind: function

#### void setAccelNoiseStd(const std::vector< double > & accelNoiseStd)

Kind: function

#### void setGyroBias(const std::vector< double > & gyroBias)

Kind: function

#### void setGyroNoiseStd(const std::vector< double > & gyroNoiseStd)

Kind: function

#### void setDefaultVIOConfig()

Kind: function

#### void runSyncOnHost(bool runOnHost)

Kind: function

### Need assistance?

Head over to [Discussion Forum](https://discuss.luxonis.com/) for technical support or any other questions you might have.
