Skip to content

Commit

Permalink
Revert "Merge pull request #219 from rbrusu/master"
Browse files Browse the repository at this point in the history
This reverts commit ef88940, reversing
changes made to ab9a891.
  • Loading branch information
rbrusu committed Aug 15, 2013
1 parent ef88940 commit a8dc588
Show file tree
Hide file tree
Showing 20 changed files with 73 additions and 132 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ endif()

if(MSVC)
SET(CMAKE_COMPILER_IS_MSVC 1)
add_definitions ("-DBOOST_ALL_NO_LIB -D_SCL_SECURE_NO_WARNINGS -D_CRT_SECURE_NO_WARNINGS -DNOMINMAX /bigobj")
add_definitions ("-DBOOST_ALL_NO_LIB -D_SCL_SECURE_NO_WARNINGS -D_CRT_SECURE_NO_WARNINGS -DNOMINMAX")
if("${CMAKE_CXX_FLAGS}" STREQUAL "")
SET(CMAKE_CXX_FLAGS "/bigobj /EHsc /fp:precise /wd4800 /wd4521 /wd4251 /wd4275 /wd4305 /wd4355 ${SSE_FLAGS}")

Expand Down
10 changes: 3 additions & 7 deletions apps/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -66,10 +66,8 @@ if(build)
PCL_ADD_EXECUTABLE(pcl_pcd_organized_multi_plane_segmentation ${SUBSYS_NAME} src/pcd_organized_multi_plane_segmentation.cpp)
target_link_libraries(pcl_pcd_organized_multi_plane_segmentation pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_features)

if (QHULL_FOUND)
PCL_ADD_EXECUTABLE(pcl_pcd_select_object_plane ${SUBSYS_NAME} src/pcd_select_object_plane.cpp)
target_link_libraries(pcl_pcd_select_object_plane pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_features pcl_surface)
endif()
PCL_ADD_EXECUTABLE(pcl_pcd_select_object_plane ${SUBSYS_NAME} src/pcd_select_object_plane.cpp)
target_link_libraries(pcl_pcd_select_object_plane pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_features pcl_surface)

# PCL_ADD_EXECUTABLE(pcl_convolve ${SUBSYS_NAME} src/convolve.cpp)
# target_link_libraries(pcl_convolve pcl_common pcl_io pcl_visualization)
Expand Down Expand Up @@ -231,9 +229,7 @@ if(build)
add_subdirectory(3d_rec_framework)
add_subdirectory(modeler)
add_subdirectory(cloud_composer)
if(OPENNI_FOUND)
add_subdirectory(in_hand_scanner)
endif(OPENNI_FOUND)
add_subdirectory(in_hand_scanner)
add_subdirectory(point_cloud_editor)
if(FZAPI_FOUND)
add_subdirectory(optronic_viewer)
Expand Down
2 changes: 2 additions & 0 deletions apps/point_cloud_editor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,8 @@ IF(BUILD)
pcl_filters
)

SET(CMAKE_CXX_FLAGS "-Wno-invalid-offsetof -Wno-extra-tokens")

PCL_ADD_INCLUDES(${SUBSYS_NAME} ${SUBSYS_NAME} ${INCS})
PCL_MAKE_PKGCONFIG(${EXE_NAME} ${SUBSYS_NAME} "${SUBSYS_DESC}" "" "" "" "" "")

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
#ifndef SELECT_2D_TOOL_H_
#define SELECT_2D_TOOL_H_

#include <qgl.h>
#include <GL/gl.h>
#include <pcl/apps/point_cloud_editor/toolInterface.h>
#include <pcl/apps/point_cloud_editor/localTypes.h>

Expand Down
5 changes: 4 additions & 1 deletion apps/point_cloud_editor/src/cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,10 @@
/// @author Yue Li and Matthew Hielsberg

#include <algorithm>
#include <qgl.h>
//#include <QtOpenGL>
//#include <qgl.h>
#include <GL/gl.h>
#include <GL/glu.h>
#include <pcl/apps/point_cloud_editor/cloud.h>
#include <pcl/apps/point_cloud_editor/selection.h>
#include <pcl/apps/point_cloud_editor/localTypes.h>
Expand Down
2 changes: 1 addition & 1 deletion apps/point_cloud_editor/src/cloudEditorWidget.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
#include <QFileDialog>
#include <QMessageBox>
#include <QMouseEvent>
#include <qgl.h>
#include <GL/gl.h>
#include <GL/glu.h>
#include <pcl/filters/filter.h>
#include <pcl/io/pcd_io.h>
Expand Down
2 changes: 1 addition & 1 deletion apps/point_cloud_editor/src/select1DTool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
/// @author Yue Li and Matthew Hielsberg

#include <algorithm>
#include <qgl.h>
#include <GL/gl.h>
#include <pcl/apps/point_cloud_editor/select1DTool.h>
#include <pcl/apps/point_cloud_editor/cloud.h>
#include <pcl/apps/point_cloud_editor/selection.h>
Expand Down
8 changes: 0 additions & 8 deletions common/include/pcl/common/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -160,14 +160,6 @@ namespace pcl
template <typename PointT> inline void
getMinMax (const PointT &histogram, int len, float &min_p, float &max_p);

/** \brief Calculate the area of a polygon given a point cloud that defines the polygon
* \param polygon point cloud that contains those vertices that comprises the polygon. Vertices are stored in counterclockwise.
* \return the polygon area
* \ingroup common
*/
template<typename PointT> inline float
calculatePolygonArea (const pcl::PointCloud<PointT> &polygon);

/** \brief Get the minimum and maximum values on a point histogram
* \param cloud the cloud containing multi-dimensional histograms
* \param idx point index representing the histogram that we need to compute min/max for
Expand Down
21 changes: 0 additions & 21 deletions common/include/pcl/common/impl/common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -386,26 +386,5 @@ pcl::getMinMax (const PointT &histogram, int len, float &min_p, float &max_p)
}
}

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointT> inline float
pcl::calculatePolygonArea (const pcl::PointCloud<PointT> &polygon)
{
float area = 0.0f;
int num_points = polygon.size ();
int j = 0;
Eigen::Vector3f va,vb,res;

res(0) = res(1) = res(2) = 0.0f;
for (int i = 0; i < num_points; ++i)
{
j = (i + 1) % num_points;
va = polygon[i].getVector3fMap ();
vb = polygon[j].getVector3fMap ();
res += va.cross (vb);
}
area = res.norm ();
return (area*0.5);
}

#endif //#ifndef PCL_COMMON_IMPL_H_

11 changes: 5 additions & 6 deletions doc/tutorials/content/alignment_prerejective.rst
Original file line number Diff line number Diff line change
Expand Up @@ -92,14 +92,13 @@ After you have made the executable, you can run it like so::

After a few seconds, you will see a visualization and a terminal output similar to::
| -0.003 -0.972 0.235 |
R = | -0.993 -0.026 -0.119 |
| 0.122 -0.233 -0.965 |
| 0.027 -0.977 0.212 |
R = | -0.991 -0.055 -0.124 |
| 0.133 -0.207 -0.969 |

t = < 0.095, -0.022, 0.069 >

Inliers: 890/3432
t = < 0.084, -0.024, 0.069 >

Inliers: 912/3432

The visualization window should look something like the below figures. The scene is shown with green color, and the aligned object model is shown with blue color. Note the high number of non-visible object points.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ main (int argc, char **argv)
// Estimate normals for scene
pcl::console::print_highlight ("Estimating scene normals...\n");
pcl::NormalEstimationOMP<PointNT,PointNT> nest;
nest.setRadiusSearch (0.01);
nest.setRadiusSearch (0.015);
nest.setInputCloud (scene);
nest.compute (*scene);

Expand Down
1 change: 0 additions & 1 deletion examples/segmentation/example_supervoxels.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
#include <vtkImageReader2.h>
#include <vtkImageData.h>
#include <vtkImageFlip.h>
#include <vtkPolyLine.h>

// Types
typedef pcl::PointXYZRGBA PointT;
Expand Down
4 changes: 2 additions & 2 deletions keypoints/include/pcl/keypoints/impl/harris_3d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
#include <pcl/features/integral_image_normal.h>
#include <pcl/common/time.h>
#include <pcl/common/centroid.h>
#ifdef __SSE__
#ifdef HAVE_SSE_EXTENSIONS
#include <xmmintrin.h>
#endif

Expand Down Expand Up @@ -99,7 +99,7 @@ pcl::HarrisKeypoint3D<PointInT, PointOutT, NormalT>::calculateNormalCovar (const
unsigned count = 0;
// indices 0 1 2 3 4 5 6 7
// coefficients: xx xy xz ?? yx yy yz ??
#ifdef __SSE__
#ifdef HAVE_SSE_EXTENSIONS
// accumulator for xx, xy, xz
__m128 vec1 = _mm_setzero_ps();
// accumulator for yy, yz, zz
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -184,13 +184,12 @@ pcl::SampleConsensusPrerejective<PointSource, PointTarget, FeatureT>::computeTra
correspondence_rejector_poly_->setInputSource (input_);
correspondence_rejector_poly_->setInputTarget (target_);
correspondence_rejector_poly_->setCardinality (nr_samples_);
std::vector<bool> accepted (input_->size (), false); // Indices of sampled points that passed prerejection
int num_rejections = 0; // For debugging

// Initialize results
final_transformation_ = guess;
inliers_.clear ();
float lowest_error = std::numeric_limits<float>::max ();
float highest_inlier_fraction = inlier_fraction_;
converged_ = false;

// Temporaries
Expand All @@ -203,12 +202,11 @@ pcl::SampleConsensusPrerejective<PointSource, PointTarget, FeatureT>::computeTra
{
getFitness (inliers, error);
inlier_fraction = static_cast<float> (inliers.size ()) / static_cast<float> (input_->size ());
error /= static_cast<float> (inliers.size ());

if (inlier_fraction >= inlier_fraction_ && error < lowest_error)
if (inlier_fraction > highest_inlier_fraction)
{
inliers_ = inliers;
lowest_error = error;
highest_inlier_fraction = inlier_fraction;
converged_ = true;
}
}
Expand All @@ -222,25 +220,12 @@ pcl::SampleConsensusPrerejective<PointSource, PointTarget, FeatureT>::computeTra

// Draw nr_samples_ random samples
selectSamples (*input_, nr_samples_, sample_indices);

// Check if all sampled points already been accepted
bool samples_accepted = true;
for (unsigned int j = 0; j < sample_indices.size(); ++j) {
if (!accepted[j]) {
samples_accepted = false;
break;
}
}

// All points have already been accepted, avoid
if (samples_accepted)
continue;

// Find corresponding features in the target cloud
findSimilarFeatures (*input_features_, sample_indices, corresponding_indices);

// Apply prerejection
if (!correspondence_rejector_poly_->thresholdPolygon (sample_indices, corresponding_indices)) {
if (!correspondence_rejector_poly_->thresholdPolygon (sample_indices, corresponding_indices)){
++num_rejections;
continue;
}
Expand All @@ -256,25 +241,19 @@ pcl::SampleConsensusPrerejective<PointSource, PointTarget, FeatureT>::computeTra

// Transform the input and compute the error (uses input_ and final_transformation_)
getFitness (inliers, error);

// Restore previous result
final_transformation_ = final_transformation_prev;

// If the new fit is better, update results
inlier_fraction = static_cast<float> (inliers.size ()) / static_cast<float> (input_->size ());

if (inlier_fraction >= inlier_fraction_) {
// Mark the sampled points accepted
for (int j = 0; j < nr_samples_; ++j)
accepted[j] = true;

// Update result if pose hypothesis is better
if (error < lowest_error) {
inliers_ = inliers;
lowest_error = error;
converged_ = true;
final_transformation_ = transformation_;
}
const float inlier_fraction = static_cast<float> (inliers.size ()) / static_cast<float> (input_->size ());
if (inlier_fraction > highest_inlier_fraction)
{
inliers_ = inliers;
highest_inlier_fraction = inlier_fraction;
converged_ = true;
}
else
{
// Restore previous result
final_transformation_ = final_transformation_prev;
}
}

Expand Down Expand Up @@ -303,7 +282,7 @@ pcl::SampleConsensusPrerejective<PointSource, PointTarget, FeatureT>::getFitness
PointCloudSource input_transformed;
input_transformed.resize (input_->size ());
transformPointCloud (*input_, input_transformed, final_transformation_);

// For each point in the source dataset
for (size_t i = 0; i < input_transformed.points.size (); ++i)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,9 @@ namespace pcl
* constraints, as also implemented in the class
* \ref registration::CorrespondenceRejectorPoly "CorrespondenceRejectorPoly".
*
* In order to robustly align partial/occluded models, this routine performs
* fit error evaluation using only inliers, i.e. points closer than a
* Euclidean threshold, which is specifiable using \ref setInlierFraction().
* In order to robustly align partial/occluded models, this routine does not
* try to minimize the fit error, but instead tries to maximize the inlier rate,
* above a threshold specifiable using \ref setInlierFraction().
*
* The amount of prerejection or "greedyness" of the algorithm can be specified
* using \ref setSimilarityThreshold() in [0,1[, where a value of 0 means disabled,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -298,7 +298,6 @@ pcl::RegionGrowing<PointT, NormalT>::extract (std::vector <pcl::PointIndices>& c
}

clusters_ = std::vector<pcl::PointIndices> (clusters.begin (), cluster_iter_input);
clusters.resize(clusters_.size());

deinitCompute ();
}
Expand Down
3 changes: 0 additions & 3 deletions visualization/include/pcl/visualization/interactor_style.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,6 @@ class vtkLegendScaleActor;
class vtkScalarBarActor;
class vtkPNGWriter;
class vtkWindowToImageFilter;
class vtkPointPicker;

namespace pcl
{
Expand Down Expand Up @@ -233,8 +232,6 @@ namespace pcl
vtkSmartPointer<vtkPNGWriter> snapshot_writer_;
/** \brief Internal window to image filter. Needed by \a snapshot_writer_. */
vtkSmartPointer<vtkWindowToImageFilter> wif_;
/** \brief Stores the point picker when switching to an area picker. */
vtkSmartPointer<vtkPointPicker> point_picker_;

boost::signals2::signal<void (const pcl::visualization::MouseEvent&)> mouse_signal_;
boost::signals2::signal<void (const pcl::visualization::KeyboardEvent&)> keyboard_signal_;
Expand Down
16 changes: 0 additions & 16 deletions visualization/src/interactor_style.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,6 @@
#include <vtkProperty.h>
#include <vtkPointData.h>
#include <vtkAssemblyPath.h>
#include <vtkAbstractPicker.h>
#include <vtkPointPicker.h>
#include <vtkAreaPicker.h>

#include <pcl/visualization/vtk/vtkVertexBufferObjectMapper.h>

Expand Down Expand Up @@ -809,19 +806,6 @@ pcl::visualization::PCLVisualizerInteractorStyle::OnKeyDown ()
case 'x' : case 'X' :
{
CurrentMode = (CurrentMode == ORIENT_MODE) ? SELECT_MODE : ORIENT_MODE;
if (CurrentMode == SELECT_MODE)
{
// Save the point picker
point_picker_ = static_cast<vtkPointPicker*> (Interactor->GetPicker ());
// Switch for an area picker
vtkSmartPointer<vtkAreaPicker> area_picker = vtkSmartPointer<vtkAreaPicker>::New ();
Interactor->SetPicker (area_picker);
}
else
{
// Restore point picker
Interactor->SetPicker (point_picker_);
}
break;
}

Expand Down
23 changes: 12 additions & 11 deletions visualization/src/pcl_visualizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,7 @@ pcl::visualization::PCLVisualizer::PCLVisualizer (const std::string &name, const
update_fps_->decimated = false;
ren->AddActor (txt);


// Create a RendererWindow
win_ = vtkSmartPointer<vtkRenderWindow>::New ();
win_->SetWindowName (name.c_str ());
Expand Down Expand Up @@ -255,9 +256,8 @@ pcl::visualization::PCLVisualizer::createInteractor ()
timer_id_ = interactor_->CreateRepeatingTimer (5000L);
#endif

// Set a simple PointPicker
vtkSmartPointer<vtkPointPicker> pp = vtkSmartPointer<vtkPointPicker>::New ();
pp->SetTolerance (pp->GetTolerance () * 2);
// Set an AreaPicker
vtkSmartPointer<vtkAreaPicker> pp = vtkSmartPointer<vtkAreaPicker>::New ();
interactor_->SetPicker (pp);

exit_main_loop_timer_callback_ = vtkSmartPointer<ExitMainLoopTimerCallback>::New ();
Expand Down Expand Up @@ -297,10 +297,12 @@ pcl::visualization::PCLVisualizer::setupInteractor (
timer_id_ = iren->CreateRepeatingTimer (5000L);
#endif

// Set a simple PointPicker
vtkSmartPointer<vtkPointPicker> pp = vtkSmartPointer<vtkPointPicker>::New ();
pp->SetTolerance (pp->GetTolerance () * 2);
iren->SetPicker (pp);
// Set an AreaPicker
if (interactor_ != NULL)
{
vtkSmartPointer<vtkAreaPicker> pp = vtkSmartPointer<vtkAreaPicker>::New ();
interactor_->SetPicker (pp);
}

exit_main_loop_timer_callback_ = vtkSmartPointer<ExitMainLoopTimerCallback>::New ();
exit_main_loop_timer_callback_->pcl_visualizer = this;
Expand Down Expand Up @@ -341,10 +343,9 @@ pcl::visualization::PCLVisualizer::setupInteractor (
timer_id_ = iren->CreateRepeatingTimer (5000L);
#endif

// Set a simple PointPicker
// vtkSmartPointer<vtkPointPicker> pp = vtkSmartPointer<vtkPointPicker>::New ();
// pp->SetTolerance (pp->GetTolerance () * 2);
// iren->SetPicker (pp);
// Set an AreaPicker
// vtkSmartPointer<vtkAreaPicker> pp = vtkSmartPointer<vtkAreaPicker>::New ();
// interactor_->SetPicker (pp);

exit_main_loop_timer_callback_ = vtkSmartPointer<ExitMainLoopTimerCallback>::New ();
exit_main_loop_timer_callback_->pcl_visualizer = this;
Expand Down
Loading

0 comments on commit a8dc588

Please sign in to comment.