rtabmap_ros icon indicating copy to clipboard operation
rtabmap_ros copied to clipboard

Problems with local openvins

Open hu-minghao opened this issue 6 months ago • 1 comments

Hello,I use openvins as rtabmap odometry, but I didn't see where to pass the openvins parameters. How can I pass the local openv configuration to rtabmap?

hu-minghao avatar Jun 12 '25 16:06 hu-minghao

Most parameters can be tuned by adding parameters like this to rtabmap_odom nodes:

Node(
            package='rtabmap_odom', executable='rgbd_odometry', name="rgbd_odometry", output="screen",
            parameters=[{
                # RTAB-Map parameters should all be string
                "OdomOpenVINS/AccelerometerNoiseDensity": "0.01",
                "OdomOpenVINS/AccelerometerRandomWalk": "0.001",
                ...
            }],

or use a parameter file

/rgbd_odometry:
      ros__parameters:
        OdomOpenVINS/AccelerometerNoiseDensity: "0.01"
        OdomOpenVINS/AccelerometerRandomWalk: "0.001"

Here a list of all supported parameters:

$ rtabmap --params | grep OdomOpenVINS
Param: OdomOpenVINS/AccelerometerNoiseDensity = "0.01"     [[m/s^2/sqrt(Hz)] (accel "white noise")]
Param: OdomOpenVINS/AccelerometerRandomWalk = "0.001"      [[m/s^3/sqrt(Hz)] (accel bias diffusion)]
Param: OdomOpenVINS/CalibCamExtrinsics = "false"           [Bool to determine whether or not to calibrate imu-to-camera pose]
Param: OdomOpenVINS/CalibCamIntrinsics = "false"           [Bool to determine whether or not to calibrate camera intrinsics]
Param: OdomOpenVINS/CalibCamTimeoffset = "false"           [Bool to determine whether or not to calibrate camera to IMU time offset]
Param: OdomOpenVINS/CalibIMUGSensitivity = "false"         [Bool to determine whether or not to calibrate the Gravity sensitivity]
Param: OdomOpenVINS/CalibIMUIntrinsics = "false"           [Bool to determine whether or not to calibrate the IMU intrinsics]
Param: OdomOpenVINS/DtSLAMDelay = "0.0"                    [Delay, in seconds, that we should wait from init before we start estimating SLAM features]
Param: OdomOpenVINS/FeatRepMSCKF = "0"                     [What representation our features are in (msckf features)]
Param: OdomOpenVINS/FeatRepSLAM = "4"                      [What representation our features are in (slam features)]
Param: OdomOpenVINS/FiMaxBaseline = "40"                   [Max baseline ratio to accept triangulated features]
Param: OdomOpenVINS/FiMaxCondNumber = "10000"              [Max condition number of linear triangulation matrix accept triangulated features]
Param: OdomOpenVINS/FiMaxRuns = "5"                        [Max runs for Levenberg-Marquardt]
Param: OdomOpenVINS/FiRefineFeatures = "true"              [If we should perform Levenberg-Marquardt refinement]
Param: OdomOpenVINS/FiTriangulate1d = "false"              [If we should perform 1d triangulation instead of 3d]
Param: OdomOpenVINS/GravityMag = "9.81"                    [Gravity magnitude in the global frame (i.e. should be 9.81 typically)]
Param: OdomOpenVINS/GyroscopeNoiseDensity = "0.001"        [[rad/s/sqrt(Hz)] (gyro "white noise")]
Param: OdomOpenVINS/GyroscopeRandomWalk = "0.0001"         [[rad/s^2/sqrt(Hz)] (gyro bias diffusion)]
Param: OdomOpenVINS/InitDynInflationBa = "100.0"           [What to inflate the recovered bias_a covariance by]
Param: OdomOpenVINS/InitDynInflationBg = "10.0"            [What to inflate the recovered bias_g covariance by]
Param: OdomOpenVINS/InitDynInflationOri = "10.0"           [What to inflate the recovered q_GtoI covariance by]
Param: OdomOpenVINS/InitDynInflationVel = "100.0"          [What to inflate the recovered v_IinG covariance by]
Param: OdomOpenVINS/InitDynMLEMaxIter = "50"               [How many iterations the MLE refinement should use (zero to skip the MLE)]
Param: OdomOpenVINS/InitDynMLEMaxThreads = "6"             [How many threads the MLE should use]
Param: OdomOpenVINS/InitDynMLEMaxTime = "0.05"             [How many seconds the MLE should be completed in]
Param: OdomOpenVINS/InitDynMLEOptCalib = "false"           [If we should optimize calibration during intialization (not recommended)]
Param: OdomOpenVINS/InitDynMinDeg = "10.0"                 [Orientation change needed to try to init]
Param: OdomOpenVINS/InitDynMinRecCond = "1e-15"            [Reciprocal condition number thresh for info inversion]
Param: OdomOpenVINS/InitDynNumPose = "6"                   [Number of poses to use within our window time (evenly spaced)]
Param: OdomOpenVINS/InitDynUse = "false"                   [If dynamic initialization should be used]
Param: OdomOpenVINS/InitIMUThresh = "1.0"                  [Variance threshold on our acceleration to be classified as moving]
Param: OdomOpenVINS/InitMaxDisparity = "10.0"              [Max disparity to consider the platform stationary (dependent on resolution)]
Param: OdomOpenVINS/InitMaxFeatures = "50"                 [How many features to track during initialization (saves on computation)]
Param: OdomOpenVINS/InitWindowTime = "2.0"                 [Amount of time we will initialize over (seconds)]
Param: OdomOpenVINS/Integration = "1"                      [0=discrete, 1=rk4, 2=analytical (if rk4 or analytical used then analytical covariance propagation is used)]
Param: OdomOpenVINS/LeftMaskPath = ""                      [Mask for left image]
Param: OdomOpenVINS/MaxClones = "11"                       [Max clone size of sliding window]
Param: OdomOpenVINS/MaxMSCKFInUpdate = "50"                [Max number of MSCKF features we will use at a given image timestep.]
Param: OdomOpenVINS/MaxSLAM = "50"                         [Max number of estimated SLAM features]
Param: OdomOpenVINS/MaxSLAMInUpdate = "25"                 [Max number of SLAM features we allow to be included in a single EKF update.]
Param: OdomOpenVINS/MinPxDist = "15"                       [Eistance between features (features near each other provide less information)]
Param: OdomOpenVINS/NumPts = "200"                         [Number of points (per camera) we will extract and try to track]
Param: OdomOpenVINS/RightMaskPath = ""                     [Mask for right image]
Param: OdomOpenVINS/TryZUPT = "true"                       [If we should try to use zero velocity update]
Param: OdomOpenVINS/UpMSCKFChi2Multiplier = "1.0"          [Chi2 multiplier for MSCKF features]
Param: OdomOpenVINS/UpMSCKFSigmaPx = "1.0"                 [Pixel noise for MSCKF features]
Param: OdomOpenVINS/UpSLAMChi2Multiplier = "1.0"           [Chi2 multiplier for SLAM features]
Param: OdomOpenVINS/UpSLAMSigmaPx = "1.0"                  [Pixel noise for SLAM features]
Param: OdomOpenVINS/UseFEJ = "true"                        [If first-estimate Jacobians should be used (enable for good consistency)]
Param: OdomOpenVINS/UseKLT = "true"                        [If true we will use KLT, otherwise use a ORB descriptor + robust matching]
Param: OdomOpenVINS/UseStereo = "true"                     [If we have more than 1 camera, if we should try to track stereo constraints between pairs]
Param: OdomOpenVINS/ZUPTChi2Multiplier = "0.0"             [Chi2 multiplier for zero velocity]
Param: OdomOpenVINS/ZUPTMaxDisparity = "0.5"               [Max disparity we will consider to try to do a zupt (i.e. if above this, don't do zupt)]
Param: OdomOpenVINS/ZUPTMaxVelodicy = "0.1"                [Max velocity we will consider to try to do a zupt (i.e. if above this, don't do zupt)]
Param: OdomOpenVINS/ZUPTNoiseMultiplier = "10.0"           [Multiplier of our zupt measurement IMU noise matrix (default should be 1.0)]
Param: OdomOpenVINS/ZUPTOnlyAtBeginning = "false"          [If we should only use the zupt at the very beginning static initialization phase]

Refer also to this if you don't find the OpenVINS parameter above, the parameter name may be one already used by rtabmap on a different name.

matlabbe avatar Jun 13 '25 03:06 matlabbe