Class RTABMapSLAM
Defined in File RTABMapSLAM.hpp
Inheritance Relationships
Base Type
public dai::NodeCRTP< dai::node::ThreadedHostNode, RTABMapSLAM >(Template Class NodeCRTP)
Class Documentation
-
class RTABMapSLAM : public dai::NodeCRTP<dai::node::ThreadedHostNode, RTABMapSLAM>
RTABMap SLAM node. Performs SLAM on given odometry pose, rectified frame and depth frame.
Public Functions
-
RTABMapSLAM()
-
~RTABMapSLAM() override
-
void setParams(const std::map<std::string, std::string> ¶ms)
Set RTABMap parameters.
-
inline void setDatabasePath(const std::string &path)
Set RTABMap database path. “/tmp/rtabmap.tmp.db” by default.
-
inline void setLoadDatabaseOnStart(bool load)
Whether to load the database on start. False by default.
-
inline void setSaveDatabaseOnClose(bool save)
Whether to save the database on close. False by default.
-
void saveDatabase()
-
inline void setSaveDatabasePeriodically(bool save)
Whether to save the database periodically. False by default.
-
inline void setSaveDatabasePeriod(double interval)
Set the interval at which the database is saved. 30.0s by default.
-
void setPublishObstacleCloud(bool publish)
Whether to publish the obstacle point cloud. True by default.
-
void setPublishGroundCloud(bool publish)
Whether to publish the ground point cloud. True by default.
-
void setPublishGrid(bool publish)
Whether to publish the ground point cloud. True by default.
-
inline void setFreq(float f)
Set the frequency at which the node processes data. 1Hz by default.
-
inline void setAlphaScaling(float alpha)
Set the alpha scaling factor for the camera model.
-
void setUseFeatures(bool use)
Whether to use input features for SLAM. False by default.
-
std::shared_ptr<TransformData> getLocalTransform()
-
void triggerNewMap()
Trigger a new map.
-
virtual void buildInternal() override
Function called from within the
createfunction to build the node. This function is useful for initialization, setting up inputs and outputs = stuff that cannot be perform in the constuctor.
Public Members
-
std::string rectInputName = "rect"
-
std::string depthInputName = "depth"
-
std::string featuresInputName = "features"
-
Input &rect = inputs[rectInputName]
Input rectified image on which SLAM is performed.
-
Input &depth = inputs[depthInputName]
Input depth image on which SLAM is performed.
-
Input features = {*this, {featuresInputName, DEFAULT_GROUP, DEFAULT_BLOCKING, 15, {{{DatatypeEnum::TrackedFeatures, true}}}}}
Input tracked features on which SLAM is performed (optional).
-
Input odom = {*this, {"odom", DEFAULT_GROUP, DEFAULT_BLOCKING, 15, {{{dai::DatatypeEnum::TransformData, true}}}}}
Input odometry pose.
-
Output transform = {*this, {"transform", DEFAULT_GROUP, {{{dai::DatatypeEnum::TransformData, true}}}}}
Output transform.
-
Output odomCorrection = {*this, {"odomCorrection", DEFAULT_GROUP, {{{dai::DatatypeEnum::TransformData, true}}}}}
Output odometry correction (map to odom).
-
Output obstaclePCL = {*this, {"obstaclePCL", DEFAULT_GROUP, {{{dai::DatatypeEnum::PointCloudData, true}}}}}
Output obstacle point cloud.
-
Output groundPCL = {*this, {"groundPCL", DEFAULT_GROUP, {{{dai::DatatypeEnum::PointCloudData, true}}}}}
Output ground point cloud.
-
Output occupancyGridMap = {*this, {"occupancyGridMap", DEFAULT_GROUP, {{{dai::DatatypeEnum::MapData, true}}}}}
Output occupancy grid map.
-
Output passthroughRect = {*this, {"passthroughRect", DEFAULT_GROUP, {{{dai::DatatypeEnum::ImgFrame, true}}}}}
Output passthrough rectified image.
-
Output passthroughDepth = {*this, {"passthroughDepth", DEFAULT_GROUP, {{{dai::DatatypeEnum::ImgFrame, true}}}}}
Output passthrough depth image.
-
Output passthroughFeatures = {*this, {"passthroughFeatures", DEFAULT_GROUP, {{{dai::DatatypeEnum::TrackedFeatures, true}}}}}
Output passthrough features.
-
Output passthroughOdom = {*this, {"passthroughOdom", DEFAULT_GROUP, {{{dai::DatatypeEnum::TransformData, true}}}}}
Output passthrough odometry pose.
Public Static Attributes
-
static constexpr const char *NAME = "RTABMapSLAM"
-
RTABMapSLAM()