Only released in EOL distros:  

Overview

More information can be found here

Dependencies

  • vslam : Really just the SBA package within this, but I find it easier (and more interesting) to just compile the whole thing.

  • OpenCV

ROS Nodes

calibrator

For the geometric calibration of both thermal-infrared cameras and regular cameras (both intrinsic and extrinsic).

Parameters

Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~alpha (double, default: 0.0)
  • Alpha level for undistortion and new cam mat Range: -1.0 to 1.0
~autoAlpha (bool, default: True)
  • Automatically find best alpha level
~trackingMode (bool, default: False)
  • Attempt to track pattern rather than redetect
~flowThreshold (double, default: 0.0001)
  • Sensitivity for optical flow algorithm Range: 0.0 to 1.0
~maxFrac (double, default: 0.05)
  • Maximum proportion of minor image dimension that points may drift between frames for tracking Range: 0.0 to 1.0
~errorThreshold (double, default: 0.0)
  • Error threshold for feature exlusion from tracker Range: 0.0 to 200.0
~stopCapturing (bool, default: False)
  • stopCapturing
~contrastLeft (double, default: 1.0)
  • Contrast left Range: 0.0 to 10.0
~brightnessLeft (double, default: 0.0)
  • Brightness left Range: -50.0 to 50.0
~normLeft (bool, default: False)
  • Histogramm equalisation left
~invertLeft (bool, default: False)
  • Invert left
~contrastRight (double, default: 1.0)
  • Contrast left Range: 0.0 to 10.0
~brightnessRight (double, default: 0.0)
  • Brightness right Range: -50.0 to 50.0
~normRight (bool, default: False)
  • Histogramm equalisation right
~invertRight (bool, default: False)
  • Invert left
~adjustMSERLeft (bool, default: False)
  • adjustMSERLeft
~deltaLeft (int, default: 8)
  • deltaLeft Range: 0 to 100
~maxVarLeft (double, default: 0.25)
  • maxVarLeft Range: 0.0 to 2.0
~minDivLeft (double, default: 0.2)
  • minDivLeft Range: 0.0 to 2.0
~areaThresholdLeft (double, default: 1.01)
  • areaThresholdLeft Range: 0.0 to 5.0
~adjustMSERRight (bool, default: False)
  • adjustMSERRight
~deltaRight (int, default: 8)
  • deltaRight Range: 0 to 100
~maxVarRight (double, default: 0.25)
  • maxVarRight Range: 0.0 to 2.0
~minDivRight (double, default: 0.2)
  • minDivRight Range: 0.0 to 2.0
~areaThresholdRight (double, default: 1.01)
  • areaThresholdRight Range: 0.0 to 5.0

Examples

For intrinsic calibration only:

$ roslaunch thermalvis calibrator_monoexample.launch

For stereo calibration:

$ roslaunch thermalvis calibrator_stereoexample.launch

streamer

For streaming from and controlling the Thermoteknix Miricle 110K and 307K cameras.

Parameters

Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~inputDatatype (int, default: 1)
  • Pixel format of input Possible values are: 8bit (0): 8-bit single channel, raw (1): Raw 16-bit format, mm (2): 8-bit dual channel (multimodal), 16uc1 (3): 16-bit from kinect depth
~forceInputGray (bool, default: False)
  • Forces color input to be converted to gray
~framerate (double, default: -1.0)
  • Desired Framerate Range: -1.0 to 100.0
~normMode (int, default: 0)
  • Histogram Normalization Mode Possible values are: standard (0): Standard dynamic range, equalize (1): Equalization, clahe (2): CLAHE, clahe_adaptive (3): Adaptive Contrast Enhancement, centralized (4): Centers intensities around median, expanded (5): Centers intensities around mid-range
~normFactor (double, default: 0.0)
  • Normalization factor Range: 0.0 to 1.0
~filterMode (int, default: 0)
  • Image Filtering Mode Possible values are: none (0): No filtering, gaussian (1): Gaussian Filter, bilateral (2): Bilateral Filter, adaptive_bilateral (3): Adaptive Bilateral Filter
~filterParam (double, default: 2.0)
  • Filter param Range: 0.0 to 20.0
~output16bit (bool, default: True)
  • Activate 16-bit (raw) output
~output8bit (bool, default: False)
  • Activeate 8-bit (mono) output
~outputColor (bool, default: True)
  • Activate color output
~map (int, default: 0)
  • A color mapping parameter which is edited via an enum Possible values are: GRAYSCALE (0): Grayscale coloring, CIECOMP (1): CIECOMP coloring, BLACKBODY (2): Blackbody coloring, RAINBOW (3): Rainbow coloring, IRON (4): Iron coloring, BLUERED (5): Blue-red coloring, JET (6): Jet coloring, ICE (7): Ice coloring, ICEIRON (8): Ice and iron coloring, ICEFIRE (9): Ice and fire coloring, REPEATED (10): Ice and fire coloring, HIGHLIGHTED (11): Highlights dominant pixels as red
~extremes (bool, default: True)
  • Allow b/w color mapping
~writeImages (bool, default: False)
  • Activate write output
~outputFormat (int, default: 4)
  • Output image format Possible values are: jpg (0): JPEG, pgm (1): PGM, bmp (2): BMP, ppm (3): PPM, png (4): PNG
~outputType (int, default: 2)
  • Output image type Possible values are: CV_8UC1 (0): 8-bit single channel, CV_8UC3 (1): 8-bit triple channel, CV_16UC1 (2): 16-bit single channel
~writeQuality (double, default: 1.0)
  • Write quality Range: 0.0 to 1.0
~keepOriginalNames (bool, default: True)
  • Keep original names
~loopMode (bool, default: False)
  • Re-loop once finished
~undistortImages (bool, default: False)
  • Activate image undistortion
~rectifyImages (bool, default: False)
  • Activate image rectification
~alpha (double, default: 0.0)
  • Alpha level for undistortion Range: -1.0 to 1.0
~autoAlpha (bool, default: True)
  • Automatically find best alpha level
~temporalSmoothing (bool, default: False)
  • Regulate change in median intensity (8-bit only)
~maxShift (int, default: 2)
  • Maximum amount of intensity shift (8-bit only) Range: 0 to 20
~temporalMemory (int, default: 5)
  • Maximum amount of past frames to consider Range: 0 to 100
~removeDuplicates (bool, default: False)
  • Remove consecutive duplicate frames
~markDuplicates (bool, default: False)
  • Mark consecutive duplicate frames
~dumpDuplicates (bool, default: False)
  • Output duplicates to a log-file
~dumpTimestamps (bool, default: False)
  • Output timestamps to console
~fusionFactor (double, default: 0.6)
  • Scaling range for modality fusion Range: 0.0 to 1.0
~syncMode (int, default: 0)
  • Input synchronization mode Possible values are: hardSync (0): Image and camera_info topics must be fully synchronized, softSync (1): Image and camera_info topics do not have to be fully synchronized, imageOnly (2): To be used when no camera_info topic is present
~syncDiff (double, default: 0.005)
  • Maximum difference in seconds for soft sync Range: 0.0 to 1.0
~readThermistor (bool, default: False)
  • Read thermistor values
~shutterPeriod (int, default: 10)
  • No. of polls between shutter switching Range: 0 to 1000
~serialPollingRate (double, default: 10.0)
  • Rate (per sec) for serial polling Range: 0.0 to 100.0
~maxNucInterval (int, default: 45)
  • Maximum NUC interval (in sec) Range: 5 to 300
~maxNucThreshold (double, default: 0.2)
  • Maximum NUC threshold (in deg) Range: 0.0 to 5.0
~maxThermistorDiff (double, default: 0.5)
  • Maximum temp difference between consecutive thermistor readings Range: 0.0 to 10.0
~verboseMode (bool, default: False)
  • Display additional debug info
~drawReticle (bool, default: False)
  • Overlay reticle

Examples

Should act as a driver for a Thermoteknix Miricle 110K or 307K camera, allowing the reading of the thermistor, and control of camera settings, along with streaming in the raw 14-bit/pixel mode.

$ roslaunch thermalvis streamer_example.launch

flow

Highly configurable sparse optical flow for thermal-infrared video.

Parameters

Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~softSync (bool, default: False)
  • Attempt to pair images and camera info that may not be strictly sync'ed
~syncDiff (double, default: 0.005)
  • Maximum difference in seconds for soft sync Range: 0.0 to 1.0
~detector_1 (int, default: 1)
  • Detector #1 Possible values are: OFF (0): No detector implemented, GFTT (1): Hessian features (GFTT), FAST (2): FAST, HARRIS (3): Harris features (GFTT)
~sensitivity_1 (double, default: 0.1)
  • Detector #1 sensitivity Range: 0.0 to 1.0
~detector_2 (int, default: 0)
  • Detector #2 Possible values are: OFF (0): No detector implemented, GFTT (1): Hessian features (GFTT), FAST (2): FAST, HARRIS (3): Harris features (GFTT)
~sensitivity_2 (double, default: 0.1)
  • Detector #2 sensitivity Range: 0.0 to 1.0
~detector_3 (int, default: 0)
  • Detector #3 Possible values are: OFF (0): No detector implemented, GFTT (1): Hessian features (GFTT), FAST (2): FAST, HARRIS (3): Harris features (GFTT)
~sensitivity_3 (double, default: 0.1)
  • Detector #3 sensitivity Range: 0.0 to 1.0
~maxFrac (double, default: 0.05)
  • Maximum proportion of minor image dimension that points may drift between frames for tracking Range: 0.0 to 1.0
~maxFeatures (int, default: 100)
  • Maximum number of features to attempt tracking Range: 0 to 500
~newDetectionFramecountTrigger (int, default: 10)
  • Number of frames to wait before attempting re-detections Range: 0 to 100
~maximumDetectionFeatures (int, default: 300)
  • Maximum number of features to allow detector to return Range: 0 to 1000
~minDistance (double, default: 5.0)
  • Minimum spatial separation between features Range: 0.0 to 20.0
~flowThreshold (double, default: 0.0001)
  • Sensitivity for optical flow algorithm Range: 0.0 to 1.0
~minTrackedFeaturesPerDetector (int, default: 50)
  • Minimum number of features to be tracked by each detector Range: 0 to 500
~maxTrackedFeaturesPerDetector (int, default: 300)
  • Maximum number of features to be tracked by each detector Range: 0 to 500
~nearSearchHistory (int, default: 5)
  • How many frames to search back for recently lost features Range: 0 to 1000
~farSearchHistory (int, default: 48)
  • How many frames to search back for historically lost features Range: 0 to 1000
~delayTimeout (double, default: 2.0)
  • Timeout in seconds before NUC is assumed Range: 0.0 to 10.0
~maxProjectionsPerFeature (int, default: 10)
  • Maximum number of projections of feature to publish Range: 0 to 100
~minPointsForWarning (int, default: 16)
  • Minimum number of tracks below which a warning is triggered Range: 0 to 100
~drawingHistory (int, default: 10)
  • Number of projections for the feature tail in the debug image Range: 0 to 100
~debugMode (bool, default: True)
  • Publish output

Examples

Should publish a customized tracks topic containing sparse optical flow information.

$ roslaunch thermalvis flow_example.launch

monoslam

Monocular SLAM with a hand-held thermal-infrared camera.

Parameters

Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~minStartupScore (double, default: 0.8)
  • Minimum keyframe pair score for initialization Range: 0.0 to 1.0
~flowback (int, default: 3)
  • Flowback frames (per adjustment) Range: 0 to 10
~keyframeSpacing (int, default: 5)
  • See the paper, variable K Range: 0 to 100
~maxKeyframeSeparation (int, default: 15)
  • Maximum number of frames separating keyframes Range: 0 to 100
~minKeyframeScore (double, default: 20.0)
  • Minimum required keyframe score Range: 0.0 to 100.0
~adjustmentFrames (int, default: 50)
  • Adjustment frames Range: 1 to 100
~motionThreshold (double, default: 20.0)
  • Maximum amount of tolerated motion Range: 1.0 to 100.0
~framesForTriangulation (int, default: 8)
  • Number of frames a feature must appear in before it's triangulated Range: 1 to 100
~min3dPtsForPnP (int, default: 24)
  • Minimum number of points to use to estimate pose of camera Range: 0 to 100
~camerasPerSys (int, default: 10)
  • Cameras to consider for each bundle adjustment Range: 0 to 100
~minTrackedFeatures (int, default: 50)
  • Minimum number of features that must be tracked Range: 0 to 500
~maxGuides (int, default: 5)
  • Maximum number of camera views to consider for initial pose estimate Range: 0 to 100
~minGeometryScore (double, default: 30.0)
  • Minimum required geometry score Range: 0.0 to 100.0
~requiredTrackFrac (double, default: 0.8)
  • Required proportion of tracks to be maintained between frames Range: 0.0 to 1.0
~dataTimeout (double, default: 5.0)
  • Time (sec) after which no data triggers program exit Range: 0.0 to 60.0
~initialStructureIterations (int, default: 1000)
  • Number of iterations to perform finalizing initial structure Range: 0 to 1000
~poseEstimateIterations (int, default: 10)
  • Number of iterations to perform when putatively estimating a camera pose Range: 0 to 1000
~fullSystemIterations (int, default: 10)
  • Number of iterations to perform each cycle on the full system Range: 0 to 1000
~keyframeIterations (int, default: 10)
  • Number of iterations to perform each cycle on the keyframes Range: 0 to 1000
~subsequenceIterations (int, default: 100)
  • Number of iterations to perform each cycle on the subsequence Range: 0 to 1000
~debugMode (bool, default: False)
  • Display additional debug info
~timeDebug (bool, default: False)
  • Display timing information
~timeSpacing (int, default: 5)
  • Number of frames to wait before publishing timing info Range: 0 to 100

Examples

I recommend making sure that you have got the flow node working effectively before trying to run the monoslam node.

$ roslaunch thermalvis monoslam_example.launch

depth

Real-time depth from stereo from thermal-infrared video [in progress].

Parameters

Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~alpha (double, default: 0.0)
  • Alpha level for undistortion Range: -1.0 to 1.0
~autoAlpha (bool, default: True)
  • Automatically find best alpha level

Examples

This should simply produce a depth map from two video streams.

$ roslaunch thermalvis depth_example.launch

listener

For processing 3D reconstruction datasets [in progress].

Parameters

Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~maxFrames (int, default: 10000)
  • Maximum number of frames to extract Range: 0 to 10000

Examples

This node requires a bag file to exist which contains relevant topics for 3D thermal mapping.

$ roslaunch thermalvis listener_example.launch

Wiki: thermalvis (last edited 2013-02-14 00:40:16 by StephenVidas)