Class RTABMapVIO
Defined in File RTABMapVIO.hpp
Inheritance Relationships
Base Type
public dai::NodeCRTP< ThreadedHostNode, RTABMapVIO >(Template Class NodeCRTP)
Class Documentation
-
class RTABMapVIO : public dai::NodeCRTP<ThreadedHostNode, RTABMapVIO>
RTABMap Visual Inertial Odometry node. Performs VIO on rectified frame, depth frame and IMU data.
Public Functions
-
RTABMapVIO()
-
~RTABMapVIO() override
-
void setParams(const std::map<std::string, std::string> ¶ms)
Set RTABMap parameters.
-
void setUseFeatures(bool use)
Whether to use input features or calculate them internally.
Reset Odometry.
-
void buildInternal() override
Public Members
-
std::string rectInputName = "rect"
-
std::string depthInputName = "depth"
-
std::string featuresInputName = "features"
-
Input &rect = inputs[rectInputName]
Input rectified image on which VIO is performed.
-
Input &depth = inputs[depthInputName]
Input depth image on which VIO is performed.
-
Input features = {*this, {featuresInputName, DEFAULT_GROUP, DEFAULT_BLOCKING, 15, {{{DatatypeEnum::TrackedFeatures, true}}}}}
Input tracked features on which VIO is performed (optional).
-
Input imu = {*this, {"imu", DEFAULT_GROUP, DEFAULT_BLOCKING, 15, {{{DatatypeEnum::IMUData, true}}}}}
Input IMU data.
-
Output transform = {*this, {"transform", DEFAULT_GROUP, {{{DatatypeEnum::TransformData, true}}}}}
Output transform.
-
Output passthroughRect = {*this, {"passthroughRect", DEFAULT_GROUP, {{{DatatypeEnum::ImgFrame, true}}}}}
Passthrough rectified frame.
-
Output passthroughDepth = {*this, {"passthroughDepth", DEFAULT_GROUP, {{{DatatypeEnum::ImgFrame, true}}}}}
Passthrough depth frame.
-
Output passthroughFeatures = {*this, {"passthroughFeatures", DEFAULT_GROUP, {{{DatatypeEnum::TrackedFeatures, true}}}}}
Passthrough features.
Public Static Attributes
-
static constexpr const char *NAME = "RTABMapVIO"
-
RTABMapVIO()