README.md
Go to the documentation of this file.
00001 rc_cloud_accumulator
00002 ====================
00003 
00004 This project demonstrates how to create a registered point cloud map
00005 using the roboception rc_visard with the [ROS driver](http://wiki.ros.org/rc_visard_driver).
00006 
00007 
00008 What it does
00009 ------------
00010 The rc_cloud_accumulator ROS node subscribes to the following topics of the *rc_visard_driver*
00011 
00012  - `/stereo/points2`
00013  - `/pose`
00014  - `/trajectory`
00015 
00016 The received information is stored, such that a registered point cloud can be
00017 computed and saved to disk. For performance reasons, the point clouds are preprocessed.
00018 See *Filters* below for more details.
00019 
00020 The node displays point clouds received on the first topic using the live pose (/pose)
00021 to position them in the global coordinate frame.
00022 
00023 The trajectory topic can be used to feed an optimized trajectory from the SLAM module
00024 into the *rc_cloud_accumulator*. The easiest way is to start the *rc_visard_driver*
00025 with the parameter *autopublish_trajectory* set to `True` and call the service 
00026 */rc_visard_driver/get_trajectory*. The *rc_visard_driver* will then send the
00027 trajectory on */trajectory*.
00028 
00029 Building
00030 --------
00031 
00032 Compilation follows the standard build process of ROS. You can also do the regular cmake cycle:
00033 
00034 - `source /opt/ros/`*your-ROS-Distro*`/setup.bash`
00035 - `mkdir build`
00036 - `cd build`
00037 - `cmake ..`
00038 - `make -j3`
00039 
00040 To build a debian package replace the last two steps with
00041 
00042 - `cmake -DCATKIN_BUILD_BINARY_PACKAGE="1" -DCMAKE_INSTALL_PREFIX="/opt/ros/${ROS_DISTRO}" -DCMAKE_PREFIX_PATH="/opt/ros/${ROS_DISTRO}" -DCMAKE_BUILD_TYPE=Release ..`
00043 - `make -j3 package`
00044 - Install the package with `sudo dpkg -i rc_cloud_accumulator*.deb`
00045 
00046 Running
00047 -------
00048 
00049 After starting the *rc_visard_driver*, execute
00050 
00051 `rosrun rc_cloud_accumulator rc_cloud_accumulator`
00052 
00053 Example with parameter:
00054 
00055 `rosrun rc_cloud_accumulator rc_cloud_accumulator _voxel_grid_size_display:=0.01`
00056 
00057 Known Bugs
00058 ----------
00059 
00060 - You have to change the view (mouse drag or mouse wheel) before the clouds are displayed
00061 - On Ubuntu trusty, the window can only be closed terminating the console application (e.g., Ctrl-C).
00062   Probably fixed (see [this issue](https://github.com/PointCloudLibrary/pcl/issues/172)) on newer versions.
00063 
00064 Point Cloud Filters
00065 -------
00066 
00067 For performance reasons the point clouds are by default filtered in several stages.
00068 The filters are parameterized via ROS parameters.
00069 All filters can be turned off using appropriate settings.
00070 See *ROS Parameters* for a detailed description of the parameters.
00071 
00072 When a point cloud is received, the points will first be filtered by
00073 a minimum and maximum distance along the optical axis.
00074 
00075 A copy of the resulting cloud will be stored in memory for later use.
00076 
00077 The point cloud will then be transformed to the global coordinate
00078 frame and merged into the currently displayed point cloud. To keep the
00079 visualization snappy, the displayed point cloud will be filtered with a voxel
00080 grid using the parameter *voxel_grid_size_display*.
00081 
00082 When the save_cloud service (see below) is used, the stored point clouds will
00083 be merged (considering pose updates received in the meantime). The result will
00084 also be be filtered with a voxel grid using the parameter
00085 *voxel_grid_size_save*.
00086 
00087 
00088 ROS Services
00089 ------------
00090 
00091 The *rc_cloud_accumulator* provides the following services
00092 
00093  - `/rc_cloud_accumulator/toggle_pause`: Toggle processing of received data
00094  - `/rc_cloud_accumulator/save_cloud`: Register stored clouds and save them to disk.
00095    The stored cloud will be displayed, but updated with the next incoming point cloud.
00096    To keep the display of the stored result pause before saving.
00097 
00098 ROS Parameters
00099 --------------
00100 
00101   - `voxel_grid_size_display` (default = 0.05m): Downsampling grid size of the point cloud in the live display. Set to zero or below to turn off.
00102   - `voxel_grid_size_save` (default = 0.01m): Downsampling grid size of the point cloud when saving to disk. Set to zero or below to turn off.
00103   - `minimum_distance` (default =  0.0m): Omit points closer to the rc_visard
00104   - `maximum_distance` (default = 10.0m): Omit points closer farther from the rc_visard. Set below minimum to turn distance filtering off.
00105   - `output_filename` (default = "cloud.pcd")
00106   - `start_paused` (default = false)
00107   - `keep_high_resolution` (default = true): Set to false to save memory and processing time.
00108     The original point clouds will not be stored and the point cloud saved to
00109     disk will be the one that is displayed. Only the voxel grid filter for the
00110     *live* pose will be applied. Also, correction of the point cloud poses via
00111     the SLAM trajectory is not possible in this mode.
00112 
00113 


rc_cloud_accumulator
Author(s): Felix Endres
autogenerated on Thu Jun 6 2019 19:56:20