Only released in EOL distros:  

ethzasl_ptam: ptam | ptam_com | rqt_ptam

Package Summary

Modified version of the monocular SLAM framework PTAM

Package Summary

Modified version of the monocular SLAM framework PTAM

  • Maintainer: Markus Achtelik <markus.achtelik AT mavt.ethz DOT ch>, Stephan Weiss <stephan.weiss AT mavt.ethz DOT ch>, Simon Lynen <simon.lynen AT mavt.ethz DOT ch>
  • Author: Markus Achtelik <markus.achtelik AT mavt.ethz DOT ch>, Stephan Weiss <stephan.weiss AT mavt.ethz DOT ch>, Simon Lynen <simon.lynen AT mavt.ethz DOT ch>
  • License: see http://www.robots.ox.ac.uk/~gk/PTAM/download.html
  • Bug / feature tracker: https://github.com/ethz-asl/ethzasl_ptam/issues
  • Source: git https://github.com/ethz-asl/ethzasl_ptam.git (branch: None)

Overview

This Package is the modified version of well known monocular SLAM framework PTAM presented by Klein & Murray in their paper at ISMAR07. We modified the original code such that:

  • it is compatible with ROS.
  • it runs on-board a computationally limited platform (e.g. at 20Hz on an ATOM 1.6GHz single core processor)
  • it is robust in outdoor and self-similar environments such as grass.

This version of PTAM was successfully used in the European project sFly to estimate a 6DoF pose for long-term vision based navigation of a micro helicopter in large outdoor environments.

Please study the original PTAM website and the corresponding paper before using this code. Also, be aware of the license that comes with it.

Note: This package is under active development. It is meant for research use only (license) and at your own responsibility.

Nodes

  • ptam: The main node described here

  • remote_ptam: Node for displaying PTAM information and managing PTAM from a remote (ground) station

  • ptam_visualizer: Node to store map, keyframe and path information and visualize it in RViz

  • cameracalibrator: Node to calibrate the camera. Copy the obtained calibration to the fix parameter file.

Modifications to the Original Code

PTAM has been ported to be compatible to the Robot Operating System (ROS) such that:

  • the input image taken from an image node and a verification image including the features found, is published. This enables the user to handle PTAM on an embedded system without human-machine interfaces.
  • the 6DoF pose is published as a pose with a covariance estimation calculated from PTAM's internal bundle adjustment.
  • the visualization of camera keyframes, trajectory and features is ported to RVIZ such that visualization can be done on a ground station, if necessary.
  • tuning parameters can be changed dynamically in a GUI for dynamic reconfiguration.

Keyframe Handling

In PTAM, the map is defined as a set of keyframes together with their observed features. In order to minimize the computational complexity, here we set a maximum number of keyframes retained in the map. If this number is exceeded, the keyframe furthest away from the current MAV pose gets deleted along with the features associated with it. If the maximum number of retained keyframes is infinite, then the algorithm is equivalent to the original PTAM, while if we set a maximum of 2 keyframes we obtain a visual odometry framework. Naturally, the larger the number of retained keyframes, the lower the estimation drift, but also the larger the computational complexity.

Improved Feature Handling for More Robust Maps

When flying outdoors, we experienced severe issues with self-similarity of the environment - e.g. the asphalt in urban areas or the grass in rural areas. Naturally, features extracted at higher pyramidal levels are more robust to scene ambiguity. Thus, while the finest-scale features are included for tracking, we omit them in map-handling - i.e. we only store features extracted in the highest 3 pyramidal levels. This improves

Thus, while the finest-scale features are included for tracking, we omit them in map-handling -- i.e. we only store features extracted in the highest 3 pyramidal levels. This improves tracking quality when moving away from a given feature (e.g. when taking-off with a MAV with a downward-looking camera), making it possible to navigate over both grass and asphalt.

Since this vision algorithm is keyframe-based, it has high measurement rates when tracking. However, at keyframe generation the frame-rate drops remarkably. Using only features detected at the highest pyramidal levels also reduces drastically the number of newly added features upon keyframe generation. This results to great speed-ups with keyframe-generation running at 13Hz (in contrast to the 7Hz of the original PTAM) and normal tracking rates of around 20Hz on an onboard Atom computer 1.6GHz.

Concerning the type of features we augmented the choice for the corner detector by the AGAST features. Compared to the FAST derivatives, the AGAST corner detector is more repetitive and usually slightly faster as described in this paper. In self-similar structures, it is crucial that the corner detector is highly repetitive. Hence we suggest here to use the AGAST corner detector instead of FAST.

Re-Initialization After Failure Mode

For automatic initialization we ensure that the baseline is sufficiently large by calculating the rotation-compensated median pixel disparity. For rotation compensation we use efficient second-order minimization techniques (ESM) in order to keep PTAM independent of IMU readings. For re-initializations, we store the median scene depth and pose of the closest keyframe and propagate this information to the new initialized map. This way we minimize large jumps in scale and pose at re-initializations.

Inverted Index Structure for Map-point Filtering

On each frame, PTAM projects the 3D points from the map into the current image according to the motion-model prior, which allows then point-correspondences to be established for tracking. Since no filtering on point visibility is preceding this step, it scales linearly with the number of points in the map. We implemented an inverted index structure based on the grouping of map points inside keyframes which allows discarding large groups of map-points with low probability of being in the field-of-view. The search for visible points is performed by re-projecting a small set of distinct map-points from every keyframe which permits inference on their visibility from the current keyframe. The total number of points that need evaluation by reprojection is thereby significantly reduced leading to a scaling of the system in linear order of the visible keyframes rather than in linear order with the overall number of keyframes in the map.

Using ETHZASL-PTAM

To use ETHZASL_PTAM you need an environment with sufficient contrast (i.e. texture) and light. If your shutter speed is above 5ms to obtain an image with sufficient contrast it is very likely that the algorithm does not work properly because of motion blur. This depends on vehicle's motion and vibrations. For good performance on MAVs you may ensure:

  • a shutter speed below 5ms
  • no over/under saturated image regions
  • no self-similar structures

Camera Calibration

The camera model used in PTAM is made for wide angle lenses (>90°). The cameracalibrator node in this package is unchanged with respect to the original code - except the ROS compatibility. You should have a re-projection error of below 0.5. If you have problems calibrating your camera, please have a look at this page.

Initialization

The manual initialization procedure is the same as on the PTAM website:

  • Hit space to start initializing
  • translate the camera (no rotation)
  • Hit space again as soon as the disparity is sufficient

For automatic initialization, enable the AutoInit checkbox in the dynamic reconfigure GUI. This activates also the re-initialization procedure if the map is lost.

Remote Interface

The node remote_ptam catches the image and information published by PTAM such that you can visualize it on a ground station offboard your vehicle. This remote interface accepts nearly all inputs as the original PTAM GUI:

  • [space] for initialization
  • [r] for full map reset
  • [q] quits PTAM
  • [s] enable/disable image streaming for remote node
  • [a] experimental: map reset while storing last pose and scale for propagation upon re-initialization

It also displays the map grid and the initialization trails but not the features in the image nor in a 3D view. See the remote_ptam node documentation for more details.

Running onboard the vehicle

Usually the robot on which PTAM runs does not have any display means and PTAM is controlled remotely using remote_ptam. In such cases the built PTAM GUI can be disabled to free additional computation resources: set the fix parameter gui=False. For further speed-up and performance boost of PTAM onboard the robot you may consider the following settings:

  • InitLevel: 1 for robust and fast initialization on self-similar structures

  • MaxStereoInitLoops: 4 for fast map initialization, prevents hanging on degenerated sets

  • MaxPatchesPerFrame: 300 maximal number of features per frame

  • MaxKF: 15 maximal number of KFs to be retained in the map, do not go lower than 5 to maintain good drift performance

  • UseKFPixelDist: True generates new KF based on pixel disparity. This is usually more robust than the built in KF request in PTAM

  • NoLevelZeroMapPoints: True only use map features in down sampled image pyramids. This greatly improves robustness in self-similar structures

Map Export and Map Display in RViz

The node ptam_visualizer fetches the 3D features, keyframes and actual pose from the PTAM framework and prepares the data to be visualized in RViz. Simply start the node and RViz to start the streaming. The node also allows to store map, path and keyframe data to a file.

Tutorials

!! under construction !! please check regularly for updates

Node Information

ptam

main framework derived from the original PTAM

Subscribed Topics

image (sensor_msgs/Image)
  • the input image to be processed by PTAM
vslam/key_pressed (std_msgs/String)
  • topic used by the remote_ptam node to send keyboard commands to the PTAM interface
vslam/imu (sensor_msgs/Imu)
  • Experimental: IMU readings to estimate a better rotation between frames. We do not recommend to use this since PTAM's estimate using the Small Blurry Images for rotation estimation is already very good.

Published Topics

vslam/info (ptam_com/ptam_info)
  • Contains information on the current status of PTAM such as framerate, number of keyframes, tracking and map quality as well as string messages
vslam/pose (geometry_msgs/PoseWithCovarianceStamped) vslam/preview (sensor_msgs/Image)
  • down sampled image used by the remote_ptam node to visualize the current camera view and PTAM status

Services

vslam/pointcloud (invalid message type for SrvLink(srv/type))
  • point cloud service to visualize 3D points in RViz
vslam/keyframes (invalid message type for SrvLink(srv/type))
  • keyframe service to visualize keyframes in RViz

Parameters

Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~Scale (double, default: 1.0)
  • Scale Range: 0.01 to 30.0
~MotionModelSource (str, default: CONSTANT)
  • selects the source for the motion model. Possible values are: MM_CONSTANT (CONSTANT): use constant motion model., MM_IMU (IMU): use imu orientation for the motion model., MM_FULL_POSE (FULL_POSE): use full pose estimated externally for motion model.
~MaxPatchesPerFrame (double, default: 500.0)
  • max features per frame Range: 10.0 to 1000.0
~MaxKFDistWiggleMult (double, default: 3.0)
  • 'distance' after which a new kf is requested Range: 0.1 to 10.0
~UseKFPixelDist (bool, default: False) ~NoLevelZeroMapPoints (bool, default: False)
  • do not add map points at level zero
~EpiDepthSearchMaxRange (double, default: 100.0)
  • depth variance to search for features Range: 1.0 to 100.0
~CoarseMin (double, default: 20.0)
  • min number of features for coarse tracking Range: 1.0 to 100.0
~CoarseMax (double, default: 60.0)
  • max number of features for coarse tracking Range: 1.0 to 100.0
~CoarseRange (double, default: 30.0)
  • Pixel search radius for coarse features Range: 1.0 to 100.0
~CoarseSubPixIts (double, default: 8.0)
  • coarse tracking sub-pixel iterations Range: 1.0 to 100.0
~DisableCoarse (bool, default: False)
  • enable/disable coarse tracking
~CoarseMinVelocity (double, default: 0.006)
  • speed above which coarse stage is used Range: 0.0 to 1.0
~TrackingQualityGood (double, default: 0.3)
  • min ratio features visible/features found for good tracking Range: 0.0 to 1.0
~TrackingQualityLost (double, default: 0.13)
  • max ratio features visible/features found before lost Range: 0.0 to 1.0
~TrackingQualityFoundPixels (int, default: 100)
  • min pixels to be found for good tracking Range: 1 to 1000
~MaxIterations (double, default: 20.0)
  • max iterations for bundle adjustment Range: 1.0 to 100.0
~MaxKF (int, default: 0)
  • number of keyframes kept in the map (0 or 1 = inf) Range: 0 to 1000
~BundleMethod (str, default: LOCAL_GLOBAL)
  • bundleadjustment method Possible values are: LOCAL_GLOBAL (LOCAL_GLOBAL): local and global bundle adjustment, LOCAL (LOCAL): local bundle adjustment only, GLOBAL (GLOBAL): global bundle adjustment only
~UpdateSquaredConvergenceLimit (double, default: 1e-06)
  • limit for convergence in bundle adjustment Range: 0.0 to 1.0
~BundleDebugMessages (bool, default: False)
  • print bundle debug messages
~FASTMethod (str, default: FAST9_nonmax)
  • FAST corner method Possible values are: FAST9 (FAST9): FAST 9, FAST10 (FAST10): FAST 10, FAST9_nonmax (FAST9_nonmax): FAST 9 with nonmax suppression, AGAST12d (AGAST12d): AGAST 12 pixel diamond, OAST16 (OAST16): AGAST 16 pixel circular
~Thres_lvl0 (int, default: 10)
  • threshold for FAST features on level 0 Range: 0 to 255
~Thres_lvl1 (int, default: 15)
  • threshold for FAST features on level 1 Range: 0 to 255
~Thres_lvl2 (int, default: 15)
  • threshold for FAST features on level 2 Range: 0 to 255
~Thres_lvl3 (int, default: 10)
  • threshold for FAST features on level 3 Range: 0 to 255
~AdaptiveThrs (bool, default: False)
  • adaptive threshold for corner extraction
~AdaptiveThrsMult (double, default: 5.0)
  • controls adaptive threshold to MaxPatches*N corners Range: 0.5 to 20.0
~RotationEstimatorBlur (double, default: 0.75)
  • small images for the rotation estimator blur Range: 0.0 to 10.0
~UseRotationEstimator (bool, default: True)
  • small images for the rotation estimator enable/disable
~MiniPatchMaxSSD (int, default: 100000)
  • MiniPatch tracking threshhold Range: 0 to 10000000
~PlaneAlignerRansacs (int, default: 100)
  • number of dominant plane RANSACs Range: 0 to 1000
~RelocMaxScore (int, default: 9000000)
  • score for relocalization Range: 0 to 90000000
~AutoInit (bool, default: False)
  • enable auto initialization
~AutoInitPixel (int, default: 20)
  • min pixel distance for auto initialization Range: 1 to 100
~MaxStereoInitLoops (int, default: 10)
  • max # of loops for stereo initialization Range: 1 to 100
Static parameters
parameters that are statically set
~InitLevel (, default: 1)
  • minimal pyramidal level for map initialization. Use higher levels on self-similar structures Range 0 to 3
~gui (, default: true)
  • enables/disables the graphical feedback. Disable this on onboard computers
~ImageSizeX (, default: 752)
  • x-dimensions of the input image to be processed by PTAM
~ImageSizeY (, default: 480)
  • y-dimensions of the input image to be processed by PTAM
~ARBuffer_width (, default: 1200)
  • width resolution of the graphical feedback window
~ARBuffer_height (, default: 960)
  • height resolution of the graphical feedback window
~WiggleScale (, default: 0.1)
  • Multiplier for the distance at which a new KF is requested
~BundleMEstimator (, default: Tukey)
  • Estimator to be used for bundle adjustment. Possible values are: Huber, Cauchy, Tukey
~TrackerMEstimator (, default: Tukey)
  • Estimator to be used for bundle adjustment. Possible values are: Huber, Cauchy, Tukey
~MinTukeySigma (, default: 0.4)
  • Sigma value for Tukey estimator
~CandidateMinSTScore (, default: 70)
  • minimal Shi-Tomasi score for a point to be considered as a candidate feature
~Cam_fx (, default: --) ~Cam_fy (, default: --) ~Cam_cx (, default: --) ~Cam_cy (, default: --) ~Cam_s (, default: --) ~Calibrator_BlurSigma (, default: 1.0) ~Calibrator_MeanGate (, default: 10) ~Calibrator_MinCornersForGrabbedImage (, default: 20) ~Calibrator_Optimize (, default: 0) ~Calibrator_Show (, default: 0) ~Calibrator_NoDistortion (, default: 0) ~CameraCalibrator_MaxStepDistFraction (, default: 0.3) ~CameraCalibrator_CornerPatchSize (, default: 20) ~GLWindowMenu_Enable (, default: true)
  • use the openGL window
~GLWindowMenu_mgvnMenuItemWidth (, default: 90)
  • openGL window size
~GLWindowMenu_mgvnMenuTextOffset (, default: 20)
  • offset for text display in the openGL window

Wiki: ptam (last edited 2012-05-14 19:16:09 by stephanweiss)