= Using RT-SLAM = == Requirements and recommendations == * '''camera''': * /!\ It '''must''' be a '''global shutter''' camera! Rolling shutter cameras such as most webcams acquire pixels line by line: different lines don't have the same timestamp and it creates peculiar distortion when moving which cannot be calibrated with standard calibration models. All CCD sensors are global shutter, most CMOS sensors are rolling shutter (only high-end CMOS sensors are global shutter). It would be possible to use a rolling shutter camera if we were considering that every line has a different date, and processing them in the right order, but this is not implemented yet nor is planned to be for now. * VGA resolution (640x480) is recommended (may work with lower resolution but will reduce precision, higher resolution will be at the expense of lower framerate which may not be desirable). * Only gray level is required, and is recommended because cameras that output color images (RGB, YUV or Bayer) will have lower framerate because of the size. Less importantly it will also require more cpu time to convert them to gray, which should not hurt the performance on a multicore CPU because it is done in a separate thread, but it is somewhat contradictory with the philosophy of active search in RT-SLAM which is avoiding image processing on full images. * Framerate should be at least 30fps (say between 30 and 60fps) for constant velocity slam (without an IMU): the higher the framerate is, the better robustness and accuracy will be, '''iff''' your computer is fast enough to make some observations for each frame (you should check that running above 50-60fps really improves the performance in your special case). With an IMU, depending on its quality, it is possible to decrease it (eg with an XSens MTi on an all-terrain robot it is possible to run the camera at only 15fps). * Firewire cameras have very good timestamps, which is especially important for inertial slam to avoid having to hard synchronize the IMU and the camera. * Being able to control the shutter time is very interesting for highly dynamic movements with low light, to avoid having fuzzy image. It's better for data association to have noisy images than fuzzy images (typically shutter time below 5ms). It can be done either by software or with hardware trigger, depending on the camera (--shutter option does the job for firewire cameras and for using an XSense MTi IMU as trigger). * If you can control the lens aperture, open it as much as you can as long as the image remains in focus at reasonable depths (bigger aperture reduces depth of field). If you change the lens aperture, it is recommended to recalibrate the camera. * For live use of RT-SLAM, only Firewire and Ueye USB cameras are currently supported. We have successfully tested RT-SLAM with !PointGrey Flea2 and Flea3, AVT Marlin, and UEye cameras, but it should work correctly with cheaper cameras such as [[http://www.unibrain.com/products/visionimg/tSpec_Fire_i_DC.htm|Unibrain Fire-i cameras]] (around $100). * It must be carefully calibrated, for instance with the [[http://www.vision.caltech.edu/bouguetj/calib_doc/|Matlab calibration toolbox]] or [[http://opencv.itseez.com/doc/tutorials/calib3d/camera_calibration/camera_calibration.html|OpenCV calibration sample]]. Tangential distortion should be disabled during calibration as it is not supported by RT-SLAM (est_dist=[1;1;0;0;1] for Matlab or -zt option for OpenCV). Third order radial distortion parameter should be enabled if distortion is high. * '''IMU''' (optional): * It must provide both angular velocities and linear accelerations * Frequency should be greater than images frequency (though otherwise it will interpolate and it will still work) * No particular requirement on quality, but the noise model has to be correctly setup in the configuration according to the datasheet. However the more precise it will be, the better RT-SLAM precision and robustness will be, and the longer you will be able to live without images. * For live use of RT-SLAM, only XSens MTi IMUs are supported. If you want to use another hardware you have to write an adapter (called hardwareSensor in RT-SLAM). * The tranformation camera<->IMU needs to be carefully computed. Check the datasheets of the devices to know where is exactly their origin (for an IMU it is the physical location of the accelerometers, for a camera it is the focal point which is located at focal length in front of the image plane). The transformation is the coordinates of the camera's frame in the IMU's frame. The cameras frame follows the OpenCV convention (when looking at the camera from the back, x is right, y is bottom, z is front). Be careful that the transformation has to be entered with the (x,y,z,roll,pitch,yaw) convention, with the angles in degrees. * Limitations: * With inertial SLAM you have to leave the system static for 2 seconds at the beginning, when it is written "Sensors are calibrating..." in the console. This is for finding the verticality and its uncertainty. * It will be more robust if you do some lateral translations at the beginning (eg a quick 20cm amplitude lateral oscillation), so that the system can start observing the depth of landmarks. If you only do rotations, it is not possible to observe the depth of landmarks and to observe translations (or stabilize translations with the IMU). * You should not remain static too long at the beginning (say more than 10-20 seconds), to prevent the system from falsely starting to converge because of noise observation. This is also true in the middle of a run but less critic (say more than 2-3 minutes). We are working on that. * Troubleshooting: * If you are not getting any display when starting an offline sequence, make sure that you compiled the display modules (qdisplay and/or gdhe), and that they are enabled in the command line (--disp-2d=1 or --disp-3d=1) == Configuring the demo == There are two configuration files : * {{{--config-setup=data/setup.cfg}}} that contains everything related to the hardware setup (camera, IMU, calibrations, hardware noise specs, ...). If none specified, the default file is data/setup.cfg in live mode, and /setup.cfg in replay mode. * {{{--config-estimation=data/estimation.cfg}}} that contains everything related to estimation and Slam (size of map, number of landmarks, strategies, ...). If none specified, the default file is data/estimation.cfg. You can use the '@' character to refer to when specifying the location of the config file to use : {{{--config-estimation=@/estimation.cfg}}} The parameters are documented in the main.hpp file, with the definition of the data structures !ConfigSetup and !ConfigEstimation. === Offline processing === If you already have some data and you want to process them with RT-SLAM: * convert the images to a sequence named with the format "image_%07d.png" with a corresponding date file "image_%07d.time" that contains the timestamp in seconds as a float number. /!\ Reminder: the images must come from a global shutter camera! See requirements section above for explanations. * if applicable, convert the IMU data to a file named MTI.log with the image files (be careful to the end-of-line sequence convention, should be '\n'), with the format "[10](, , , , , , , , , )". The date has the same format than for images, and must have the same origin (but you can shift it with the option IMU_TIMESTAMP_CORRECTION in setup.cfg). The gyrometers values corresponding to the rotation velocity around the specified axis, in rad/s. The magnetometers values are ignored for now. There must be several data before the first image, where the system is static, to allow RT-SLAM to initialize the orientation by measuring g (1-2 seconds are advised to reduce noise). The file sdate.log must contain the date when the system starts moving (there should be images starting from this moment). * don't forget to change the file setup.cfg for the camera calibration, IMU noise specs, transformation camera<->IMU etc, and to use the right robot model with option --robot. === Sample demo === You can [[attachment:2011-02-15_inertial-high-dyn.zip|download here]] a sample image and IMU sequence to quickly test RT-SLAM offline. Give the path where the archive has been unzipped with the option --data-path. Note that this sequence was meant to illustrate the high dynamic movements that the system can withstand thanks to IMU-vision fusion, so it is recommended to enable the use of IMU data with --robot=1 option. It will still diverge at the very end because it goes beyond the IMU limits (300 deg/s). As an example you can use a command similar to this one to run the demo (from $JAFAR_DIR/build/modules/rtslam): {{{ demo_suite/x86_64-linux-gnu/demo_slam --disp-2d=1 --disp-3d=1 --robot=1 --camera=1 --map=1 --render-all=0 --replay=1 --rand-seed=1 --pause=1 --config-setup=@/setup.cfg --config-estimation=@/estimation.cfg --data-path=/home/cyril/2011-02-15_inertial-high-dyn/ }}} == Running the demo == {{{#!highlight sh cd $JAFAR_DIR/build/modules/rtslam demo_suite//demo_slam }}} ||||||||||Control options|| ||'''Name'''||'''Default'''||'''Possible values'''||'''Description'''||'''Requirements'''|| ||--disp-2d||0||0/1 (disabled/enabled)|| use 2D display||Qt installed|| ||--disp-3d||0||0/1 (disabled/enabled)|| use 3D display||Gdhe installed|| ||--render-all||0||0/1 (disabled/enabled)||force rendering display for all frames||--replay 1|| ||--replay||0||0/1/2/3 (offline/online/online no slam/offline replay)|| replay mode: offline runs from offline data ; online runs from live sensors ; online no slam disables slam processing for pure data dumps ; offline replay replays exactly an online run selecting the same data.<
> /!\ Don't run online (--replay 0/2) with --data-path pointing to a data set you want to keep, because it will start by cleaning it! || set --data-path to path with dumped data|| ||--dump||0||0/1 (disabled/enabled)||dump the images (with --replay=0) or the rendered views (with --replay=1)||set --data-path to free directory|| ||--export||0||0/1/2 (Off/Socket/Poster)||export the pose of the robot|| || ||--log||0||0/1/ (disabled/enabled to rtslam.log/enabled to )||log result output in text file in --data-path|| || ||--rand-seed||0||0/1/n (generate new one/replay uses the saved one/use this value)||random seed to use|| || ||--pause||0||0/n (disabled/pause after frame n)||pause after each data integrated, waiting for space key pressed in 2d display window or console if no 2d display|| --replay 1/3|| ||--data-path|| . || ||path to store or read data || || ||--config-setup||data/setup.cfg|| ||use this file for setup configuration|| || ||--config-estimation||data/estimation.cfg|| ||use this file for estimation configuration|| || ||--verbose||0||0/1/2/3/4/5 (Off/Trace/Warning/Debug/VerboseDebug/VeryVerboseDebug) || verbosity level of debug output || compiled in debug mode|| ||--help|| || || prints help || || ||--usage|| || || prints usage || || ||||||||||Slam options|| ||--robot||0||0/1/1n (constant velocity/inertial/order n constant)||motion model used for the prediction step|| || ||--camera||10|| || =sum(2^id) defines which camera are used (for instance 1 for left camera, 2 for right, 3 for both left and right cameras), (0=Raw/1=Rectify/2=Stereo) defines how cameras are used, only Raw being implemented right now|| || || --map||0||0/1/2 (visual odometry/global/local)|| type of map used, ie how landmark memory is managed: visual odometry forgets landmarks soon after they are lost, use it for long ranges ; global keeps landmarks in the whole environment to allow loop closure, use it in small ranges ; local is optimized for submaps, but not fully implemented yet|| || ||--odom||0||0/1 (disabled/enabled)|| use odometry data from genom poster or log file as observations in the filter || || ||--gps||0||0/1/2/3 (disabled/position/position+velocity/position+orientation)|| use absolute sensor such as GPS or MoCap from genom poster or log file as observations in the filter || || ||--heading|| 0.0 || || initial absolute heading, required for use of GPS (overrides the value in setup.cfg) || || ||||||||||Raw data options|| ||--simu||0||0/||use the ad hoc simulator and specify which trajectory and which environment to use, does not work for inertial|| || ||--trigger||0||0/1/2 (internal/external with shutter control/external without shutter control)|| configure the trigger used for the cameras|| || ||--freq|| 60.0 || || cameras frequency || || ||--shutter|| 0.0 || || shutter time, 0.0 meaning automatic || || ||--cams-filter|| 100 ||
|| only use one image every
, with shift of for each camera || --replay=1/3 || For instance to start a simple SLAM process : {{{#!highlight sh demo_suite//demo_slam --disp-2d=1 --disp-3d=1 --camera=10 }}} == Controlling the demo == When doing a replay, you can control how slam is running by interacting with the 2D viewer: * '''Press "[space]"''' to switch between play and pause mode. * '''Press "N"''' to process one image when in pause mode. * '''Press "F"''' to switch between render-all mode and fast mode. * '''Press "Q"''' to quit. * '''Click on an observation''' to get textual and visual information about the observation and associated landmark. * '''Click on an empty part of the image''' to get information about the sensor and the associated robot. == Interpreting the demo == Color code: * '''magenta:''' !InitialParametrization landmarks that were observed this frame * '''dark red:''' !InitialParametrization landmarks that were not observed this frame * '''cyan:''' !ConvergedParametrization landmarks that were observed this frame * '''dark blue:''' !ConvergedParametrization landmarks that were not observed this frame Another way to remember the color code: * '''bright colors''' represent observed landmarks * '''dark colors''' represent non observed landmarks * '''reddish hues''' represent !InitialParametrization landmarks (like inverse depth for points) * '''bluish hues''' represent !ConvergedParametrization landmarks (like euclidean for points) 2D landmark representation: * '''a colored + cross:''' the predicted position of the landmark * '''a colored ellipse:''' the 3-sigma prediction uncertainty * '''an orange x cross:''' the measured position of the landmark * '''a colored label:''' the id of the landmark, followed by the matching score (/100) Reasons for a landmark not being observed: * outside of the sensor frame (you can still see them in the 3D view) * matching failed (you can see the matching score that is below the threshold) * the observation was inconsistent (the measure is out of the uncertainty ellipse) * too many landmarks are in the sensor frame and we didn't try to observe some of them (no matching score is present). In that case the landmark is regardless drawn with the "observed" color, because it wasn't due to a problem with the landmark. == Contributions == If you are willing to submit some contribution, you can either: * commit, create a patch with the command "git format-patch -M origin/master" and send it to me, so that I can apply it to the main tree with your credits. * commit, and send me the address of your git repository if it is externally accessible so that I can pull from it.