Skip to content

Commit

Permalink
* tagging PCL 1.6.0-rc1
Browse files Browse the repository at this point in the history
git-svn-id: svn+ssh://svn.pointclouds.org/pcl/tags/pcl-1.6.0rc1@6230 a9d63959-f2ad-4865-b262-bf0e56cfafb6
  • Loading branch information
rbrusu committed Jul 7, 2012
1 parent 0a44de3 commit ea8fe31
Show file tree
Hide file tree
Showing 117 changed files with 6,272 additions and 153 deletions.
2 changes: 1 addition & 1 deletion apps/include/pcl/apps/organized_segmentation_demo.h
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ class OrganizedSegmentationDemo : public QMainWindow
QTimer *vis_timer_;
pcl::PointCloud<PointT> prev_cloud_;
pcl::PointCloud<pcl::Normal> prev_normals_;
std::vector<pcl::PlanarRegion<PointT> > prev_regions_;
std::vector<pcl::PlanarRegion<PointT>, Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > > prev_regions_;
float* prev_distance_map_;

pcl::PointCloud<PointT>::CloudVectorType prev_clusters_;
Expand Down
2 changes: 1 addition & 1 deletion apps/src/ni_linemod.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -316,7 +316,7 @@ class NILinemod
mps_.setInputCloud (search_.getInputCloud ());

// Use one of the overloaded segmentAndRefine calls to get all the information that we want out
vector<PlanarRegion<PointT> > regions;
vector<PlanarRegion<PointT>, Eigen::aligned_allocator<PlanarRegion<PointT> > > regions;
vector<ModelCoefficients> model_coefficients;
vector<PointIndices> inlier_indices;
PointCloud<Label>::Ptr labels (new PointCloud<Label>);
Expand Down
2 changes: 1 addition & 1 deletion apps/src/openni_organized_multi_plane_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ class OpenNIOrganizedMultiPlaneSegmentation
mps.setAngularThreshold (0.017453 * 2.0); //3 degrees
mps.setDistanceThreshold (0.02); //2cm

std::vector<pcl::PlanarRegion<PointT> > regions;
std::vector<pcl::PlanarRegion<PointT>, Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > > regions;
pcl::PointCloud<PointT>::Ptr contour (new pcl::PointCloud<PointT>);
size_t prev_models_size = 0;
char name[1024];
Expand Down
4 changes: 2 additions & 2 deletions apps/src/organized_segmentation_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
#include <pcl/surface/convex_hull.h>

void
displayPlanarRegions (std::vector<pcl::PlanarRegion<PointT> > &regions,
displayPlanarRegions (std::vector<pcl::PlanarRegion<PointT>, Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > > &regions,
boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer)
{
char name[1024];
Expand Down Expand Up @@ -289,7 +289,7 @@ OrganizedSegmentationDemo::cloud_cb (const CloudConstPtr& cloud)

// Segment Planes
double mps_start = pcl::getTime ();
std::vector<pcl::PlanarRegion<PointT> > regions;
std::vector<pcl::PlanarRegion<PointT>, Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > > regions;
std::vector<pcl::ModelCoefficients> model_coefficients;
std::vector<pcl::PointIndices> inlier_indices;
pcl::PointCloud<pcl::Label>::Ptr labels (new pcl::PointCloud<pcl::Label>);
Expand Down
2 changes: 1 addition & 1 deletion apps/src/pcd_organized_multi_plane_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ class PCDOrganizedMultiPlaneSegmentation
mps.setDistanceThreshold (0.03); //2cm
mps.setRefinementComparator (refinement_compare);

std::vector<pcl::PlanarRegion<PointT> > regions;
std::vector<pcl::PlanarRegion<PointT>, Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > > regions;
typename pcl::PointCloud<PointT>::Ptr contour (new pcl::PointCloud<PointT>);
typename pcl::PointCloud<PointT>::Ptr approx_contour (new pcl::PointCloud<PointT>);
char name[1024];
Expand Down
7 changes: 7 additions & 0 deletions doc/tutorials/content/basic_structures.rst
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,13 @@ PointCloud is a C++ class which contains the following data fields:
much more efficient, thus speeding up the computation and lowering the
costs of certain algorithms in PCL.

.. note::

An **projectable point cloud** dataset is the name given to point clouds
that have a correlation according to a pinhole camera model between the (u,v) index
of a point in the organized point cloud and the actual 3D values. This correlation can be
expressed in it's easiest form as: u = f*x/z and v = f*y/z

Examples::

cloud.width = 640; // there are 640 points per line
Expand Down
2 changes: 1 addition & 1 deletion doc/tutorials/content/cluster_extraction.rst
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ The Code
--------

First, download the dataset `table_scene_lms400.pcd
<http://dev.pointclouds.org/attachments/download/157/table_scene_lms400.pcd>`_ and save it somewhere to disk.
<http://svn.pointclouds.org/data/tutorials/table_scene_lms400.pcd>`_ and save it somewhere to disk.

Then, create a file, let's say, ``cluster_extraction.cpp`` in your favorite
editor, and place the following inside it:
Expand Down
4 changes: 2 additions & 2 deletions doc/tutorials/content/compiling_pcl_windows.rst
Original file line number Diff line number Diff line change
Expand Up @@ -206,11 +206,11 @@ Let's check whether CMake did actually find the needed third party dependencies

- **Qt** :

It is highly recommended to install Qt to the default path suggested by the installer. You need then to define an
It is highly recommended to install Qt to the default path suggested by the installer. You need then to define an
environment variable named **QTDIR** to point to Qt installation path (e.g. `C:\\Qt\\4.8.0`). Also, you need to
append the bin folder to the **PATH** environment variable. Once you modify the environment variables, you need to
restart CMake and click "Configure" again. If Qt is not found, you need at least to fill **QT_QMAKE_EXECUTABLE**
CMake entry with the path of `qmake.exe` (e.g. C:\\Qt\\4.8.0\\bin\qmake.exe), then click "Configure".
CMake entry with the path of `qmake.exe` (e.g. C:\\Qt\\4.8.0\\bin\\qmake.exe), then click "Configure".

- **VTK** :

Expand Down
4 changes: 2 additions & 2 deletions doc/tutorials/content/convex_hull_2d.rst
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ for a set of points supported by a plane.

The following video shows a demonstration of the code given below on the test
dataset `table_scene_mug_stereo_textured.pcd
<http://dev.pointclouds.org/attachments/download/158/table_scene_mug_stereo_textured.pcd>`_.
<http://svn.pointclouds.org/data/tutorials/table_scene_mug_stereo_textured.pcd>`_.

.. raw:: html

Expand All @@ -18,7 +18,7 @@ The code
--------

First, download the dataset `table_scene_mug_stereo_textured.pcd
<http://dev.pointclouds.org/attachments/download/158/table_scene_mug_stereo_textured.pcd>`_
<http://svn.pointclouds.org/data/tutorials/table_scene_mug_stereo_textured.pcd>`_
and save it somewhere to disk.

Then, create a file, let's say, ``convex_hull_2d.cpp`` in your favorite
Expand Down
2 changes: 1 addition & 1 deletion doc/tutorials/content/cylinder_segmentation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ The code
--------

First, download the dataset `table_scene_mug_stereo_textured.pcd
<http://dev.pointclouds.org/attachments/download/158/table_scene_mug_stereo_textured.pcd>`_
<http://svn.pointclouds.org/data/tutorials/table_scene_mug_stereo_textured.pcd>`_
and save it somewhere to disk.

Then, create a file, let's say, ``cylinder_segmentation.cpp`` in your favorite
Expand Down
2 changes: 1 addition & 1 deletion doc/tutorials/content/extract_indices.rst
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ The code
--------

First, download the dataset `table_scene_lms400.pcd
<http://dev.pointclouds.org/attachments/download/157/table_scene_lms400.pcd>`_
<http://svn.pointclouds.org/data/tutorials/table_scene_lms400.pcd>`_
and save it somewhere to disk.

Then, create a file, let's say, ``extract_indices.cpp`` in your favorite
Expand Down
11 changes: 6 additions & 5 deletions doc/tutorials/content/hull_2d.rst
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ The code
--------

First, download the dataset `table_scene_mug_stereo_textured.pcd
<http://dev.pointclouds.org/attachments/download/158/table_scene_mug_stereo_textured.pcd>`_
<http://svn.pointclouds.org/data/tutorials/table_scene_mug_stereo_textured.pcd>`_
and save it somewhere to disk.

Then, create a file, let's say, ``concave_hull_2d.cpp`` or
Expand All @@ -23,10 +23,11 @@ Then, create a file, let's say, ``concave_hull_2d.cpp`` or

.. note::

This tutorial is written for assuming you are looking for the **CONCAVE**
hull. If you would like the **CONVEX** hull for a plane model, just replace
concave with convex at EVERY point in this tutorial, including the source
file, file names and the CMakeLists.txt file.
This tutorial is written for assuming you are looking for the **CONCAVE** hull.
If you would like the **CONVEX** hull for a plane model, just replace concave
with convex at EVERY point in this tutorial, including the source file, file
names and the CMakeLists.txt file. You will also need to comment out
setAlpha(), as this is not applicable to convex hulls.

The explanation
---------------
Expand Down
Binary file added doc/tutorials/content/images/3dtree.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/bunny.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/ex1.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/features_bunny.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/features_normal.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/features_small.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/filters_small.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/form_0.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/form_1.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/histogram.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/io_small.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/kdtree_mug.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/kdtree_small.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/keypoints_small.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/normals.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/octree_bunny.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/octree_bunny2.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/octree_small.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/pcs.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/plane_model_seg.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/range_image.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/s1-6.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added doc/tutorials/content/images/scans.png
Binary file added doc/tutorials/content/images/shapes.jpg
Binary file added doc/tutorials/content/images/surface_hull.png
Binary file added doc/tutorials/content/images/surface_meshing.png
Binary file added doc/tutorials/content/images/surface_small.png
9 changes: 5 additions & 4 deletions doc/tutorials/content/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ Table of contents
* :ref:`kdtree_tutorial`
* :ref:`octree_tutorial`
* :ref:`range_images`
* :ref:`recognition_tutorial`
* :ref:`registration_tutorial`
* :ref:`sample_consensus`
* :ref:`segmentation_tutorial`
Expand Down Expand Up @@ -55,7 +56,7 @@ Basic Usage
* :ref:`using_pcl_pcl_config`

====== ======
|mi_1| Title: **Using PCL in own project**
|mi_1| Title: **Using PCL in your own project**

Author: *Nizar Sallem*

Expand Down Expand Up @@ -130,7 +131,7 @@ Basic Usage
* :ref:`installing_homebrew`

====== ======
|mi_5| Title: **Installing on Mac OS X using Homebrew**
|mi_6| Title: **Installing on Mac OS X using Homebrew**

Author: *Geoffrey Biggs*

Expand All @@ -139,7 +140,7 @@ Basic Usage
This tutorial explains how to install the Point Cloud Library on Mac OS X using Homebrew. Both direct installation and compiling PCL from source are explained.
====== ======

.. |mi_5| image:: images/macosx_logo.png
.. |mi_6| image:: images/macosx_logo.png
:height: 100px

.. _advanced_usage:
Expand Down Expand Up @@ -616,7 +617,7 @@ Registration

Author: *Dirk Holz, Radu B. Rusu, Jochen Sprickerhof*

Compatibility: PCL 1.2
Compatibility: > PCL 1.5

In this document, we describe the point cloud registration API and its modules: the estimation and rejection of point correspondences, and the estimation of rigid transformations.
====== ======
Expand Down
13 changes: 3 additions & 10 deletions doc/tutorials/content/installing_homebrew.rst
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ which parts of PCL are installed.

The PCL formula is currently in development. It will be submitted to
Homebrew shortly. Until then, you can download it from
`PCL.RB <http://dev.pointclouds.org/attachments/download/604/pcl.rb>`_. To prepare it,
`PCL.RB <http://dev.pointclouds.org/attachments/download/876/pcl.rb>`_. To prepare it,
follow these steps:


Expand All @@ -51,18 +51,11 @@ To install using the formula, execute the following command::

$ brew install pcl

.. note::

The current version of PCL (1.3.1) properly supports the visualization
module for Mac OS X. However if you do want to disable it, you can run::

$ brew install pcl --novis

You can specify options to control which parts of PCL are installed. For
example, to disable the Python bindings and Segmentation, and enable the
example, to disable the Python bindings and visualisation, and enable the
documentation, execute the following command::

$ brew install pcl --nopython --nosegmentation --doc
$ brew install pcl --nopython --novis --doc

For a full list of the available options, see the formula's help::

Expand Down
128 changes: 61 additions & 67 deletions doc/tutorials/content/normal_estimation_using_integral_images.rst
Original file line number Diff line number Diff line change
Expand Up @@ -10,92 +10,71 @@ cloud using integral images.
The code
--------

First, create a file, let's say, ``normal_estimation.cpp`` in your favorite
First, create a file, let's say, ``normal_estimation_using_integral_images.cpp`` in your favorite
editor, and place the following inside it:

.. code-block:: cpp
:linenos:
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/features/integral_image_normal.h>
int
main (int argc, char** argv)
{
pcl::PointCloud<pcl::PointXYZ> cloud;
// ... fill point cloud...
cloud.width = 640;
cloud.height = 480;
cloud.points.resize (cloud.width * cloud.height);
for (int ri = 0; ri < cloud.height; ++ri)
{
for (int ci = 0; ci < cloud.width; ++ci)
{
const float depth = 0.2f*static_cast<float> (rand ()) / static_cast<float>(RAND_MAX) + 1.0f;
cloud.points (ri, ci).x = (ci - 320) * depth;
cloud.points (ri, ci).y = (ri - 240) * depth;
cloud.points (ri, ci).z = depth;
}
}
// Estimate normals
pcl::IntegralImageNormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
pcl::PointCloud<pcl::Normal> normals;
ne.setNormalEstimationMethod (ne.AVERAGE_DEPTH_CHANGE);
ne.setMaxDepthChangeFactor(0.02f);
ne.setNormalSmoothingSize(10.0f);
ne.setInputCloud(cloud);
ne.compute(normals);
return (0);
}
#include <pcl/io/io.h>
#include <pcl/io/pcd_io.h>
#include <pcl/features/integral_image_normal.h>
#include <pcl/visualization/cloud_viewer.h>
int
main ()
{
// load point cloud
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::io::loadPCDFile ("table_scene_mug_stereo_textured.pcd", *cloud);
// estimate normals
pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
pcl::IntegralImageNormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
ne.setMaxDepthChangeFactor(0.02f);
ne.setNormalSmoothingSize(10.0f);
ne.setInputCloud(cloud);
ne.compute(*normals);
// visualize normals
pcl::visualization::PCLVisualizer viewer("PCL Viewer");
viewer.setBackgroundColor (0.0, 0.0, 0.5);
viewer.addPointCloudNormals<pcl::PointXYZ,pcl::Normal>(cloud, normals);
while (!viewer.wasStopped ())
{
viewer.spinOnce ();
}
return 0;
}
The explanation
---------------

Now, let's break down the code piece by piece. In the first part we create a
random point cloud for which we estimate the normals:
Now, let's break down the code piece by piece. In the first part we load a
point cloud from a file:

.. code-block:: cpp
pcl::PointCloud<pcl::PointXYZ> cloud;
// ... fill point cloud...
cloud.width = 640;
cloud.height = 480;
cloud.points.resize (cloud.width*cloud.height);
for (int ri = 0; ri < cloud.height; ++ri)
{
for (int ci = 0; ci < cloud.width; ++ci)
{
const float depth = 0.2f*static_cast<float> (rand ()) / static_cast<float>(RAND_MAX) + 1.0f;
cloud.points (ri, ci).x = (ci - 320) * depth;
cloud.points (ri, ci).y = (ri - 240) * depth;
cloud.points (ri, ci).z = depth;
}
}
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
pcl::io::loadPCDFile ("table_scene_mug_stereo_textured.pcd", *cloud);
In the second part we create an object for the normal estimation and compute
the normals:

.. code-block:: cpp
// Estimate normals
pcl::IntegralImageNormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
// estimate normals
pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
pcl::PointCloud<pcl::Normal> normals;
ne.setNormalEstimationMethod (ne.AVERAGE_DEPTH_CHANGE);
ne.setMaxDepthChangeFactor(0.02f);
ne.setNormalSmoothingSize(10.0f);
ne.setInputCloud(cloud);
ne.compute(normals);
pcl::IntegralImageNormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
ne.setMaxDepthChangeFactor(0.02f);
ne.setNormalSmoothingSize(10.0f);
ne.setInputCloud(cloud);
ne.compute(*normals);
The following normal estimation methods are available:

Expand All @@ -116,3 +95,18 @@ cross-product between these two gradients. The AVERAGE_DEPTH_CHANGE mode
creates only a single integral image and computes the normals from the average
depth changes.

In the last part we visualize the point cloud and the corresponding normals:

.. code-block:: cpp
// visualize normals
pcl::visualization::PCLVisualizer viewer("PCL Viewer");
viewer.setBackgroundColor (0.0, 0.0, 0.5);
viewer.addPointCloudNormals<pcl::PointXYZ,pcl::Normal>(cloud, normals);
while (!viewer.wasStopped ())
{
viewer.spinOnce ();
}
Loading

0 comments on commit ea8fe31

Please sign in to comment.