Class BasaltVIO

Inheritance Relationships

Base Type

Class Documentation

class BasaltVIO : public dai::NodeCRTP<ThreadedHostNode, BasaltVIO>

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

Public Functions

BasaltVIO()
~BasaltVIO()
void buildInternal() override
inline void setImuUpdateRate(int rate)
inline void setConfigPath(const std::string &path)
inline void setUseSpecTranslation(bool use)
void setLocalTransform(const std::shared_ptr<TransformData> &transform)
void setImuExtrinsics(const std::shared_ptr<TransformData> &imuExtr)
void setAccelBias(const std::vector<double> &accelBias)
void setAccelNoiseStd(const std::vector<double> &accelNoiseStd)
void setGyroBias(const std::vector<double> &gyroBias)
void setGyroNoiseStd(const std::vector<double> &gyroNoiseStd)
void setDefaultVIOConfig()
void runSyncOnHost(bool runOnHost)

Public Members

Subnode<node::Sync> sync = {*this, "sync"}
InputMap &inputs = sync->inputs
std::string leftInputName = "left"
std::string rightInputName = "right"
Input &left = inputs[leftInputName]

Input left image on which VIO is performed.

Input &right = inputs[rightInputName]

Input right image on which VIO is performed.

Input imu = {*this, {"inIMU", DEFAULT_GROUP, false, 0, {{DatatypeEnum::IMUData, true}}}}

Input IMU data.

Output transform = {*this, {"transform", DEFAULT_GROUP, {{DatatypeEnum::TransformData, true}}}}

Output transform data.

Output passthrough = {*this, {"imgPassthrough", DEFAULT_GROUP, {{DatatypeEnum::ImgFrame, true}}}}

Output passthrough of left image.

Public Static Attributes

static constexpr const char *NAME = "BasaltVIO"