Skip to content

[feat][ROS] Add new translation constraint for the wheel encoder

Julia Sanchez requested to merge feat/AddWheelDirection into master

Goal

Add an optional direction information to the wheel odometer constraint

Changes

  • A new 3D Ceres residual is added for the wheel encoder
  • A new constraint is added in external sensors
  • The parameters interfaces are created in the slam manager and in ROS wrapper

Results

Data

fast-filtered

Commands to reproduce the results

catkin build --cmake-args -DCMAKE_BUILD_TYPE=Release

  • Change the parameters :
    wheel_encoder:
    enable: true            # [bool] To receive and use a wheel encoder (distance measurement)
    relative: true          # [bool] To set the constraint from reference or from previous frame
    weight: 100.               # [float] Weight to apply onto the wheel encoder constraint in the front end optimization
    saturation_distance: 0.5 # [m] Spatial distance threshold to discard the measurement in SLAM optimization
    reference: [0., 0., 0.]  # [m, m, m] Reference point for the odometry measure
                             # Do not set if relative mode is true, [0.,0.,0.] deactivates the feature
    direction: [0.96592582628, 0, -0.2588190451]  # [m, m, m] Direction on which the odometry is measured
                             # [0.,0.,0.] deactivates the feature: the residual will be 1D

Note : the direction was derived approximately looking at the data. The direction of motion changes during the acquisition in these data.

roslaunch lidar_slam slam_ouster.launch outdoor:=false aggregate:=true

rosbag play --clock -d 2 path/to/bag.bag /wire_converted:=wheel_odom

Results

Resulting map and trajectory.

What remains to solve

  • Test on real data (with good motion direction)
Edited by Julia Sanchez

Merge request reports

Loading