From 6999dce4766427fe4806cbb9124ae8642b1c193b Mon Sep 17 00:00:00 2001 From: "luz.paz" Date: Thu, 15 Feb 2018 17:50:15 -0500 Subject: [PATCH 1/5] Misc. typos (cont. 2) Found via `codespell -q 3 -I ../pcl-whitelist.txt --skip="./surface/include/pcl/surface/3rdparty,./surface/src/3rdparty,./recognition/include/pcl/recognition/3rdparty"` Whitelist: ``` ang childs everytime iff indeces isnt ith lod metre metres mitre nd normaly ot resizeable te vertexes ``` --- 2d/include/pcl/2d/edge.h | 2 +- 2d/include/pcl/2d/impl/morphology.hpp | 6 ++--- CHANGES.md | 22 +++++++++---------- PCLConfig.cmake.in | 2 +- .../feature_wrapper/normal_estimator.h | 2 +- .../pipeline/local_recognizer.h | 2 +- .../pcl/apps/cloud_composer/item_inspector.h | 2 +- apps/cloud_composer/src/commands.cpp | 2 +- apps/cloud_composer/src/items/cloud_item.cpp | 2 +- apps/cloud_composer/src/items/fpfh_item.cpp | 2 +- .../src/point_selectors/selection_event.cpp | 2 +- .../pcl/apps/dominant_plane_segmentation.h | 2 +- apps/include/pcl/apps/pcd_video_player.h | 2 +- .../pcl/apps/render_views_tesselated_sphere.h | 12 +++++----- .../pcl/apps/optronic_viewer/filter_window.h | 2 +- .../pcl/apps/point_cloud_editor/cloud.h | 2 +- .../apps/point_cloud_editor/commandQueue.h | 4 ++-- .../point_cloud_editor/transformCommand.h | 2 +- apps/point_cloud_editor/src/common.cpp | 2 +- .../src/pcd_video_player/pcd_video_player.cpp | 4 ++-- apps/src/render_views_tesselated_sphere.cpp | 2 +- cmake/CMakeParseArguments.cmake | 2 +- cmake/pcl_cpack.cmake | 2 +- cmake/pcl_targets.cmake | 10 ++++----- cmake/pcl_utils.cmake | 2 +- .../include/pcl/common/bivariate_polynomial.h | 4 ++-- common/include/pcl/common/centroid.h | 18 +++++++-------- common/include/pcl/common/generate.h | 10 ++++----- common/include/pcl/common/impl/eigen.hpp | 2 +- .../include/pcl/common/impl/intersections.hpp | 2 +- common/include/pcl/common/intersections.h | 2 +- common/include/pcl/common/io.h | 2 +- common/include/pcl/common/spring.h | 4 ++-- common/include/pcl/common/time.h | 2 +- common/include/pcl/common/time_trigger.h | 2 +- common/include/pcl/console/parse.h | 12 +++++----- common/include/pcl/exceptions.h | 4 ++-- common/include/pcl/impl/point_types.hpp | 2 +- common/include/pcl/point_representation.h | 4 ++-- common/include/pcl/point_traits.h | 2 +- common/include/pcl/range_image/range_image.h | 8 +++---- .../pcl/range_image/range_image_planar.h | 4 ++-- .../pcl/range_image/range_image_spherical.h | 2 +- common/src/fft/kiss_fft.c | 2 +- common/src/poses_from_matches.cpp | 4 ++-- cuda/common/include/pcl/cuda/common/eigen.h | 2 +- cuda/common/include/pcl/cuda/cutil.h | 6 ++--- .../include/pcl/cuda/cutil_inline_drvapi.h | 4 ++-- .../include/pcl/cuda/cutil_inline_runtime.h | 4 ++-- cuda/nn/organized_neighbor_search.hpp | 2 +- cuda/segmentation/src/mssegmentation.cpp | 4 ++-- features/src/range_image_border_extractor.cpp | 2 +- filters/include/pcl/filters/convolution.h | 4 ++-- filters/include/pcl/filters/convolution_3d.h | 4 ++-- .../pcl/filters/model_outlier_removal.h | 2 +- .../pcl/filters/voxel_grid_covariance.h | 2 +- filters/src/passthrough.cpp | 2 +- gpu/surface/src/internal.h | 2 +- io/include/pcl/compression/color_coding.h | 8 +++---- .../impl/organized_pointcloud_compression.hpp | 4 ++-- .../octree_pointcloud_compression.h | 4 ++-- .../organized_pointcloud_compression.h | 2 +- io/include/pcl/compression/point_coding.h | 4 ++-- io/include/pcl/io/ascii_io.h | 2 +- io/include/pcl/io/fotonic_grabber.h | 2 +- io/include/pcl/io/grabber.h | 2 +- io/include/pcl/io/impl/lzf_image_io.hpp | 4 ++-- io/include/pcl/io/oni_grabber.h | 2 +- io/include/pcl/io/openni2/openni2_device.h | 6 ++--- .../pcl/io/openni_camera/openni_driver.h | 2 +- io/include/pcl/io/pcd_io.h | 2 +- io/include/pcl/io/ply/byte_order.h | 2 +- io/include/pcl/io/ply_io.h | 6 ++--- io/include/pcl/io/real_sense_grabber.h | 2 +- io/src/ifs_io.cpp | 2 +- io/src/openni2_grabber.cpp | 2 +- io/src/openni_grabber.cpp | 2 +- io/src/pcd_grabber.cpp | 4 ++-- io/src/ply/ply_parser.cpp | 2 +- io/src/real_sense_grabber.cpp | 2 +- io/tools/openni_pcd_recorder.cpp | 2 +- ml/include/pcl/ml/impl/kmeans.hpp | 2 +- .../ml/regression_variance_stats_estimator.h | 2 +- ml/src/kmeans.cpp | 2 +- ml/src/svm.cpp | 2 +- .../ground_based_people_detection_app.h | 2 +- .../pcl/people/impl/head_based_subcluster.hpp | 2 +- .../pcl/recognition/color_gradient_modality.h | 6 ++--- .../include/pcl/recognition/crh_alignment.h | 2 +- .../include/pcl/recognition/hv/hv_go.h | 2 +- .../impl/hv/greedy_verification.hpp | 2 +- .../pcl/recognition/impl/hv/hv_papazov.hpp | 4 ++-- .../recognition/impl/linemod/line_rgbd.hpp | 2 +- .../pcl/recognition/implicit_shape_model.h | 8 +++---- .../pcl/recognition/linemod/line_rgbd.h | 4 ++-- .../pcl/recognition/quantizable_modality.h | 2 +- .../ransac_based/voxel_structure.h | 2 +- .../pcl/recognition/surface_normal_modality.h | 4 ++-- .../transformation_estimation_lm.h | 2 +- ...ation_estimation_point_to_plane_weighted.h | 2 +- .../pcl/sample_consensus/impl/lmeds.hpp | 2 +- .../pcl/sample_consensus/impl/mlesac.hpp | 2 +- .../pcl/sample_consensus/impl/msac.hpp | 2 +- .../pcl/sample_consensus/impl/ransac.hpp | 2 +- .../pcl/sample_consensus/impl/rmsac.hpp | 2 +- .../pcl/sample_consensus/impl/rransac.hpp | 2 +- .../sample_consensus/impl/sac_model_cone.hpp | 8 +++---- .../impl/sac_model_cylinder.hpp | 8 +++---- .../include/pcl/sample_consensus/sac_model.h | 2 +- .../pcl/segmentation/cpc_segmentation.h | 2 +- .../pcl/segmentation/grabcut_segmentation.h | 8 +++---- .../segmentation/impl/cpc_segmentation.hpp | 10 ++++----- .../segmentation/impl/lccp_segmentation.hpp | 8 +++---- ...nized_connected_component_segmentation.hpp | 2 +- .../organized_multi_plane_segmentation.hpp | 2 +- .../segmentation/impl/region_growing_rgb.hpp | 4 ++-- .../pcl/segmentation/lccp_segmentation.h | 6 ++--- ...ganized_connected_component_segmentation.h | 2 +- .../pcl/segmentation/sac_segmentation.h | 4 ++-- .../pcl/segmentation/supervoxel_clustering.h | 4 ++-- segmentation/src/supervoxel_clustering.cpp | 4 ++-- simulation/src/model.cpp | 2 +- simulation/src/range_likelihood.cpp | 6 ++--- simulation/tools/README_about_tools | 2 +- simulation/tools/sim_test_simple.cpp | 6 ++--- simulation/tools/sim_viewer.cpp | 4 ++-- simulation/tools/simulation_io.cpp | 2 +- stereo/include/pcl/stereo/stereo_matching.h | 8 +++---- .../3rdparty/opennurbs/opennurbs_bezier.h | 2 +- .../pcl/surface/bilateral_upsampling.h | 2 +- surface/include/pcl/surface/grid_projection.h | 2 +- surface/include/pcl/surface/mls.h | 8 +++---- .../3rdparty/opennurbs/opennurbs_archive.cpp | 2 +- surface/src/on_nurbs/sequential_fitter.cpp | 4 ++-- test/common/test_eigen.cpp | 2 +- test/filters/test_filters.cpp | 2 +- test/io/test_io.cpp | 6 ++--- test/io/test_octree_compression.cpp | 2 +- test/kdtree/test_kdtree.cpp | 2 +- test/registration/test_registration.cpp | 2 +- test/search/test_search.cpp | 2 +- test/surface/test_gp3.cpp | 2 +- tools/mesh2pcd.cpp | 2 +- tools/pcl_video.cpp | 4 ++-- tools/png2pcd.cpp | 2 +- tools/virtual_scanner.cpp | 2 +- tracking/include/pcl/tracking/pyramidal_klt.h | 10 ++++----- .../pcl/visualization/interactor_style.h | 2 +- .../include/pcl/visualization/pcl_plotter.h | 2 +- .../pcl/visualization/pcl_visualizer.h | 2 +- .../point_cloud_geometry_handlers.h | 4 ++-- .../pcl/visualization/point_picking_event.h | 2 +- .../visualization/simple_buffer_visualizer.h | 8 +++---- .../vtk/vtkRenderWindowInteractorFix.mm | 2 +- .../visualization/vtk/vtkVertexBufferObject.h | 2 +- visualization/src/interactor_style.cpp | 2 +- visualization/src/pcl_painter2D.cpp | 2 +- visualization/src/pcl_visualizer.cpp | 2 +- visualization/tools/openni_image.cpp | 2 +- 159 files changed, 280 insertions(+), 280 deletions(-) diff --git a/2d/include/pcl/2d/edge.h b/2d/include/pcl/2d/edge.h index 78b1af36108..c1ad4cf0596 100644 --- a/2d/include/pcl/2d/edge.h +++ b/2d/include/pcl/2d/edge.h @@ -76,7 +76,7 @@ namespace pcl /** \brief This function suppresses the edges which don't form a local maximum * in the edge direction. * \param[in] edges point cloud containing all the edges - * \param[out] maxima point cloud containing the non-max supressed edges + * \param[out] maxima point cloud containing the non-max suppressed edges * \param[in] tLow */ void diff --git a/2d/include/pcl/2d/impl/morphology.hpp b/2d/include/pcl/2d/impl/morphology.hpp index 6528eed9a81..c2d82671c12 100644 --- a/2d/include/pcl/2d/impl/morphology.hpp +++ b/2d/include/pcl/2d/impl/morphology.hpp @@ -77,7 +77,7 @@ pcl::Morphology::erosionBinary (pcl::PointCloud &output) { continue; } - // If one of the elements of the kernel and image dont match, + // If one of the elements of the kernel and image don't match, // the output image is 0. So, move to the next point. if ((*input_)(j + l - kernel_width / 2, i + k - kernel_height / 2).intensity != 1) { @@ -192,7 +192,7 @@ pcl::Morphology::erosionGray (pcl::PointCloud &output) { continue; } - // If one of the elements of the kernel and image dont match, + // If one of the elements of the kernel and image don't match, // the output image is 0. So, move to the next point. if ((*input_)(j + l - kernel_width / 2, i + k - kernel_height / 2).intensity < min || min == -1) { @@ -236,7 +236,7 @@ pcl::Morphology::dilationGray (pcl::PointCloud &output) { continue; } - // If one of the elements of the kernel and image dont match, + // If one of the elements of the kernel and image don't match, // the output image is 0. So, move to the next point. if ((*input_)(j + l - kernel_width / 2, i + k - kernel_height / 2).intensity > max || max == -1) { diff --git a/CHANGES.md b/CHANGES.md index 44b1b12152e..cdb916c502b 100644 --- a/CHANGES.md +++ b/CHANGES.md @@ -384,7 +384,7 @@ * Removed unnecessary mutex locking in `TimeTrigger::registerCallback` [[#1087]](https://github.com/PointCloudLibrary/pcl/pull/1087) * Updated PCL exception types to have nothrow copy constructor and copy - assigment operator + assignment operator [[#1119]](https://github.com/PointCloudLibrary/pcl/pull/1119) * Fixed a bug with `PCA` not triggering recomputation when input indices are changed @@ -625,7 +625,7 @@ * Added a new `MetaRegistration` class that allows to register a stream of clouds where each cloud is aligned to the conglomerate of all previous clouds [[#1426]](https://github.com/PointCloudLibrary/pcl/pull/1426) -* Fixed segmentation fault occuring in `CorrespondenceRejectorSurfaceNormal` +* Fixed segmentation fault occurring in `CorrespondenceRejectorSurfaceNormal` [[#1536]](https://github.com/PointCloudLibrary/pcl/pull/1536) * Use aligned allocator in vectors of MatchingCandidate [[#1552]](https://github.com/PointCloudLibrary/pcl/pull/1552) @@ -1381,13 +1381,13 @@ The most notable overall changes are: * Added a setDimension function to concave hull, so users can specify desired dimensionality of the resulting hull. If no dimension is specified, one will be automatically determined. * Fixed bug #692 - MovingLeastSquares indices issues * Added curve fitting and trimming of surfaces to examples/surface/example_nurbs_fitting_surface.cpp -* Added iterative fitting routines for curve fitting surface::on_nurbs::Triangulation - added convertion functions for nurbs curve to line-polygon - added convertion functions for nurbs surface and curve to PolyMesh +* Added iterative fitting routines for curve fitting surface::on_nurbs::Triangulation - added conversion functions for nurbs curve to line-polygon - added conversion functions for nurbs surface and curve to PolyMesh * Added flag to enable/disable usage of UmfPack for fast solving of sparse systems of equations - added triangulation functions to convert ON_NurbsSurface to pcl::PolygonMesh * Added bug fix in ConcaveHull, thanks to summer.icecream * Added marching cubes using RBF and Hoppe SDF * Pushed new functions that perform texture-mapping on meshes. * Fix: issue #646 (vtk_smoothing not copied) -* Added new functionalities to TextureMapping: Find occlusions based on raytracing in octrees, UV mapping based on Texture resolution and camera focal lenght. +* Added new functionalities to TextureMapping: Find occlusions based on raytracing in octrees, UV mapping based on Texture resolution and camera focal length. * Relaxing dimensionality check threshold on concave_hull, so that 3D hulls should no longer be calculated on 2D input. * Added poisson filter @@ -1629,7 +1629,7 @@ The most notable overall changes are: * added a normal space sampling filter * fixed bug #433: `pcl::CropBox` doesn't update `width` and `height` member of output point cloud * fixed bug #423 `CropBox` + `VoxelGrid` filters, order changes behaviour (using openni grabber) -* add `CropHull` filter for filtering points based on a 2D or 3D convex or concave hull. The ray-polygon intersection test is used, which relys on closed polygons/surfaces +* add `CropHull` filter for filtering points based on a 2D or 3D convex or concave hull. The ray-polygon intersection test is used, which relies on closed polygons/surfaces * added clipper3D interface and a draft plane_clipper3D implementation * removed spurious old `ColorFilter` class (obsolete, and it was never implemented - the skeleton was just lurking around) * better Doxygen documentation to `PassThrough`, `VoxelGrid` and `Filter` @@ -1683,7 +1683,7 @@ The most notable overall changes are: ### `lipcl_keypoints` * added refine method for `Harris3D` corner detector -* rewrote big parts of the NARF keypoint extraction. Hopfully fixing some stability issues. Unfortunately still pretty slow for high resolution point clouds. +* rewrote big parts of the NARF keypoint extraction. Hopefully fixing some stability issues. Unfortunately still pretty slow for high resolution point clouds. * fixed bug #461 (SIFT Keypoint result cloud fields not complete); cleaned up the line-wrapping in the error/warning messages ### `libpcl_surface` @@ -1827,7 +1827,7 @@ pcl::OrganizedDataIndex -> pcl::search::OrganizedNeighbor * fixed a bug in `getRejectedQueryIndices`, wrong output when order of correspondences have been changed * moved `getRejectedQueryIndices` to pcl/common/correspondence.h * added more doxygen documentation to the registration components -* marked all `getRemainingCorrespondences`-functions as DEPRECATED, we sould replace them with purely stateless version outside the class body +* marked all `getRemainingCorrespondences`-functions as DEPRECATED, we should replace them with purely stateless version outside the class body * fixed a const missing in `PolynomialCalculationsT` (#388 - thanks Julian!) * add `PCL_DEPRECATED` macro, closes #354. * added `PointXYZHSV` type and the conversions for it @@ -1913,7 +1913,7 @@ pcl::OrganizedDataIndex -> pcl::search::OrganizedNeighbor * fixed bug in getRejectedQueryIndices, wrong output when order of correspondences have been changed * moved getRejectedQueryIndices to pcl/common/correspondence.h * added more doxygen documentation to the registration components - * marked all "getRemainingCorrespondences"-functions as DEPRECATED, we sould replace them with purely stateless version outside the class body + * marked all "getRemainingCorrespondences"-functions as DEPRECATED, we should replace them with purely stateless version outside the class body * Update: remove ciminpack dependency and rely on eigen for LM * Fixed a bug in ICP-NL by modifying `WarpPointRigid` to preserve the value of the 4th coordinate when warping; Re-enabled missing unit tests for ICP and ICP-NL * Added point-to-plane ICP @@ -2306,7 +2306,7 @@ The version numbers below belong to the *perception_pcl* stack in ROS, which coo * added a new generalized field value filter (_pcl::ConditionalRemoval_) * cleaned up normal estimation through integral images * PCL rift.hpp and point_types.hpp fixed for Windows/VS2010 - * fixed all _is_dense_ occurances + * fixed all _is_dense_ occurrences * *unmanged all _Eigen3::_ calls to _Eigen::_* * changed all _!isnan_ checks to _isfinite_ in order to catch INF/-INF values * added vtk_io tools for saving VTK data from _PolygonMesh_ structures @@ -2341,7 +2341,7 @@ The version numbers below belong to the *perception_pcl* stack in ROS, which coo * Added Correspondence as a structure representing correspondences/matches (similar to OpenCV's DMatch) containing query and match indices as well as the distance between them respective points. * Added _CorrespondenceEstimation_ for determining closest point correspondence, feature correspondences and reciprocal point correspondences. * Added _CorrespondenceRejection_ and derivations for rejecting correspondences, e.g., based on distance, removing 1-to-n correspondences, RANSAC-based outlier removal (+transformation estimation). - * Further splitted up registration.h and added transformation estimation classes, e.g., for estimating rigid transformation using SVD. + * Further split up registration.h and added transformation estimation classes, e.g., for estimating rigid transformation using SVD. * Added ```sensor_msgs::Image image; pcl::toROSMsg (cloud, image);```See tools/convert_pcd_image.cpp for a sample. * Added a new point type, _PointWithScale_, to store the output of _SIFTKeypoint_ detection. * Fixed a minor bug in the error-checking in _SIFTKeypoint::setScales(...)_ @@ -2395,7 +2395,7 @@ The version numbers below belong to the *perception_pcl* stack in ROS, which coo * Added RSD (Radius Signature Descriptor) feature. * Updated the entire PCL tree to use FLANN as a default _KdTree_ * Optimized the _KdTreeFLANN::radiusSearch_ so it doesn't do any memory allocation if the indices and distances vectors passed in are pre-allocated to the point cloud size. - * Changed _KdTree::radiusSearch_ method signature to return int (number of neighbors found) intead of bool + * Changed _KdTree::radiusSearch_ method signature to return int (number of neighbors found) instead of bool * added new _pcl::View_ class that holds a _PointCloud_, an _Image_, and a _CameraInfo_ message (r34575) * Moving the _Surface_ reconstruction framework to the new structure (r34547) * Moving the _Segmentation_ framework to the new structure (r34546) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index 6350a87b7f7..ffe27543b9d 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -265,7 +265,7 @@ endmacro(find_glew) # |--> _lib is optional ==> disable it (thanks to the guardians) # | and warn # `--> _lib is required -# |--> component is required explicitely ==> error +# |--> component is required explicitly ==> error # `--> component is induced ==> warn and remove it # from the list diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/normal_estimator.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/normal_estimator.h index a5229cdaff8..4399dfb0748 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/normal_estimator.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/normal_estimator.h @@ -140,7 +140,7 @@ namespace pcl if (out->points.size () == 0) { - PCL_WARN("NORMAL estimator: Cloud has no points after voxel grid, wont be able to compute normals!\n"); + PCL_WARN("NORMAL estimator: Cloud has no points after voxel grid, won't be able to compute normals!\n"); return; } diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/local_recognizer.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/local_recognizer.h index b882dd47508..eeb6b65ea37 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/local_recognizer.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/local_recognizer.h @@ -334,7 +334,7 @@ namespace pcl /** * \brief Initializes the FLANN structure from the provided source - * It does training for the models that havent been trained yet + * It does training for the models that haven't been trained yet */ void diff --git a/apps/cloud_composer/include/pcl/apps/cloud_composer/item_inspector.h b/apps/cloud_composer/include/pcl/apps/cloud_composer/item_inspector.h index c9fb09433b8..f4527474bfd 100644 --- a/apps/cloud_composer/include/pcl/apps/cloud_composer/item_inspector.h +++ b/apps/cloud_composer/include/pcl/apps/cloud_composer/item_inspector.h @@ -74,7 +74,7 @@ namespace pcl /** \brief Stores the state of the current tree view in item_treestate_map_ */ void storeTreeState (); - /** \brief Retores the state of \param model 's view from item_treestate_map_ */ + /** \brief Restores the state of \param model 's view from item_treestate_map_ */ void restoreTreeState (); /** \brief Removes the extra tabs the item might have */ diff --git a/apps/cloud_composer/src/commands.cpp b/apps/cloud_composer/src/commands.cpp index ecd6d015095..a61274ada37 100644 --- a/apps/cloud_composer/src/commands.cpp +++ b/apps/cloud_composer/src/commands.cpp @@ -582,7 +582,7 @@ pcl::cloud_composer::MergeCloudCommand::redo () { qDebug () << "Redo in MergeCloudCommand "; last_was_undo_ = false; - //There is only one output_pair, but thats ok + //There is only one output_pair, but that's ok foreach (OutputPair output_pair, output_data_) { //Replace the input with the output for this pair diff --git a/apps/cloud_composer/src/items/cloud_item.cpp b/apps/cloud_composer/src/items/cloud_item.cpp index d73a13556ab..b77641ba6df 100644 --- a/apps/cloud_composer/src/items/cloud_item.cpp +++ b/apps/cloud_composer/src/items/cloud_item.cpp @@ -90,7 +90,7 @@ pcl::cloud_composer::CloudItem::removeFromView (boost::shared_ptr (new pcl::visualization::PCLPlotter); diff --git a/apps/cloud_composer/src/point_selectors/selection_event.cpp b/apps/cloud_composer/src/point_selectors/selection_event.cpp index 4f80fda6c89..4f1e295c047 100644 --- a/apps/cloud_composer/src/point_selectors/selection_event.cpp +++ b/apps/cloud_composer/src/point_selectors/selection_event.cpp @@ -11,7 +11,7 @@ pcl::cloud_composer::SelectionEvent::~SelectionEvent () void pcl::cloud_composer::SelectionEvent::findIndicesInItem (CloudItem* cloud_item, pcl::PointIndices::Ptr indices) { - // WE DONT NEED TO DO THIS SEARCH BECAUSE WE HAVE A 1-1 CORRESPONDENCE VTK TO PCL + // WE DON'T NEED TO DO THIS SEARCH BECAUSE WE HAVE A 1-1 CORRESPONDENCE VTK TO PCL // THIS IS ONLY THE CASE FOR CLOUDS WITH NO NANs //Go through every point in the selected data set and find the matching index in this cloud //pcl::search::KdTree::Ptr search = cloud_item->data (KD_TREE_SEARCH).value ::Ptr> (); diff --git a/apps/include/pcl/apps/dominant_plane_segmentation.h b/apps/include/pcl/apps/dominant_plane_segmentation.h index cdb273071e6..a996bed687d 100644 --- a/apps/include/pcl/apps/dominant_plane_segmentation.h +++ b/apps/include/pcl/apps/dominant_plane_segmentation.h @@ -230,7 +230,7 @@ namespace pcl return 1; else { - //compute distance and check aginst max_dist + //compute distance and check against max_dist if ((p1.getVector3fMap () - p2.getVector3fMap ()).norm () <= max_dist) { p2.intensity = p1.intensity; diff --git a/apps/include/pcl/apps/pcd_video_player.h b/apps/include/pcl/apps/pcd_video_player.h index 3d395c876de..59afa0b557a 100644 --- a/apps/include/pcl/apps/pcd_video_player.h +++ b/apps/include/pcl/apps/pcd_video_player.h @@ -128,7 +128,7 @@ class PCDVideoPlayer : public QMainWindow /** \brief Indicate that the timeoutSlot needs to reload the pointcloud */ bool cloud_modified_; - /** \brief Indicate that files should play continiously */ + /** \brief Indicate that files should play continuously */ bool play_mode_; /** \brief In play mode only update if speed_counter_ == speed_value */ unsigned int speed_counter_; diff --git a/apps/include/pcl/apps/render_views_tesselated_sphere.h b/apps/include/pcl/apps/render_views_tesselated_sphere.h index 04a18d55759..a311046e935 100644 --- a/apps/include/pcl/apps/render_views_tesselated_sphere.h +++ b/apps/include/pcl/apps/render_views_tesselated_sphere.h @@ -17,7 +17,7 @@ namespace pcl { namespace apps { - /** \brief @b Class to render synthetic views of a 3D mesh using a tesselated sphere + /** \brief @b Class to render synthetic views of a 3D mesh using a tessellated sphere * NOTE: This class should replace renderViewTesselatedSphere from pcl::visualization. * Some extensions are planned in the near future to this class like removal of duplicated views for * symmetrical objects, generation of RGB synthetic clouds when RGB available on mesh, etc. @@ -70,7 +70,7 @@ namespace pcl campos_constraints_func_ = bb; } - /* \brief Indicates wether to generate organized or unorganized data + /* \brief Indicates whether to generate organized or unorganized data * \param b organized/unorganized */ void @@ -88,7 +88,7 @@ namespace pcl resolution_ = res; } - /* \brief Wether to use the vertices or triangle centers of the tesselated sphere + /* \brief Whether to use the vertices or triangle centers of the tessellated sphere * \param use true indicates to use vertices, false triangle centers */ @@ -107,7 +107,7 @@ namespace pcl radius_sphere_ = radius; } - /* \brief Wether to compute the entropies (level of occlusions for each view) + /* \brief Whether to compute the entropies (level of occlusions for each view) * \param compute true to compute entropies, false otherwise */ void @@ -116,8 +116,8 @@ namespace pcl compute_entropy_ = compute; } - /* \brief How many times the icosahedron should be tesselated. Results in more or less camera positions and generated views. - * \param level amount of tesselation + /* \brief How many times the icosahedron should be tessellated. Results in more or less camera positions and generated views. + * \param level amount of tessellation */ void setTesselationLevel (int level) diff --git a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/filter_window.h b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/filter_window.h index da53c2ad107..d92618c017a 100644 --- a/apps/optronic_viewer/include/pcl/apps/optronic_viewer/filter_window.h +++ b/apps/optronic_viewer/include/pcl/apps/optronic_viewer/filter_window.h @@ -81,7 +81,7 @@ namespace pcl virtual void next (); Q_SIGNALS: - /** \brief Ommitted when a filter is created. */ + /** \brief Omitted when a filter is created. */ void filterCreated (); protected: diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloud.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloud.h index 9e895e30ce6..f1a2ce1b01a 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloud.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloud.h @@ -409,7 +409,7 @@ class Cloud : public Statistics /// The internal representation of the cloud Cloud3D cloud_; - /// @breif A weak pointer pointing to the selection object. + /// @brief A weak pointer pointing to the selection object. /// @details This implementation uses the weak pointer to allow for a lazy /// update of the cloud if the selection object is destroyed. boost::weak_ptr selection_wk_ptr_; diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/commandQueue.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/commandQueue.h index 199afadc162..19bb990f511 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/commandQueue.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/commandQueue.h @@ -53,7 +53,7 @@ class CommandQueue { public: - /// @brief Defaut Constructor + /// @brief Default Constructor /// @details Creates a command queue object and makes its depth limit /// be the default value. CommandQueue (); @@ -81,7 +81,7 @@ class CommandQueue void undo (); - /// @breif Changes the command history limit. + /// @brief Changes the command history limit. /// @details If the passed size is smaller than the current size then the /// oldest commands are removed (their undo functions are not called). /// @param size The new maximum number of commands that may exist in this diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/transformCommand.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/transformCommand.h index 12e65612644..b710250abe2 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/transformCommand.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/transformCommand.h @@ -34,7 +34,7 @@ /// /// @file transformCommand.h -/// @details a TransfromCommand object provides transformation and undo +/// @details a TransformCommand object provides transformation and undo /// functionalities. // XXX - transformation of what? /// @author Yue Li and Matthew Hielsberg diff --git a/apps/point_cloud_editor/src/common.cpp b/apps/point_cloud_editor/src/common.cpp index 7289664b037..08c79e677e8 100644 --- a/apps/point_cloud_editor/src/common.cpp +++ b/apps/point_cloud_editor/src/common.cpp @@ -70,7 +70,7 @@ multMatrix(const float* left, const float* right, float* result) // This code was found on: // http://stackoverflow.com/questions/1148309/inverting-a-4x4-matrix -// and is listed as being part of an open soure project (the MESA project) +// and is listed as being part of an open source project (the MESA project) // // The original code in MESA comes from __gluInvertMatrixd() in project.c // diff --git a/apps/src/pcd_video_player/pcd_video_player.cpp b/apps/src/pcd_video_player/pcd_video_player.cpp index e990461f8cf..c9b91ad0770 100644 --- a/apps/src/pcd_video_player/pcd_video_player.cpp +++ b/apps/src/pcd_video_player/pcd_video_player.cpp @@ -113,7 +113,7 @@ PCDVideoPlayer::PCDVideoPlayer () void PCDVideoPlayer::backButtonPressed () { - if(current_frame_ == 0) // Allready in the beginning + if(current_frame_ == 0) // Already in the beginning { PCL_DEBUG ("[PCDVideoPlayer::nextButtonPressed] : reached the end\n"); current_frame_ = nr_of_frames_ - 1; // reset to end @@ -295,7 +295,7 @@ print_usage () PCL_INFO ("\t Up/Down move a vertical slider by one single step.\n"); PCL_INFO ("\t PageUp moves up one page.\n"); PCL_INFO ("\t PageDown moves down one page.\n"); - PCL_INFO ("\t Home moves to the start (mininum).\n"); + PCL_INFO ("\t Home moves to the start (minimum).\n"); PCL_INFO ("\t End moves to the end (maximum).\n"); } diff --git a/apps/src/render_views_tesselated_sphere.cpp b/apps/src/render_views_tesselated_sphere.cpp index b3e0004f471..ea077fb1568 100644 --- a/apps/src/render_views_tesselated_sphere.cpp +++ b/apps/src/render_views_tesselated_sphere.cpp @@ -113,7 +113,7 @@ pcl::apps::RenderViewsTesselatedSphere::generateViews() { ico->SetSolidTypeToIcosahedron (); ico->Update (); - //tesselate cells from icosahedron + //tessellate cells from icosahedron vtkSmartPointer subdivide = vtkSmartPointer::New (); subdivide->SetNumberOfSubdivisions (tesselation_level_); subdivide->SetInputConnection (ico->GetOutputPort ()); diff --git a/cmake/CMakeParseArguments.cmake b/cmake/CMakeParseArguments.cmake index 7ce4c49ae5b..66016cb2ff1 100644 --- a/cmake/CMakeParseArguments.cmake +++ b/cmake/CMakeParseArguments.cmake @@ -58,7 +58,7 @@ # the new option. # E.g. my_install(TARGETS foo DESTINATION OPTIONAL) would result in # MY_INSTALL_DESTINATION set to "OPTIONAL", but MY_INSTALL_DESTINATION would -# be empty and MY_INSTALL_OPTIONAL would be set to TRUE therefor. +# be empty and MY_INSTALL_OPTIONAL would be set to TRUE therefore. #============================================================================= # Copyright 2010 Alexander Neundorf diff --git a/cmake/pcl_cpack.cmake b/cmake/pcl_cpack.cmake index 3c52f3d5533..8869279f127 100644 --- a/cmake/pcl_cpack.cmake +++ b/cmake/pcl_cpack.cmake @@ -78,7 +78,7 @@ set(PCL_CPACK_CFG_FILE "${PCL_BINARY_DIR}/cpack_options.cmake") # Make the CPack input file. macro(PCL_MAKE_CPACK_INPUT) set(_cpack_cfg_in "${PCL_SOURCE_DIR}/cmake/cpack_options.cmake.in") - set(${_var} "${${_var}}\nset(CPACK_COMPONENT_GROUP_PCL_DESCRIPTION \"PCL headers and librairies\")\n") + set(${_var} "${${_var}}\nset(CPACK_COMPONENT_GROUP_PCL_DESCRIPTION \"PCL headers and libraries\")\n") # Prepare the components list set(PCL_CPACK_COMPONENTS) diff --git a/cmake/pcl_targets.cmake b/cmake/pcl_targets.cmake index 80dfedf2263..4befb7f48a1 100644 --- a/cmake/pcl_targets.cmake +++ b/cmake/pcl_targets.cmake @@ -450,7 +450,7 @@ endmacro(PCL_ADD_LINKFLAGS) ############################################################################### # Make a pkg-config file for a library. Do not include general PCL stuff in the -# arguments; they will be added automaticaly. +# arguments; they will be added automatically. # _name The library name. "pcl_" will be preprended to this. # _component The part of PCL that this pkg-config file belongs to. # _desc Description of the library. @@ -487,7 +487,7 @@ endmacro(PCL_MAKE_PKGCONFIG) # Essentially a duplicate of PCL_MAKE_PKGCONFIG, but # ensures that no -L or l flags will be created # Do not include general PCL stuff in the -# arguments; they will be added automaticaly. +# arguments; they will be added automatically. # _name The library name. "pcl_" will be preprended to this. # _component The part of PCL that this pkg-config file belongs to. # _desc Description of the library. @@ -623,7 +623,7 @@ endmacro(PCL_GET_SUBSUBSYS_STATUS) ############################################################################### # Set the hyperstatus of a subsystem and its dependee # _name Subsystem name. -# _dependee Dependant subsystem. +# _dependee Dependent subsystem. # _status AUTO_OFF to disable AUTO_ON to enable # ARGN[0] Reason for not building. macro(PCL_SET_SUBSYS_HYPERSTATUS _name _dependee _status) @@ -636,7 +636,7 @@ endmacro(PCL_SET_SUBSYS_HYPERSTATUS) ############################################################################### # Get the hyperstatus of a subsystem and its dependee # _name IN subsystem name. -# _dependee IN dependant subsystem. +# _dependee IN dependent subsystem. # _var OUT hyperstatus # ARGN[0] Reason for not building. macro(PCL_GET_SUBSYS_HYPERSTATUS _var _name) @@ -852,7 +852,7 @@ endmacro(PCL_ADD_DOC) # This macro adds on option named "WITH_NAME", where NAME is the capitalized # dependency name. The user may use this option to control whether the # corresponding grabber should be built or not. Also an attempt to find a -# package with the given name is made. If it is not successfull, then the +# package with the given name is made. If it is not successful, then the # "WITH_NAME" option is coerced to FALSE. macro(PCL_ADD_GRABBER_DEPENDENCY _name _description) string(TOUPPER ${_name} _name_capitalized) diff --git a/cmake/pcl_utils.cmake b/cmake/pcl_utils.cmake index 69f1e76a4f9..41a64a26984 100644 --- a/cmake/pcl_utils.cmake +++ b/cmake/pcl_utils.cmake @@ -405,7 +405,7 @@ macro(sort_relative _list _sorted_list _to_sort_relative) if(NOT (list_length EQUAL to_sort_list_length)) message(FATAL_ERROR "size mismatch between ${_to_sort_relative} ${to_sort_list_length} and ${_list} ${list_length}") endif(NOT (list_length EQUAL to_sort_list_length)) - # unset the temporary list to avoid suprises (I had some them and were hard to find) + # unset the temporary list to avoid surprises (I had some them and were hard to find) unset(tmp_list) # fill it with a dummy value fill_list(tmp_list list_length "#") diff --git a/common/include/pcl/common/bivariate_polynomial.h b/common/include/pcl/common/bivariate_polynomial.h index ccb313f9807..357764e44f4 100644 --- a/common/include/pcl/common/bivariate_polynomial.h +++ b/common/include/pcl/common/bivariate_polynomial.h @@ -70,7 +70,7 @@ namespace pcl void setDegree (int new_degree); - /** How many parametes has a bivariate polynomial with this degree */ + /** How many parameters has a bivariate polynomial with this degree */ unsigned int getNoOfParameters () const { return getNoOfParametersFromDegree (degree);} @@ -108,7 +108,7 @@ namespace pcl void readBinary (const char* filename); - /** How many parametes has a bivariate polynomial of the given degree */ + /** How many parameters has a bivariate polynomial of the given degree */ static unsigned int getNoOfParametersFromDegree (int n) { return ((n+2)* (n+1))/2;} diff --git a/common/include/pcl/common/centroid.h b/common/include/pcl/common/centroid.h index 535ddf0cdb0..30332845b5c 100644 --- a/common/include/pcl/common/centroid.h +++ b/common/include/pcl/common/centroid.h @@ -204,7 +204,7 @@ namespace pcl /** \brief Compute normalized the 3x3 covariance matrix of a given set of points. * The result is returned as a Eigen::Matrix3f. * Normalized means that every entry has been divided by the number of points in the point cloud. - * For small number of points, or if you want explicitely the sample-variance, use computeCovarianceMatrix + * For small number of points, or if you want explicitly the sample-variance, use computeCovarianceMatrix * and scale the covariance matrix with 1 / (n-1), where n is the number of points used to calculate * the covariance matrix and is returned by the computeCovarianceMatrix function. * \param[in] cloud the input point cloud @@ -313,7 +313,7 @@ namespace pcl * their indices. * The result is returned as a Eigen::Matrix3f. * Normalized means that every entry has been divided by the number of entries in indices. - * For small number of points, or if you want explicitely the sample-variance, use computeCovarianceMatrix + * For small number of points, or if you want explicitly the sample-variance, use computeCovarianceMatrix * and scale the covariance matrix with 1 / (n-1), where n is the number of points used to calculate * the covariance matrix and is returned by the computeCovarianceMatrix function. * \param[in] cloud the input point cloud @@ -351,7 +351,7 @@ namespace pcl /** \brief Compute the normalized 3x3 covariance matrix of a given set of points using * their indices. The result is returned as a Eigen::Matrix3f. * Normalized means that every entry has been divided by the number of entries in indices. - * For small number of points, or if you want explicitely the sample-variance, use computeCovarianceMatrix + * For small number of points, or if you want explicitly the sample-variance, use computeCovarianceMatrix * and scale the covariance matrix with 1 / (n-1), where n is the number of points used to calculate * the covariance matrix and is returned by the computeCovarianceMatrix function. * \param[in] cloud the input point cloud @@ -388,7 +388,7 @@ namespace pcl /** \brief Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. * Normalized means that every entry has been divided by the number of entries in indices. - * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. * \param[in] cloud the input point cloud @@ -421,7 +421,7 @@ namespace pcl /** \brief Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. * Normalized means that every entry has been divided by the number of entries in indices. - * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. * \param[in] cloud the input point cloud @@ -458,7 +458,7 @@ namespace pcl /** \brief Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single loop. * Normalized means that every entry has been divided by the number of entries in indices. - * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. * \param[in] cloud the input point cloud @@ -495,7 +495,7 @@ namespace pcl /** \brief Compute the normalized 3x3 covariance matrix for a already demeaned point cloud. * Normalized means that every entry has been divided by the number of entries in indices. - * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. * \param[in] cloud the input point cloud @@ -524,7 +524,7 @@ namespace pcl /** \brief Compute the normalized 3x3 covariance matrix for a already demeaned point cloud. * Normalized means that every entry has been divided by the number of entries in indices. - * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. * \param[in] cloud the input point cloud @@ -557,7 +557,7 @@ namespace pcl /** \brief Compute the normalized 3x3 covariance matrix for a already demeaned point cloud. * Normalized means that every entry has been divided by the number of entries in indices. - * For small number of points, or if you want explicitely the sample-variance, scale the covariance matrix + * For small number of points, or if you want explicitly the sample-variance, scale the covariance matrix * with n / (n-1), where n is the number of points used to calculate the covariance matrix and is returned by this function. * \note This method is theoretically exact. However using float for internal calculations reduces the accuracy but increases the efficiency. * \param[in] cloud the input point cloud diff --git a/common/include/pcl/common/generate.h b/common/include/pcl/common/generate.h index 09291258f40..575a0c46d96 100644 --- a/common/include/pcl/common/generate.h +++ b/common/include/pcl/common/generate.h @@ -64,13 +64,13 @@ namespace pcl /// Default constructor CloudGenerator (); - /** Consttructor with single generator to ensure all X, Y and Z values are within same range + /** Constructor with single generator to ensure all X, Y and Z values are within same range * \param params paramteres for X, Y and Z values generation. Uniqueness is ensured through * seed incrementation */ CloudGenerator (const GeneratorParameters& params); - /** Constructor with independant generators per axis + /** Constructor with independent generators per axis * \param x_params parameters for x values generation * \param y_params parameters for y values generation * \param z_params parameters for z values generation @@ -86,19 +86,19 @@ namespace pcl setParameters (const GeneratorParameters& params); /** Set parameters for x values generation - * \param x_params paramters for x values generation + * \param x_params parameters for x values generation */ void setParametersForX (const GeneratorParameters& x_params); /** Set parameters for y values generation - * \param y_params paramters for y values generation + * \param y_params parameters for y values generation */ void setParametersForY (const GeneratorParameters& y_params); /** Set parameters for z values generation - * \param z_params paramters for z values generation + * \param z_params parameters for z values generation */ void setParametersForZ (const GeneratorParameters& z_params); diff --git a/common/include/pcl/common/impl/eigen.hpp b/common/include/pcl/common/impl/eigen.hpp index 3f3c00ebdf4..cd12e16b277 100644 --- a/common/include/pcl/common/impl/eigen.hpp +++ b/common/include/pcl/common/impl/eigen.hpp @@ -116,7 +116,7 @@ pcl::computeRoots (const Matrix& m, Roots& roots) std::swap (roots (0), roots (1)); } - if (roots (0) <= 0) // eigenval for symetric positive semi-definite matrix can not be negative! Set it to 0 + if (roots (0) <= 0) // eigenval for symmetric positive semi-definite matrix can not be negative! Set it to 0 computeRoots2 (c2, c1, roots); } } diff --git a/common/include/pcl/common/impl/intersections.hpp b/common/include/pcl/common/impl/intersections.hpp index 1a286ed107e..cfc7a67b85a 100644 --- a/common/include/pcl/common/impl/intersections.hpp +++ b/common/include/pcl/common/impl/intersections.hpp @@ -145,7 +145,7 @@ pcl::threePlanesIntersection (const Eigen::Matrix &plane_a, if (fabs (determinant) < determinant_tolerance) { // det ~= 0 - PCL_DEBUG ("At least two planes are parralel.\n"); + PCL_DEBUG ("At least two planes are parallel.\n"); return (false); } diff --git a/common/include/pcl/common/intersections.h b/common/include/pcl/common/intersections.h index 7cf30b1201c..d0b6733b369 100644 --- a/common/include/pcl/common/intersections.h +++ b/common/include/pcl/common/intersections.h @@ -112,7 +112,7 @@ namespace pcl } /** \brief Determine the point of intersection of three non-parallel planes by solving the equations. - * \note If using nearly parralel planes you can lower the determinant_tolerance value. This can + * \note If using nearly parallel planes you can lower the determinant_tolerance value. This can * lead to inconsistent results. * If the three planes intersects in a line the point will be anywhere on the line. * \param[in] plane_a are the coefficients of the first plane in the form ax + by + cz + d = 0 diff --git a/common/include/pcl/common/io.h b/common/include/pcl/common/io.h index cf2047a9abf..3192af779cd 100644 --- a/common/include/pcl/common/io.h +++ b/common/include/pcl/common/io.h @@ -416,7 +416,7 @@ namespace pcl * BORDER_REFLECT_101: gfedcb|abcdefgh|gfedcba * BORDER_WRAP: cdefgh|abcdefgh|abcdefg * BORDER_CONSTANT: iiiiii|abcdefgh|iiiiiii with some specified 'i' - * BORDER_TRANSPARENT: mnopqr|abcdefgh|tuvwxyz where m-r and t-z are orignal values of cloud_out + * BORDER_TRANSPARENT: mnopqr|abcdefgh|tuvwxyz where m-r and t-z are original values of cloud_out * \param value * \throw pcl::BadArgumentException if any of top, bottom, left or right is negative. * \ingroup common diff --git a/common/include/pcl/common/spring.h b/common/include/pcl/common/spring.h index db7268da0d3..4d980829df4 100644 --- a/common/include/pcl/common/spring.h +++ b/common/include/pcl/common/spring.h @@ -51,7 +51,7 @@ namespace pcl * custom values. * \param[in] input the input point cloud * \param[out] output the output point cloud - * \param[in] val the point value to be insterted + * \param[in] val the point value to be inserted * \param[in] amount the amount of rows to be added */ template void @@ -63,7 +63,7 @@ namespace pcl * custom values. * \param[in] input the input point cloud * \param[out] output the output point cloud - * \param[in] val the point value to be insterted + * \param[in] val the point value to be inserted * \param[in] amount the amount of columns to be added */ template void diff --git a/common/include/pcl/common/time.h b/common/include/pcl/common/time.h index bf44ecff6ad..093c262eca2 100644 --- a/common/include/pcl/common/time.h +++ b/common/include/pcl/common/time.h @@ -163,7 +163,7 @@ namespace pcl stop_watch_.reset (); } - /** \brief Notifies the class that the event occured. */ + /** \brief Notifies the class that the event occurred. */ void event () { event_time_queue_.push (stop_watch_.getTimeSeconds ()); diff --git a/common/include/pcl/common/time_trigger.h b/common/include/pcl/common/time_trigger.h index 941f96b916d..c4af9b5e910 100644 --- a/common/include/pcl/common/time_trigger.h +++ b/common/include/pcl/common/time_trigger.h @@ -70,7 +70,7 @@ namespace pcl /** \brief Destructor. */ ~TimeTrigger (); - /** \brief registeres a callback + /** \brief registers a callback * \param[in] callback callback function to the list of callbacks. signature has to be boost::function * \return connection the connection, which can be used to disable/enable and remove callback from list */ diff --git a/common/include/pcl/console/parse.h b/common/include/pcl/console/parse.h index 0015875292b..07fba38c172 100644 --- a/common/include/pcl/console/parse.h +++ b/common/include/pcl/console/parse.h @@ -274,7 +274,7 @@ namespace pcl PCL_EXPORTS int parse_x_arguments (int argc, char** argv, const char* str, std::vector& v); - /** \brief Parse for specific given command line arguments (multiple occurences + /** \brief Parse for specific given command line arguments (multiple occurrences * of the same command line parameter). * \param[in] argc the number of command line arguments * \param[in] argv the command line arguments @@ -285,7 +285,7 @@ namespace pcl PCL_EXPORTS bool parse_multiple_arguments (int argc, char** argv, const char* str, std::vector &values); - /** \brief Parse for specific given command line arguments (multiple occurences + /** \brief Parse for specific given command line arguments (multiple occurrences * of the same command line parameter). * \param[in] argc the number of command line arguments * \param[in] argv the command line arguments @@ -296,7 +296,7 @@ namespace pcl PCL_EXPORTS bool parse_multiple_arguments (int argc, char** argv, const char* str, std::vector &values); - /** \brief Parse for specific given command line arguments (multiple occurences + /** \brief Parse for specific given command line arguments (multiple occurrences * of the same command line parameter). * \param[in] argc the number of command line arguments * \param[in] argv the command line arguments @@ -307,7 +307,7 @@ namespace pcl PCL_EXPORTS bool parse_multiple_arguments (int argc, char** argv, const char* str, std::vector &values); - /** \brief Parse for a specific given command line argument (multiple occurences + /** \brief Parse for a specific given command line argument (multiple occurrences * of the same command line parameter). * \param[in] argc the number of command line arguments * \param[in] argv the command line arguments @@ -318,7 +318,7 @@ namespace pcl PCL_EXPORTS bool parse_multiple_arguments (int argc, char** argv, const char* str, std::vector &values); - /** \brief Parse command line arguments for file names with given extension (multiple occurences + /** \brief Parse command line arguments for file names with given extension (multiple occurrences * of 2x argument groups, separated by commas). * \param[in] argc the number of command line arguments * \param[in] argv the command line arguments @@ -332,7 +332,7 @@ namespace pcl std::vector &values_f, std::vector &values_s); - /** \brief Parse command line arguments for file names with given extension (multiple occurences + /** \brief Parse command line arguments for file names with given extension (multiple occurrences * of 3x argument groups, separated by commas). * \param[in] argc the number of command line arguments * \param[in] argv the command line arguments diff --git a/common/include/pcl/exceptions.h b/common/include/pcl/exceptions.h index 1fc1ac046c5..485e1e67a8a 100644 --- a/common/include/pcl/exceptions.h +++ b/common/include/pcl/exceptions.h @@ -145,7 +145,7 @@ namespace pcl } ; /** \class IsNotDenseException - * \brief An exception that is thrown when a PointCloud is not dense but is attemped to be used as dense + * \brief An exception that is thrown when a PointCloud is not dense but is attempted to be used as dense */ class IsNotDenseException : public PCLException { @@ -251,7 +251,7 @@ namespace pcl }; /** \class BadArgumentException - * \brief An exception that is thrown when the argments number or type is wrong/unhandled. + * \brief An exception that is thrown when the arguments number or type is wrong/unhandled. */ class BadArgumentException : public PCLException { diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index cdf5f43bf10..907b8f55633 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -1519,7 +1519,7 @@ namespace pcl union { - /** \brief Diameter of the meaningfull keypoint neighborhood. */ + /** \brief Diameter of the meaningful keypoint neighborhood. */ float scale; float size; }; diff --git a/common/include/pcl/point_representation.h b/common/include/pcl/point_representation.h index 20f49480f24..15ae97f4e4b 100644 --- a/common/include/pcl/point_representation.h +++ b/common/include/pcl/point_representation.h @@ -48,7 +48,7 @@ namespace pcl /** \brief @b PointRepresentation provides a set of methods for converting a point structs/object into an * n-dimensional vector. * \note This is an abstract class. Subclasses must set nr_dimensions_ to the appropriate value in the constructor - * and provide an implemention of the pure virtual copyToFloatArray method. + * and provide an implementation of the pure virtual copyToFloatArray method. * \author Michael Dixon */ template @@ -80,7 +80,7 @@ namespace pcl /** \brief Empty destructor */ virtual ~PointRepresentation () {} - /** \brief Copy point data from input point to a float array. This method must be overriden in all subclasses. + /** \brief Copy point data from input point to a float array. This method must be overridden in all subclasses. * \param[in] p The input point * \param[out] out A pointer to a float array. */ diff --git a/common/include/pcl/point_traits.h b/common/include/pcl/point_traits.h index d30e760fefd..e69004316d4 100644 --- a/common/include/pcl/point_traits.h +++ b/common/include/pcl/point_traits.h @@ -344,7 +344,7 @@ namespace pcl /** \brief Get the value at a specified field in a point * \param[in] pt the point to get the value from * \param[in] field_offset the offset of the field - * \param[out] value the value to retreive + * \param[out] value the value to retrieve */ template inline void getFieldValue (const PointT &pt, size_t field_offset, ValT &value) diff --git a/common/include/pcl/range_image/range_image.h b/common/include/pcl/range_image/range_image.h index 79b1d65fb27..e2d1d2a6836 100644 --- a/common/include/pcl/range_image/range_image.h +++ b/common/include/pcl/range_image/range_image.h @@ -349,7 +349,7 @@ namespace pcl getTransformationToWorldSystem () const { return to_world_system_;} /** Getter for the angular resolution of the range image in x direction in radians per pixel. - * Provided for downwards compatability */ + * Provided for downwards compatibility */ inline float getAngularResolution () const { return angular_resolution_x_;} @@ -746,7 +746,7 @@ namespace pcl getViewingDirection (const Eigen::Vector3f& point, Eigen::Vector3f& viewing_direction) const; /** Return a newly created Range image. - * Can be reimplmented in derived classes like RangeImagePlanar to return an image of the same type. */ + * Can be reimplemented in derived classes like RangeImagePlanar to return an image of the same type. */ PCL_EXPORTS virtual RangeImage* getNew () const { return new RangeImage; } @@ -771,9 +771,9 @@ namespace pcl Eigen::Affine3f to_world_system_; /**< Inverse of to_range_image_system_ */ float angular_resolution_x_; /**< Angular resolution of the range image in x direction in radians per pixel */ float angular_resolution_y_; /**< Angular resolution of the range image in y direction in radians per pixel */ - float angular_resolution_x_reciprocal_; /**< 1.0/angular_resolution_x_ - provided for better performace of + float angular_resolution_x_reciprocal_; /**< 1.0/angular_resolution_x_ - provided for better performance of * multiplication compared to division */ - float angular_resolution_y_reciprocal_; /**< 1.0/angular_resolution_y_ - provided for better performace of + float angular_resolution_y_reciprocal_; /**< 1.0/angular_resolution_y_ - provided for better performance of * multiplication compared to division */ int image_offset_x_, image_offset_y_; /**< Position of the top left corner of the range image compared to * an image of full size (360x180 degrees) */ diff --git a/common/include/pcl/range_image/range_image_planar.h b/common/include/pcl/range_image/range_image_planar.h index 90b96bfab55..3d2db0c6d9f 100644 --- a/common/include/pcl/range_image/range_image_planar.h +++ b/common/include/pcl/range_image/range_image_planar.h @@ -64,11 +64,11 @@ namespace pcl PCL_EXPORTS virtual ~RangeImagePlanar (); /** Return a newly created RangeImagePlanar. - * Reimplmentation to return an image of the same type. */ + * Reimplementation to return an image of the same type. */ virtual RangeImage* getNew () const { return new RangeImagePlanar; } - /** Copy *this to other. Derived version - also copying additonal RangeImagePlanar members */ + /** Copy *this to other. Derived version - also copying additional RangeImagePlanar members */ PCL_EXPORTS virtual void copyTo (RangeImage& other) const; diff --git a/common/include/pcl/range_image/range_image_spherical.h b/common/include/pcl/range_image/range_image_spherical.h index dfba4d43489..82ea66373ba 100644 --- a/common/include/pcl/range_image/range_image_spherical.h +++ b/common/include/pcl/range_image/range_image_spherical.h @@ -63,7 +63,7 @@ namespace pcl PCL_EXPORTS virtual ~RangeImageSpherical () {} /** Return a newly created RangeImagePlanar. - * Reimplmentation to return an image of the same type. */ + * Reimplementation to return an image of the same type. */ virtual RangeImage* getNew () const { return new RangeImageSpherical; } diff --git a/common/src/fft/kiss_fft.c b/common/src/fft/kiss_fft.c index 98fc588f5ca..8228b1c7cec 100644 --- a/common/src/fft/kiss_fft.c +++ b/common/src/fft/kiss_fft.c @@ -15,7 +15,7 @@ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND #include "pcl/common/fft/_kiss_fft_guts.h" /* The guts header contains all the multiplication and addition macros that are defined for - fixed or floating point complex numbers. It also delares the kf_ internal functions. + fixed or floating point complex numbers. It also declares the kf_ internal functions. */ static void kf_bfly2( diff --git a/common/src/poses_from_matches.cpp b/common/src/poses_from_matches.cpp index d1854326464..8e75354e2f3 100644 --- a/common/src/poses_from_matches.cpp +++ b/common/src/poses_from_matches.cpp @@ -95,7 +95,7 @@ pcl::PosesFromMatches::estimatePosesUsing2Correspondences (const pcl::PointCorre pcl::TransformationFromCorrespondences transformation_from_correspondeces; // The following loop structure goes through the pairs in the order 12, 13, 23, 14, 24, 34, ..., - // testing the best correspondences pairs first, without beeing stuck too long with one specific + // testing the best correspondences pairs first, without being stuck too long with one specific // (possibly wrong) correspondence. bool done = false; for (int correspondence2_idx = 0; correspondence2_idx < max_correspondence_idx && !done; ++correspondence2_idx) @@ -209,7 +209,7 @@ pcl::PosesFromMatches::estimatePosesUsing3Correspondences (const PointCorrespond pcl::TransformationFromCorrespondences transformation_from_correspondeces; // The following loop structure goes through the triples in the order 123, 124, 134, 234, 125, 135, 235, ..., - // testing the best correspondences triples first, without beeing stuck too long with one specific + // testing the best correspondences triples first, without being stuck too long with one specific // (possibly wrong) correspondence. bool done = false; for (int correspondence3_idx = 0; correspondence3_idx < max_correspondence_idx && !done; ++correspondence3_idx) diff --git a/cuda/common/include/pcl/cuda/common/eigen.h b/cuda/common/include/pcl/cuda/common/eigen.h index db354f704ff..f7d3c6bb83a 100644 --- a/cuda/common/include/pcl/cuda/common/eigen.h +++ b/cuda/common/include/pcl/cuda/common/eigen.h @@ -218,7 +218,7 @@ namespace pcl swap (roots.x, roots.y); } - if (roots.x <= 0.0f) // eigenval for symetric positive semi-definite matrix can not be negative! Set it to 0 + if (roots.x <= 0.0f) // eigenval for symmetric positive semi-definite matrix can not be negative! Set it to 0 computeRoots2 (c2, c1, roots); } } diff --git a/cuda/common/include/pcl/cuda/cutil.h b/cuda/common/include/pcl/cuda/cutil.h index 8f2ad57d791..0dabbf348be 100644 --- a/cuda/common/include/pcl/cuda/cutil.h +++ b/cuda/common/include/pcl/cuda/cutil.h @@ -340,7 +340,7 @@ extern "C" { //! @param w width of the image //! @param h height of the image //! @note If a NULL pointer is passed to this function and it is - //! initialized withing Cutil then cutFree() has to be used to + //! initialized within Cutil then cutFree() has to be used to //! deallocate the memory //////////////////////////////////////////////////////////////////////////// DLL_MAPPING @@ -355,7 +355,7 @@ extern "C" { //! @param w width of the image //! @param h height of the image //! @note If a NULL pointer is passed to this function and it is - //! initialized withing Cutil then cutFree() has to be used to + //! initialized within Cutil then cutFree() has to be used to //! deallocate the memory //////////////////////////////////////////////////////////////////////////// DLL_MAPPING @@ -439,7 +439,7 @@ extern "C" { //////////////////////////////////////////////////////////////////////////// // Command line arguments: General notes // * All command line arguments begin with '--' followed by the token; - // token and value are seperated by '='; example --samples=50 + // token and value are separated by '='; example --samples=50 // * Arrays have the form --model=[one.obj,two.obj,three.obj] // (without whitespaces) //////////////////////////////////////////////////////////////////////////// diff --git a/cuda/common/include/pcl/cuda/cutil_inline_drvapi.h b/cuda/common/include/pcl/cuda/cutil_inline_drvapi.h index 50261782ef1..2ce92fc13ce 100644 --- a/cuda/common/include/pcl/cuda/cutil_inline_drvapi.h +++ b/cuda/common/include/pcl/cuda/cutil_inline_drvapi.h @@ -57,7 +57,7 @@ inline int _ConvertSMVer2CoresDrvApi(int major, int minor) { // Defines for GPU Architecture types (using the SM version to determine the # of cores per SM typedef struct { - int SM; // 0xMm (hexidecimal notation), M = SM Major version, and m = SM minor version + int SM; // 0xMm (hexadecimal notation), M = SM Major version, and m = SM minor version int Cores; } sSMtoCores; @@ -195,7 +195,7 @@ inline int cutilDrvGetMaxGflopsGraphicsDeviceId() sm_per_multiproc = _ConvertSMVer2CoresDrvApi(major, minor); } - // If this is a Tesla based GPU and SM 2.0, and TCC is disabled, this is a contendor + // If this is a Tesla based GPU and SM 2.0, and TCC is disabled, this is a contender if (!bTCC) // Is this GPU running the TCC driver? If so we pass on this { int compute_perf = multiProcessorCount * sm_per_multiproc * clockRate; diff --git a/cuda/common/include/pcl/cuda/cutil_inline_runtime.h b/cuda/common/include/pcl/cuda/cutil_inline_runtime.h index c0a607be37c..4e2d51b4f36 100644 --- a/cuda/common/include/pcl/cuda/cutil_inline_runtime.h +++ b/cuda/common/include/pcl/cuda/cutil_inline_runtime.h @@ -85,7 +85,7 @@ inline int _ConvertSMVer2Cores(int major, int minor) { // Defines for GPU Architecture types (using the SM version to determine the # of cores per SM typedef struct { - int SM; // 0xMm (hexidecimal notation), M = SM Major version, and m = SM minor version + int SM; // 0xMm (hexadecimal notation), M = SM Major version, and m = SM minor version int Cores; } sSMtoCores; @@ -226,7 +226,7 @@ inline int cutGetMaxGflopsGraphicsDeviceId() return max_perf_device; } -// Give a little more for Windows : the console window often disapears before we can read the message +// Give a little more for Windows : the console window often disappears before we can read the message #ifdef _WIN32 # if 1//ndef UNICODE # ifdef _DEBUG // Do this only in debug mode... diff --git a/cuda/nn/organized_neighbor_search.hpp b/cuda/nn/organized_neighbor_search.hpp index 29908718f69..c0a06515903 100644 --- a/cuda/nn/organized_neighbor_search.hpp +++ b/cuda/nn/organized_neighbor_search.hpp @@ -190,7 +190,7 @@ namespace pcl // vector for nearest neighbor candidates std::vector nearestNeighbors; - // iterator for radius seach lookup table + // iterator for radius search lookup table typename std::vector::const_iterator radiusSearchLookup_Iterator; radiusSearchLookup_Iterator = radiusSearchLookup_.begin (); diff --git a/cuda/segmentation/src/mssegmentation.cpp b/cuda/segmentation/src/mssegmentation.cpp index f0e7001dc68..1ca0e0f37c6 100644 --- a/cuda/segmentation/src/mssegmentation.cpp +++ b/cuda/segmentation/src/mssegmentation.cpp @@ -162,7 +162,7 @@ void meanShiftSegmentation(const GpuMat& src, Mat& dst, int sp, int sr, int mins vector edges; edges.reserve(g.numv); - // Prepare edges connecting differnet components + // Prepare edges connecting different components for (int v = 0; v < g.numv; ++v) { int c1 = comps.find(v); @@ -174,7 +174,7 @@ void meanShiftSegmentation(const GpuMat& src, Mat& dst, int sp, int sr, int mins } } - // Sort all graph's edges connecting differnet components (in asceding order) + // Sort all graph's edges connecting different components (in ascending order) sort(edges.begin(), edges.end()); // Exclude small components (starting from the nearest couple) diff --git a/features/src/range_image_border_extractor.cpp b/features/src/range_image_border_extractor.cpp index 713606a6da4..e71b2a547ba 100644 --- a/features/src/range_image_border_extractor.cpp +++ b/features/src/range_image_border_extractor.cpp @@ -504,7 +504,7 @@ RangeImageBorderExtractor::calculateBorderDirections () if (neighbor_border_direction==NULL || index2==index) continue; - // Oposite directions? + // Opposite directions? float cos_angle = neighbor_border_direction->dot(*border_direction); if (cos_angle& indices, const std::vector& distances) = 0; - /** \brief Must call this methode before doing any computation + /** \brief Must call this method before doing any computation * \note make sure to override this with at least * \code * bool initCompute () @@ -150,7 +150,7 @@ namespace pcl inline void setThreshold (float threshold) { threshold_ = threshold; } - /** Must call this methode before doing any computation */ + /** Must call this method before doing any computation */ bool initCompute (); virtual PointOutT diff --git a/filters/include/pcl/filters/model_outlier_removal.h b/filters/include/pcl/filters/model_outlier_removal.h index 600d90de97a..5587d9f1803 100644 --- a/filters/include/pcl/filters/model_outlier_removal.h +++ b/filters/include/pcl/filters/model_outlier_removal.h @@ -228,7 +228,7 @@ namespace pcl /** \brief The model used to calculate distances */ SampleConsensusModelPtr model_; - /** \brief The threshold used to seperate outliers (removed_indices) from inliers (indices) */ + /** \brief The threshold used to separate outliers (removed_indices) from inliers (indices) */ float thresh_; /** \brief The model coefficients */ diff --git a/filters/include/pcl/filters/voxel_grid_covariance.h b/filters/include/pcl/filters/voxel_grid_covariance.h index d4e6a094ddc..f1bbc859311 100644 --- a/filters/include/pcl/filters/voxel_grid_covariance.h +++ b/filters/include/pcl/filters/voxel_grid_covariance.h @@ -367,7 +367,7 @@ namespace pcl } - /** \brief Get the voxels surrounding point p, not including the voxel contating point p. + /** \brief Get the voxels surrounding point p, not including the voxel containing point p. * \note Only voxels containing a sufficient number of points are used (slower than radius search in practice). * \param[in] reference_point the point to get the leaf structure at * \param[out] neighbors diff --git a/filters/src/passthrough.cpp b/filters/src/passthrough.cpp index 90e9f7f7689..e7fe2461dbb 100644 --- a/filters/src/passthrough.cpp +++ b/filters/src/passthrough.cpp @@ -86,7 +86,7 @@ pcl::PassThrough::applyFilter (PCLPointCloud2 &output) { // Copy the header (and thus the frame_id) + allocate enough space for points output.height = 1; // filtering breaks the organized structure - // Because we're doing explit checks for isfinite, is_dense = true + // Because we're doing explicit checks for isfinite, is_dense = true output.is_dense = true; } output.row_step = input_->row_step; diff --git a/gpu/surface/src/internal.h b/gpu/surface/src/internal.h index 6f4fa93417f..2a1e7b29a8b 100644 --- a/gpu/surface/src/internal.h +++ b/gpu/surface/src/internal.h @@ -66,7 +66,7 @@ namespace pcl public: FacetStream(size_t buffer_size); - // indeces: in each col indeces of vertexes for sigle facet + // indeces: in each col indeces of vertexes for single facet DeviceArray2D verts_inds; DeviceArray head_points; diff --git a/io/include/pcl/compression/color_coding.h b/io/include/pcl/compression/color_coding.h index 382d33a9641..8783bcbbabc 100644 --- a/io/include/pcl/compression/color_coding.h +++ b/io/include/pcl/compression/color_coding.h @@ -294,8 +294,8 @@ namespace pcl /** \brief Decode color information * \param outputCloud_arg output point cloud - * \param beginIdx_arg index indicating first point to be assiged with color information - * \param endIdx_arg index indicating last point to be assiged with color information + * \param beginIdx_arg index indicating first point to be assigned with color information + * \param endIdx_arg index indicating last point to be assigned with color information * \param rgba_offset_arg offset to color information */ void @@ -355,8 +355,8 @@ namespace pcl /** \brief Set default color to points * \param outputCloud_arg output point cloud - * \param beginIdx_arg index indicating first point to be assiged with color information - * \param endIdx_arg index indicating last point to be assiged with color information + * \param beginIdx_arg index indicating first point to be assigned with color information + * \param endIdx_arg index indicating last point to be assigned with color information * \param rgba_offset_arg offset to color information * */ void diff --git a/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp b/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp index 8849aa36d02..d10f6728e5e 100644 --- a/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp +++ b/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp @@ -88,7 +88,7 @@ namespace pcl compressedDataOut_arg.write (reinterpret_cast (&cloud_height), sizeof (cloud_height)); // encode frame max depth compressedDataOut_arg.write (reinterpret_cast (&maxDepth), sizeof (maxDepth)); - // encode frame focal lenght + // encode frame focal length compressedDataOut_arg.write (reinterpret_cast (&focalLength), sizeof (focalLength)); // encode frame disparity scale compressedDataOut_arg.write (reinterpret_cast (&disparityScale), sizeof (disparityScale)); @@ -186,7 +186,7 @@ namespace pcl compressedDataOut_arg.write (reinterpret_cast (&height_arg), sizeof (height_arg)); // encode frame max depth compressedDataOut_arg.write (reinterpret_cast (&maxDepth), sizeof (maxDepth)); - // encode frame focal lenght + // encode frame focal length compressedDataOut_arg.write (reinterpret_cast (&focalLength_arg), sizeof (focalLength_arg)); // encode frame disparity scale compressedDataOut_arg.write (reinterpret_cast (&disparityScale_arg), sizeof (disparityScale_arg)); diff --git a/io/include/pcl/compression/octree_pointcloud_compression.h b/io/include/pcl/compression/octree_pointcloud_compression.h index de1690489c6..550355ac694 100644 --- a/io/include/pcl/compression/octree_pointcloud_compression.h +++ b/io/include/pcl/compression/octree_pointcloud_compression.h @@ -265,13 +265,13 @@ namespace pcl /** \brief Vector for storing binary tree structure */ std::vector binary_tree_data_vector_; - /** \brief Interator on binary tree structure vector */ + /** \brief Iterator on binary tree structure vector */ std::vector binary_color_tree_vector_; /** \brief Vector for storing points per voxel information */ std::vector point_count_data_vector_; - /** \brief Interator on points per voxel vector */ + /** \brief Iterator on points per voxel vector */ std::vector::const_iterator point_count_data_vector_iterator_; /** \brief Color coding instance */ diff --git a/io/include/pcl/compression/organized_pointcloud_compression.h b/io/include/pcl/compression/organized_pointcloud_compression.h index 5485ae312c2..d75f13277cb 100644 --- a/io/include/pcl/compression/organized_pointcloud_compression.h +++ b/io/include/pcl/compression/organized_pointcloud_compression.h @@ -122,7 +122,7 @@ namespace pcl * \param[in] compressedDataIn_arg: binary input stream containing compressed data * \param[out] cloud_arg: reference to decoded point cloud * \param[in] bShowStatistics_arg: show compression statistics during decoding - * \return false if an I/O error occured. + * \return false if an I/O error occurred. */ bool decodePointCloud (std::istream& compressedDataIn_arg, PointCloudPtr &cloud_arg, diff --git a/io/include/pcl/compression/point_coding.h b/io/include/pcl/compression/point_coding.h index 2c77350a9ff..436370cad30 100644 --- a/io/include/pcl/compression/point_coding.h +++ b/io/include/pcl/compression/point_coding.h @@ -162,8 +162,8 @@ namespace pcl /** \brief Decode differential point information * \param outputCloud_arg output point cloud * \param referencePoint_arg coordinates of reference point - * \param beginIdx_arg index indicating first point to be assiged with color information - * \param endIdx_arg index indicating last point to be assiged with color information + * \param beginIdx_arg index indicating first point to be assigned with color information + * \param endIdx_arg index indicating last point to be assigned with color information */ void decodePoints (PointCloudPtr outputCloud_arg, const double* referencePoint_arg, std::size_t beginIdx_arg, diff --git a/io/include/pcl/io/ascii_io.h b/io/include/pcl/io/ascii_io.h index bcd70c77290..927b6e53205 100644 --- a/io/include/pcl/io/ascii_io.h +++ b/io/include/pcl/io/ascii_io.h @@ -125,7 +125,7 @@ namespace pcl } - /** \brief Set the Separting characters for the ascii point fields 2. + /** \brief Set the Separating characters for the ascii point fields 2. * \param[in] chars string of separating characters * Sets the separating characters for the point fields. The * default separating characters are " \n\t," diff --git a/io/include/pcl/io/fotonic_grabber.h b/io/include/pcl/io/fotonic_grabber.h index 907dc9c4c2e..ef834197427 100644 --- a/io/include/pcl/io/fotonic_grabber.h +++ b/io/include/pcl/io/fotonic_grabber.h @@ -135,7 +135,7 @@ namespace pcl void setupDevice (const FZ_DEVICE_INFO& device_info, const Mode& depth_mode, const Mode& image_mode); - /** \brief Continously asks for data from the device and publishes it if available. */ + /** \brief Continuously asks for data from the device and publishes it if available. */ void processGrabbing (); diff --git a/io/include/pcl/io/grabber.h b/io/include/pcl/io/grabber.h index 0858ed48e4c..9c23b26cc7c 100644 --- a/io/include/pcl/io/grabber.h +++ b/io/include/pcl/io/grabber.h @@ -62,7 +62,7 @@ namespace pcl /** \brief Constructor. */ Grabber () : signals_ (), connections_ (), shared_connections_ () {} - /** \brief virtual desctructor. */ + /** \brief virtual destructor. */ virtual inline ~Grabber () throw (); /** \brief registers a callback function/method to a signal with the corresponding signature diff --git a/io/include/pcl/io/impl/lzf_image_io.hpp b/io/include/pcl/io/impl/lzf_image_io.hpp index be2da298af3..d215687ade0 100644 --- a/io/include/pcl/io/impl/lzf_image_io.hpp +++ b/io/include/pcl/io/impl/lzf_image_io.hpp @@ -147,7 +147,7 @@ pcl::io::LZFDepth16ImageReader::readOMP (const std::string &filename, #ifdef _OPENMP #pragma omp parallel for num_threads (num_threads) #else - (void) num_threads; // supress warning if OMP is not present + (void) num_threads; // suppress warning if OMP is not present #endif for (int i = 0; i < static_cast< int> (cloud.size ()); ++i) { @@ -278,7 +278,7 @@ pcl::io::LZFRGB24ImageReader::readOMP ( #ifdef _OPENMP #pragma omp parallel for num_threads (num_threads) #else - (void) num_threads; // supress warning if OMP is not present + (void) num_threads; // suppress warning if OMP is not present #endif//_OPENMP for (long int i = 0; i < cloud.size (); ++i) { diff --git a/io/include/pcl/io/oni_grabber.h b/io/include/pcl/io/oni_grabber.h index 907a40dffba..f02831f3e11 100644 --- a/io/include/pcl/io/oni_grabber.h +++ b/io/include/pcl/io/oni_grabber.h @@ -84,7 +84,7 @@ namespace pcl typedef void (sig_cb_openni_point_cloud_rgba) (const boost::shared_ptr >&); typedef void (sig_cb_openni_point_cloud_i) (const boost::shared_ptr >&); - /** \brief constuctor + /** \brief constructor * \param[in] file_name the path to the ONI file * \param[in] repeat whether the play back should be in an infinite loop or not * \param[in] stream whether the playback should be in streaming mode or in triggered mode. diff --git a/io/include/pcl/io/openni2/openni2_device.h b/io/include/pcl/io/openni2/openni2_device.h index 354de9f552d..4ae70f0b35a 100644 --- a/io/include/pcl/io/openni2/openni2_device.h +++ b/io/include/pcl/io/openni2/openni2_device.h @@ -230,21 +230,21 @@ namespace pcl void setUseDeviceTimer (bool enable); - /** \brief Get absolut number of depth frames in the current stream. + /** \brief Get absolute number of depth frames in the current stream. * This function returns 0 if the current device is not a file stream or * if the current mode has no depth stream. */ int getDepthFrameCount (); - /** \brief Get absolut number of color frames in the current stream. + /** \brief Get absolute number of color frames in the current stream. * This function returns 0 if the current device is not a file stream or * if the current mode has no color stream. */ int getColorFrameCount (); - /** \brief Get absolut number of ir frames in the current stream. + /** \brief Get absolute number of ir frames in the current stream. * This function returns 0 if the current device is not a file stream or * if the current mode has no ir stream. */ diff --git a/io/include/pcl/io/openni_camera/openni_driver.h b/io/include/pcl/io/openni_camera/openni_driver.h index 797549b6bef..ca3323f40e4 100644 --- a/io/include/pcl/io/openni_camera/openni_driver.h +++ b/io/include/pcl/io/openni_camera/openni_driver.h @@ -198,7 +198,7 @@ namespace openni_wrapper /** * @author Suat Gedikli * @brief decomposes the connection string into vendor id and product id. - * @param[in] connection_string the string containing teh connection information + * @param[in] connection_string the string containing the connection information * @param[out] vendorId the vendor id * @param[out] productId the product id */ diff --git a/io/include/pcl/io/pcd_io.h b/io/include/pcl/io/pcd_io.h index 6d078893098..cb8ac7a0707 100644 --- a/io/include/pcl/io/pcd_io.h +++ b/io/include/pcl/io/pcd_io.h @@ -70,7 +70,7 @@ namespace pcl * - POINTS ... * - DATA ascii/binary * - * Everything that follows \b DATA is intepreted as data points and + * Everything that follows \b DATA is interpreted as data points and * will be read accordingly. * * PCD_V7 represents PCD files with version 0.7 and has an important diff --git a/io/include/pcl/io/ply/byte_order.h b/io/include/pcl/io/ply/byte_order.h index 4fff118f5a5..2af95d01131 100644 --- a/io/include/pcl/io/ply/byte_order.h +++ b/io/include/pcl/io/ply/byte_order.h @@ -49,7 +49,7 @@ namespace pcl namespace ply { /** \file byte_order.h - * defines byte shift operations and endianess. + * defines byte shift operations and endianness. * \author Ares Lagae as part of libply, Nizar Sallem * \ingroup io */ diff --git a/io/include/pcl/io/ply_io.h b/io/include/pcl/io/ply_io.h index 44ab134ba00..3b525a845d4 100644 --- a/io/include/pcl/io/ply_io.h +++ b/io/include/pcl/io/ply_io.h @@ -742,7 +742,7 @@ namespace pcl { /** \brief Load a PLY v.6 file into a templated PointCloud type. * - * Any PLY files containg sensor data will generate a warning as a + * Any PLY files containing sensor data will generate a warning as a * pcl/PCLPointCloud2 message cannot hold the sensor origin. * * \param[in] file_name the name of the file to load @@ -760,7 +760,7 @@ namespace pcl * \param[in] file_name the name of the file to load * \param[in] cloud the resultant templated point cloud * \param[in] origin the sensor acquisition origin (only for > PLY_V7 - null if not present) - * \param[in] orientation the sensor acquisition orientation if availble, + * \param[in] orientation the sensor acquisition orientation if available, * identity if not present * \ingroup io */ @@ -787,7 +787,7 @@ namespace pcl /** \brief Load a PLY file into a PolygonMesh type. * - * Any PLY files containg sensor data will generate a warning as a + * Any PLY files containing sensor data will generate a warning as a * pcl/PolygonMesh message cannot hold the sensor origin. * * \param[in] file_name the name of the file to load diff --git a/io/include/pcl/io/real_sense_grabber.h b/io/include/pcl/io/real_sense_grabber.h index 4ddf3f06af7..583a1ade2c7 100644 --- a/io/include/pcl/io/real_sense_grabber.h +++ b/io/include/pcl/io/real_sense_grabber.h @@ -137,7 +137,7 @@ namespace pcl * If the default is supplied, then the mode closest to VGA at 30 Hz * will be chosen. * \param[in] strict if set to \c true, an exception will be thrown if - * device does not support exactly the mode requsted. Otherwise the + * device does not support exactly the mode requested. Otherwise the * closest available mode is selected. */ RealSenseGrabber (const std::string& device_id = "", const Mode& mode = Mode (), bool strict = false); diff --git a/io/src/ifs_io.cpp b/io/src/ifs_io.cpp index 247fca81b85..6424cbfe5dc 100644 --- a/io/src/ifs_io.cpp +++ b/io/src/ifs_io.cpp @@ -329,7 +329,7 @@ pcl::IFSWriter::write (const std::string &file_name, const pcl::PCLPointCloud2 & if (!cloud.is_dense) { - PCL_ERROR ("[pcl::IFSWriter::write] Non dense cloud are not alowed by IFS format!\n"); + PCL_ERROR ("[pcl::IFSWriter::write] Non dense cloud are not allowed by IFS format!\n"); return (-1); } diff --git a/io/src/openni2_grabber.cpp b/io/src/openni2_grabber.cpp index 1178a3630fe..d7addb67482 100644 --- a/io/src/openni2_grabber.cpp +++ b/io/src/openni2_grabber.cpp @@ -347,7 +347,7 @@ pcl::io::OpenNI2Grabber::setupDevice (const std::string& device_id, const Mode& } catch (...) { - PCL_THROW_EXCEPTION (pcl::IOException, "unknown error occured"); + PCL_THROW_EXCEPTION (pcl::IOException, "unknown error occurred"); } typedef pcl::io::openni2::OpenNI2VideoMode VideoMode; diff --git a/io/src/openni_grabber.cpp b/io/src/openni_grabber.cpp index 6f1e6ad7666..a67be1b988a 100644 --- a/io/src/openni_grabber.cpp +++ b/io/src/openni_grabber.cpp @@ -366,7 +366,7 @@ pcl::OpenNIGrabber::setupDevice (const std::string& device_id, const Mode& depth } catch (...) { - PCL_THROW_EXCEPTION (pcl::IOException, "unknown error occured"); + PCL_THROW_EXCEPTION (pcl::IOException, "unknown error occurred"); } XnMapOutputMode depth_md; diff --git a/io/src/pcd_grabber.cpp b/io/src/pcd_grabber.cpp index 1ee3a727cb1..0b14e1f1cf4 100644 --- a/io/src/pcd_grabber.cpp +++ b/io/src/pcd_grabber.cpp @@ -199,7 +199,7 @@ pcl::PCDGrabberBase::PCDGrabberImpl::readAhead () // Try to read in the file as a PCD first valid_ = (reader.read (*pcd_iterator_, next_cloud_, origin_, orientation_, pcd_version) == 0); - // Has an error occured? Check if we can interpret the file as a TAR file first before going onto the next + // Has an error occurred? Check if we can interpret the file as a TAR file first before going onto the next if (!valid_ && openTARFile (*pcd_iterator_) >= 0 && readTARHeader ()) { tar_file_ = *pcd_iterator_; @@ -241,7 +241,7 @@ pcl::PCDGrabberBase::PCDGrabberImpl::readTARHeader () } // We only support regular files for now. - // Addional file types in TAR include: hard links, symbolic links, device/special files, block devices, + // Additional file types in TAR include: hard links, symbolic links, device/special files, block devices, // directories, and named pipes. if (tar_header_.file_type[0] != '0' && tar_header_.file_type[0] != '\0') { diff --git a/io/src/ply/ply_parser.cpp b/io/src/ply/ply_parser.cpp index f678b612570..1f923b1c54d 100644 --- a/io/src/ply/ply_parser.cpp +++ b/io/src/ply/ply_parser.cpp @@ -380,7 +380,7 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename) { if (error_callback_) { - error_callback_ (line_number_, "parse error: unkonwn scalar type"); + error_callback_ (line_number_, "parse error: unknown scalar type"); } return false; } diff --git a/io/src/real_sense_grabber.cpp b/io/src/real_sense_grabber.cpp index 14a26882ca5..2b429a3fd20 100644 --- a/io/src/real_sense_grabber.cpp +++ b/io/src/real_sense_grabber.cpp @@ -323,7 +323,7 @@ pcl::RealSenseGrabber::run () frequency_.event (); fps_mutex_.unlock (); - /* We preform the following steps to convert received data into point clouds: + /* We perform the following steps to convert received data into point clouds: * * 1. Push depth image to the depth buffer * 2. Pull filtered depth image from the depth buffer diff --git a/io/tools/openni_pcd_recorder.cpp b/io/tools/openni_pcd_recorder.cpp index 1174498bcab..82358653f0e 100644 --- a/io/tools/openni_pcd_recorder.cpp +++ b/io/tools/openni_pcd_recorder.cpp @@ -298,7 +298,7 @@ class Consumer { boost::mutex::scoped_lock io_lock (io_mutex); - print_info ("Writing remaing %ld clouds in the buffer to disk...\n", buf_.getSize ()); + print_info ("Writing remaining %ld clouds in the buffer to disk...\n", buf_.getSize ()); } while (!buf_.isEmpty ()) writeToDisk (buf_.getFront ()); diff --git a/ml/include/pcl/ml/impl/kmeans.hpp b/ml/include/pcl/ml/impl/kmeans.hpp index 5afe11884a2..79449e4b78d 100644 --- a/ml/include/pcl/ml/impl/kmeans.hpp +++ b/ml/include/pcl/ml/impl/kmeans.hpp @@ -132,7 +132,7 @@ pcl::Kmeans::cluster (std::vector &clusters) } - // if cluster field name is set, check if field name is valied + // if cluster field name is set, check if field name is valid else { user_index = pcl::getFieldIndex (point, cluster_field_name_.c_str (), fields); diff --git a/ml/include/pcl/ml/regression_variance_stats_estimator.h b/ml/include/pcl/ml/regression_variance_stats_estimator.h index c7b94d40e46..ef7c247877f 100644 --- a/ml/include/pcl/ml/regression_variance_stats_estimator.h +++ b/ml/include/pcl/ml/regression_variance_stats_estimator.h @@ -156,7 +156,7 @@ namespace pcl * \param[in] data_set The data set corresponding to the supplied result data. * \param[in] examples The examples used for extracting the supplied result data. * \param[in] label_data The label data corresponding to the specified examples. - * \param[in] results The results computed using the specifed examples. + * \param[in] results The results computed using the specified examples. * \param[in] flags The flags corresponding to the results. * \param[in] threshold The threshold for which the information gain is computed. */ diff --git a/ml/src/kmeans.cpp b/ml/src/kmeans.cpp index 9cfcbaeef62..1b943246634 100644 --- a/ml/src/kmeans.cpp +++ b/ml/src/kmeans.cpp @@ -258,7 +258,7 @@ pcl::Kmeans::cluster (std::vector &clusters) /* } - // if cluster field name is set, check if field name is valied + // if cluster field name is set, check if field name is valid else { user_index = pcl::getFieldIndex (point, cluster_field_name_.c_str (), fields); diff --git a/ml/src/svm.cpp b/ml/src/svm.cpp index dcd6504a958..e9c162d0c4d 100755 --- a/ml/src/svm.cpp +++ b/ml/src/svm.cpp @@ -1981,7 +1981,7 @@ static decision_function svm_train_one ( return f; } -// Platt's binary SVM Probablistic Output: an improvement from Lin et al. +// Platt's binary SVM Probabilistic Output: an improvement from Lin et al. static void sigmoid_train ( int l, const double *dec_values, const double *labels, double& A, double& B) diff --git a/people/include/pcl/people/ground_based_people_detection_app.h b/people/include/pcl/people/ground_based_people_detection_app.h index e30bc2de7ac..9c07db1f492 100644 --- a/people/include/pcl/people/ground_based_people_detection_app.h +++ b/people/include/pcl/people/ground_based_people_detection_app.h @@ -150,7 +150,7 @@ namespace pcl /** * \brief Set sensor orientation (vertical = true means portrait mode, vertical = false means landscape mode). * - * \param[in] vertical Set landscape/portait camera orientation (default = false). + * \param[in] vertical Set landscape/portrait camera orientation (default = false). */ void setSensorPortraitOrientation (bool vertical); diff --git a/people/include/pcl/people/impl/head_based_subcluster.hpp b/people/include/pcl/people/impl/head_based_subcluster.hpp index 0c624c71423..5f88be2a107 100644 --- a/people/include/pcl/people/impl/head_based_subcluster.hpp +++ b/people/include/pcl/people/impl/head_based_subcluster.hpp @@ -210,7 +210,7 @@ pcl::people::HeadBasedSubclustering::createSubClusters (pcl::people::Per Eigen::Vector3f p_current_eigen(current_point->x, current_point->y, current_point->z); // conversion to eigen float t = p_current_eigen.dot(head_ground_coeffs) / normalize_factor; // height from the ground maxima_projected.col(i).matrix () = p_current_eigen - head_ground_coeffs * t; // projection of the point on the groundplane - subclusters_number_of_points(i) = 0; // intialize number of points + subclusters_number_of_points(i) = 0; // initialize number of points } // Associate cluster points to one of the maximum: diff --git a/recognition/include/pcl/recognition/color_gradient_modality.h b/recognition/include/pcl/recognition/color_gradient_modality.h index 295893be0d8..566d4622168 100644 --- a/recognition/include/pcl/recognition/color_gradient_modality.h +++ b/recognition/include/pcl/recognition/color_gradient_modality.h @@ -149,7 +149,7 @@ namespace pcl return (filtered_quantized_color_gradients_); } - /** \brief Returns a reference to the internally computed spreaded quantized map. */ + /** \brief Returns a reference to the internally computed spread quantized map. */ inline QuantizedMap & getSpreadedQuantizedMap () { @@ -243,7 +243,7 @@ namespace pcl /** \brief Determines whether variable numbers of features are extracted or not. */ bool variable_feature_nr_; - /** \brief Stores a smoothed verion of the input cloud. */ + /** \brief Stores a smoothed version of the input cloud. */ pcl::PointCloud::Ptr smoothed_input_; /** \brief Defines which feature selection method is used. */ @@ -264,7 +264,7 @@ namespace pcl pcl::QuantizedMap quantized_color_gradients_; /** \brief The map which holds the filtered quantized data. */ pcl::QuantizedMap filtered_quantized_color_gradients_; - /** \brief The map which holds the spreaded quantized data. */ + /** \brief The map which holds the spread quantized data. */ pcl::QuantizedMap spreaded_filtered_quantized_color_gradients_; }; diff --git a/recognition/include/pcl/recognition/crh_alignment.h b/recognition/include/pcl/recognition/crh_alignment.h index 0a2a45901da..43b81ad8870 100644 --- a/recognition/include/pcl/recognition/crh_alignment.h +++ b/recognition/include/pcl/recognition/crh_alignment.h @@ -176,7 +176,7 @@ namespace pcl } - /** \brief Computes the roll angle that aligns input to modle. + /** \brief Computes the roll angle that aligns input to model. * \param[in] input_ftt CRH histogram of the input cloud * \param[in] target_ftt CRH histogram of the target cloud * \param[out] peaks Vector containing angles where the histograms correlate diff --git a/recognition/include/pcl/recognition/hv/hv_go.h b/recognition/include/pcl/recognition/hv/hv_go.h index 557a26f6a60..7483c4c0cb2 100644 --- a/recognition/include/pcl/recognition/hv/hv_go.h +++ b/recognition/include/pcl/recognition/hv/hv_go.h @@ -94,7 +94,7 @@ namespace pcl { solution_[index] = val; //update optimizer solution - cost_ = opt_->evaluateSolution (solution_, index); //this will udpate the cost function in opt_ + cost_ = opt_->evaluateSolution (solution_, index); //this will update the cost function in opt_ } void setSolution(std::vector & sol) { diff --git a/recognition/include/pcl/recognition/impl/hv/greedy_verification.hpp b/recognition/include/pcl/recognition/impl/hv/greedy_verification.hpp index 9e2c4fedcc1..f3624dbf488 100644 --- a/recognition/include/pcl/recognition/impl/hv/greedy_verification.hpp +++ b/recognition/include/pcl/recognition/impl/hv/greedy_verification.hpp @@ -53,7 +53,7 @@ template // initialize explained_by_RM points_explained_by_rm_.resize (scene_cloud_downsampled_->points.size ()); - // initalize model + // initialize model for (size_t m = 0; m < visible_models_.size (); m++) { boost::shared_ptr < RecognitionModel > recog_model (new RecognitionModel); diff --git a/recognition/include/pcl/recognition/impl/hv/hv_papazov.hpp b/recognition/include/pcl/recognition/impl/hv/hv_papazov.hpp index 8e104bf7c21..fbca1c1f638 100644 --- a/recognition/include/pcl/recognition/impl/hv/hv_papazov.hpp +++ b/recognition/include/pcl/recognition/impl/hv/hv_papazov.hpp @@ -59,7 +59,7 @@ template explained_by_RM_.resize (scene_cloud_downsampled_->points.size ()); points_explained_by_rm_.resize (scene_cloud_downsampled_->points.size ()); - // initalize model + // initialize model for (size_t m = 0; m < complete_models_.size (); m++) { boost::shared_ptr < RecognitionModel > recog_model (new RecognitionModel); @@ -120,7 +120,7 @@ template } else { - mask_[m] = false; // the model didnt survive the sequential check... + mask_[m] = false; // the model didn't survive the sequential check... } } } diff --git a/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp b/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp index 2d5f5f7871b..8574ad1a56c 100644 --- a/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp +++ b/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp @@ -67,7 +67,7 @@ pcl::LineRGBD::readLTMHeader (int fd, pcl::io::TARHeader & return (false); // We only support regular files for now. - // Addional file types in TAR include: hard links, symbolic links, device/special files, block devices, + // Additional file types in TAR include: hard links, symbolic links, device/special files, block devices, // directories, and named pipes. if (header.file_type[0] != '0' && header.file_type[0] != '\0') return (false); diff --git a/recognition/include/pcl/recognition/implicit_shape_model.h b/recognition/include/pcl/recognition/implicit_shape_model.h index c643ef30fa2..845923c929c 100644 --- a/recognition/include/pcl/recognition/implicit_shape_model.h +++ b/recognition/include/pcl/recognition/implicit_shape_model.h @@ -357,7 +357,7 @@ namespace pcl void setTrainingClasses (const std::vector& training_classes); - /** \brief This method returns the coresponding cloud of normals for every training point cloud. */ + /** \brief This method returns the corresponding cloud of normals for every training point cloud. */ std::vector::Ptr> getTrainingNormals (); @@ -405,7 +405,7 @@ namespace pcl /** \brief This method allows to set the value of sigma used for calculating the learned weights for every single class. * \param[in] training_sigmas new sigmas for every class. If you want these values to be computed automatically, * just pass the empty array. The automatic regime calculates the maximum distance between the objects points and takes 10% of - * this value as recomended in the article. If there are several objects of the same class, + * this value as recommended in the article. If there are several objects of the same class, * then it computes the average maximum distance and takes 10%. Note that each class has its own sigma value. */ void @@ -435,7 +435,7 @@ namespace pcl * and returns the list of votes. * \param[in] model trained model which will be used for searching the objects * \param[in] in_cloud input cloud that need to be investigated - * \param[in] in_normals cloud of normals coresponding to the input cloud + * \param[in] in_normals cloud of normals corresponding to the input cloud * \param[in] in_class_of_interest class which we are looking for */ boost::shared_ptr > @@ -567,7 +567,7 @@ namespace pcl void generateRandomCenter (const std::vector >& boxes, Eigen::VectorXf& center); - /** \brief Computes the square distance beetween two vectors. + /** \brief Computes the square distance between two vectors. * \param[in] vec_1 first vector * \param[in] vec_2 second vector */ diff --git a/recognition/include/pcl/recognition/linemod/line_rgbd.h b/recognition/include/pcl/recognition/linemod/line_rgbd.h index 8b1b3f381a1..c0d6dcecd3e 100644 --- a/recognition/include/pcl/recognition/linemod/line_rgbd.h +++ b/recognition/include/pcl/recognition/linemod/line_rgbd.h @@ -209,7 +209,7 @@ namespace pcl void detect (std::vector::Detection> & detections); - /** \brief Applies the detection process in a semi-scale-invariant manner. This is done by acutally + /** \brief Applies the detection process in a semi-scale-invariant manner. This is done by actually * scaling the template to different sizes. */ void @@ -304,7 +304,7 @@ namespace pcl /** \brief Point clouds corresponding to the templates. */ pcl::PointCloud::CloudVectorType template_point_clouds_; - /** \brief Bounding boxes corresonding to the templates. */ + /** \brief Bounding boxes corresponding to the templates. */ std::vector bounding_boxes_; /** \brief Object IDs corresponding to the templates. */ std::vector object_ids_; diff --git a/recognition/include/pcl/recognition/quantizable_modality.h b/recognition/include/pcl/recognition/quantizable_modality.h index c64617b63f2..c7dcaee146b 100644 --- a/recognition/include/pcl/recognition/quantizable_modality.h +++ b/recognition/include/pcl/recognition/quantizable_modality.h @@ -62,7 +62,7 @@ namespace pcl virtual QuantizedMap & getQuantizedMap () = 0; - /** \brief Returns a reference to the internally computed spreaded quantized map. */ + /** \brief Returns a reference to the internally computed spread quantized map. */ virtual QuantizedMap & getSpreadedQuantizedMap () = 0; diff --git a/recognition/include/pcl/recognition/ransac_based/voxel_structure.h b/recognition/include/pcl/recognition/ransac_based/voxel_structure.h index ed90c4d3965..b3819031b66 100644 --- a/recognition/include/pcl/recognition/ransac_based/voxel_structure.h +++ b/recognition/include/pcl/recognition/ransac_based/voxel_structure.h @@ -160,7 +160,7 @@ namespace pcl T *voxels_; int num_of_voxels_[3], num_of_voxels_xy_plane_, total_num_of_voxels_; REAL bounds_[6]; - REAL spacing_[3]; // spacing betwen the voxel in x, y and z direction = voxel size in x, y and z direction + REAL spacing_[3]; // spacing between the voxel in x, y and z direction = voxel size in x, y and z direction REAL min_center_[3]; // the center of the voxel with integer coordinates (0, 0, 0) }; } // namespace recognition diff --git a/recognition/include/pcl/recognition/surface_normal_modality.h b/recognition/include/pcl/recognition/surface_normal_modality.h index f9b088c3fea..4e4f876ff62 100644 --- a/recognition/include/pcl/recognition/surface_normal_modality.h +++ b/recognition/include/pcl/recognition/surface_normal_modality.h @@ -372,7 +372,7 @@ namespace pcl return (filtered_quantized_surface_normals_); } - /** \brief Returns a reference to the internal spreaded quantized map. */ + /** \brief Returns a reference to the internal spread quantized map. */ inline QuantizedMap & getSpreadedQuantizedMap () { @@ -476,7 +476,7 @@ namespace pcl pcl::QuantizedMap quantized_surface_normals_; /** \brief Filtered quantized surface normals. */ pcl::QuantizedMap filtered_quantized_surface_normals_; - /** \brief Spreaded quantized surface normals. */ + /** \brief Spread quantized surface normals. */ pcl::QuantizedMap spreaded_quantized_surface_normals_; /** \brief Map containing surface normal orientations. */ diff --git a/registration/include/pcl/registration/transformation_estimation_lm.h b/registration/include/pcl/registration/transformation_estimation_lm.h index 86520b311b5..601b3fc5b21 100644 --- a/registration/include/pcl/registration/transformation_estimation_lm.h +++ b/registration/include/pcl/registration/transformation_estimation_lm.h @@ -219,7 +219,7 @@ namespace pcl /** Base functor all the models that need non linear optimization must * define their own one and implement operator() (const Eigen::VectorXd& x, Eigen::VectorXd& fvec) - * or operator() (const Eigen::VectorXf& x, Eigen::VectorXf& fvec) dependening on the chosen _Scalar + * or operator() (const Eigen::VectorXf& x, Eigen::VectorXf& fvec) depending on the chosen _Scalar */ template struct Functor diff --git a/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h b/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h index 1fe0fa5c0c5..42931cb03c2 100644 --- a/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h +++ b/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h @@ -204,7 +204,7 @@ namespace pcl /** Base functor all the models that need non linear optimization must * define their own one and implement operator() (const Eigen::VectorXd& x, Eigen::VectorXd& fvec) - * or operator() (const Eigen::VectorXf& x, Eigen::VectorXf& fvec) dependening on the chosen _Scalar + * or operator() (const Eigen::VectorXf& x, Eigen::VectorXf& fvec) depending on the chosen _Scalar */ template struct Functor diff --git a/sample_consensus/include/pcl/sample_consensus/impl/lmeds.hpp b/sample_consensus/include/pcl/sample_consensus/impl/lmeds.hpp index c24e988aeba..960e3c0b87b 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/lmeds.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/lmeds.hpp @@ -65,7 +65,7 @@ pcl::LeastMedianSquares::computeModel (int debug_verbosity_level) int n_inliers_count = 0; unsigned skipped_count = 0; - // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + // suppress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! const unsigned max_skip = max_iterations_ * 10; // Iterate diff --git a/sample_consensus/include/pcl/sample_consensus/impl/mlesac.hpp b/sample_consensus/include/pcl/sample_consensus/impl/mlesac.hpp index 7c6141e2cd2..a92cf3881bf 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/mlesac.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/mlesac.hpp @@ -78,7 +78,7 @@ pcl::MaximumLikelihoodSampleConsensus::computeModel (int debug_verbosity int n_inliers_count = 0; size_t indices_size; unsigned skipped_count = 0; - // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + // suppress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! const unsigned max_skip = max_iterations_ * 10; // Iterate diff --git a/sample_consensus/include/pcl/sample_consensus/impl/msac.hpp b/sample_consensus/include/pcl/sample_consensus/impl/msac.hpp index 659d338eaf8..888db53cbaa 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/msac.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/msac.hpp @@ -65,7 +65,7 @@ pcl::MEstimatorSampleConsensus::computeModel (int debug_verbosity_level) int n_inliers_count = 0; unsigned skipped_count = 0; - // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + // suppress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! const unsigned max_skip = max_iterations_ * 10; // Iterate diff --git a/sample_consensus/include/pcl/sample_consensus/impl/ransac.hpp b/sample_consensus/include/pcl/sample_consensus/impl/ransac.hpp index 3c174feadb6..bab6a1b9b31 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/ransac.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/ransac.hpp @@ -66,7 +66,7 @@ pcl::RandomSampleConsensus::computeModel (int) int n_inliers_count = 0; unsigned skipped_count = 0; - // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + // suppress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! const unsigned max_skip = max_iterations_ * 10; // Iterate diff --git a/sample_consensus/include/pcl/sample_consensus/impl/rmsac.hpp b/sample_consensus/include/pcl/sample_consensus/impl/rmsac.hpp index 186f30334b7..4948735c081 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/rmsac.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/rmsac.hpp @@ -66,7 +66,7 @@ pcl::RandomizedMEstimatorSampleConsensus::computeModel (int debug_verbos int n_inliers_count = 0; unsigned skipped_count = 0; - // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + // suppress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! const unsigned max_skip = max_iterations_ * 10; // Number of samples to try randomly diff --git a/sample_consensus/include/pcl/sample_consensus/impl/rransac.hpp b/sample_consensus/include/pcl/sample_consensus/impl/rransac.hpp index 338780dc004..62aed6f42c6 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/rransac.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/rransac.hpp @@ -64,7 +64,7 @@ pcl::RandomizedRandomSampleConsensus::computeModel (int debug_verbosity_ int n_inliers_count = 0; unsigned skipped_count = 0; - // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + // suppress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! const unsigned max_skip = max_iterations_ * 10; // Number of samples to try randomly diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp index 0b310515db4..dd1a29a1ead 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp @@ -172,7 +172,7 @@ pcl::SampleConsensusModelCone::getDistancesToModel ( // Calculate the cones perfect normals Eigen::Vector4f cone_normal = sinf (opening_angle) * height + cosf (opening_angle) * dir; - // Aproximate the distance from the point to the cone as the difference between + // Approximate the distance from the point to the cone as the difference between // dist(point,cone_axis) and actual cone radius double d_euclid = fabs (pointToAxisDistance (pt, model_coefficients) - actual_cone_radius); @@ -228,7 +228,7 @@ pcl::SampleConsensusModelCone::selectWithinDistance ( // Calculate the cones perfect normals Eigen::Vector4f cone_normal = sinf (opening_angle) * height + cosf (opening_angle) * pp_pt_dir; - // Aproximate the distance from the point to the cone as the difference between + // Approximate the distance from the point to the cone as the difference between // dist(point,cone_axis) and actual cone radius double d_euclid = fabs (pointToAxisDistance (pt, model_coefficients) - actual_cone_radius); @@ -290,7 +290,7 @@ pcl::SampleConsensusModelCone::countWithinDistance ( // Calculate the cones perfect normals Eigen::Vector4f cone_normal = sinf (opening_angle) * height + cosf (opening_angle) * pp_pt_dir; - // Aproximate the distance from the point to the cone as the difference between + // Approximate the distance from the point to the cone as the difference between // dist(point,cone_axis) and actual cone radius double d_euclid = fabs (pointToAxisDistance (pt, model_coefficients) - actual_cone_radius); @@ -473,7 +473,7 @@ pcl::SampleConsensusModelCone::doSamplesVerifyModel ( Eigen::Vector4f height = apex - pt_proj; double actual_cone_radius = tan (openning_angle) * height.norm (); - // Aproximate the distance from the point to the cone as the difference between + // Approximate the distance from the point to the cone as the difference between // dist(point,cone_axis) and actual cone radius if (fabs (static_cast(pointToAxisDistance (pt, model_coefficients) - actual_cone_radius)) > threshold) return (false); diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp index 190115b2385..798c41c79a4 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp @@ -147,7 +147,7 @@ pcl::SampleConsensusModelCylinder::getDistancesToModel ( // Iterate through the 3d points and calculate the distances from them to the sphere for (size_t i = 0; i < indices_->size (); ++i) { - // Aproximate the distance from the point to the cylinder as the difference between + // Approximate the distance from the point to the cylinder as the difference between // dist(point,cylinder_axis) and cylinder radius // @note need to revise this. Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0); @@ -192,7 +192,7 @@ pcl::SampleConsensusModelCylinder::selectWithinDistance ( // Iterate through the 3d points and calculate the distances from them to the sphere for (size_t i = 0; i < indices_->size (); ++i) { - // Aproximate the distance from the point to the cylinder as the difference between + // Approximate the distance from the point to the cylinder as the difference between // dist(point,cylinder_axis) and cylinder radius Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0); Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0); @@ -239,7 +239,7 @@ pcl::SampleConsensusModelCylinder::countWithinDistance ( // Iterate through the 3d points and calculate the distances from them to the sphere for (size_t i = 0; i < indices_->size (); ++i) { - // Aproximate the distance from the point to the cylinder as the difference between + // Approximate the distance from the point to the cylinder as the difference between // dist(point,cylinder_axis) and cylinder radius Eigen::Vector4f pt (input_->points[(*indices_)[i]].x, input_->points[(*indices_)[i]].y, input_->points[(*indices_)[i]].z, 0); Eigen::Vector4f n (normals_->points[(*indices_)[i]].normal[0], normals_->points[(*indices_)[i]].normal[1], normals_->points[(*indices_)[i]].normal[2], 0); @@ -400,7 +400,7 @@ pcl::SampleConsensusModelCylinder::doSamplesVerifyModel ( for (std::set::const_iterator it = indices.begin (); it != indices.end (); ++it) { - // Aproximate the distance from the point to the cylinder as the difference between + // Approximate the distance from the point to the cylinder as the difference between // dist(point,cylinder_axis) and cylinder radius // @note need to revise this. Eigen::Vector4f pt (input_->points[*it].x, input_->points[*it].y, input_->points[*it].z, 0); diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model.h b/sample_consensus/include/pcl/sample_consensus/sac_model.h index f1b80556baf..7cd0a72e6d9 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model.h @@ -647,7 +647,7 @@ namespace pcl /** Base functor all the models that need non linear optimization must * define their own one and implement operator() (const Eigen::VectorXd& x, Eigen::VectorXd& fvec) - * or operator() (const Eigen::VectorXf& x, Eigen::VectorXf& fvec) dependening on the choosen _Scalar + * or operator() (const Eigen::VectorXf& x, Eigen::VectorXf& fvec) depending on the chosen _Scalar */ template struct Functor diff --git a/segmentation/include/pcl/segmentation/cpc_segmentation.h b/segmentation/include/pcl/segmentation/cpc_segmentation.h index 70a20932c75..cc10277fd66 100644 --- a/segmentation/include/pcl/segmentation/cpc_segmentation.h +++ b/segmentation/include/pcl/segmentation/cpc_segmentation.h @@ -157,7 +157,7 @@ namespace pcl /** \brief Use clean cutting */ bool use_clean_cutting_; - /** \brief Interations for RANSAC */ + /** \brief Iterations for RANSAC */ uint32_t ransac_itrs_; diff --git a/segmentation/include/pcl/segmentation/grabcut_segmentation.h b/segmentation/include/pcl/segmentation/grabcut_segmentation.h index 378bc022bba..caef3ba6005 100644 --- a/segmentation/include/pcl/segmentation/grabcut_segmentation.h +++ b/segmentation/include/pcl/segmentation/grabcut_segmentation.h @@ -195,7 +195,7 @@ namespace pcl colorDistance (const Color& c1, const Color& c2); /// User supplied Trimap values enum TrimapValue { TrimapUnknown = -1, TrimapForeground, TrimapBackground }; - /// Grabcut derived hard segementation values + /// Grabcut derived hard segmentation values enum SegmentationValue { SegmentationForeground = 0, SegmentationBackground }; /// Gaussian structure struct Gaussian @@ -211,9 +211,9 @@ namespace pcl Eigen::Matrix3f inverse; /// weighting of this gaussian in the GMM. float pi; - /// heighest eigenvalue of covariance matrix + /// highest eigenvalue of covariance matrix float eigenvalue; - /// eigenvector corresponding to the heighest eigenvector + /// eigenvector corresponding to the highest eigenvector Eigen::Vector3f eigenvector; }; @@ -332,7 +332,7 @@ namespace pcl , nb_neighbours_ (9) , initialized_ (false) {} - /// Desctructor + /// Destructor virtual ~GrabCut () {}; // /// Set input cloud void diff --git a/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp index 30f789b8342..967267f8458 100644 --- a/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp @@ -68,7 +68,7 @@ pcl::CPCSegmentation::segment () // Correct edge relations using extended convexity definition if k>0 applyKconvexity (k_factor_); - // Determine wether to use cutting planes + // Determine whether to use cutting planes doGrouping (); grouping_data_valid_ = true; @@ -98,7 +98,7 @@ pcl::CPCSegmentation::applyCuttingPlane (uint32_t depth_levels_left) boost::tie (edge_itr, edge_itr_end) = boost::edges (sv_adjacency_list_); for (next_edge = edge_itr; edge_itr != edge_itr_end; edge_itr = next_edge) { - next_edge++; // next_edge iterator is neccessary, because removing an edge invalidates the iterator to the current edge + next_edge++; // next_edge iterator is necessary, because removing an edge invalidates the iterator to the current edge uint32_t source_sv_label = sv_adjacency_list_[boost::source (*edge_itr, sv_adjacency_list_)]; uint32_t target_sv_label = sv_adjacency_list_[boost::target (*edge_itr, sv_adjacency_list_)]; @@ -183,7 +183,7 @@ pcl::CPCSegmentation::applyCuttingPlane (uint32_t depth_levels_left) Eigen::Vector3f plane_normal (model_coefficients[0], model_coefficients[1], model_coefficients[2]); // Cut the connections. // We only interate through the points which are within the support (when we are local, otherwise all points in the segment). - // We also just acutally cut when the edge goes through the plane. This is why we check the planedistance + // We also just actually cut when the edge goes through the plane. This is why we check the planedistance std::vector cluster_indices; pcl::EuclideanClusterExtraction euclidean_clusterer; pcl::search::KdTree::Ptr tree (new pcl::search::KdTree); @@ -225,7 +225,7 @@ pcl::CPCSegmentation::applyCuttingPlane (uint32_t depth_levels_left) } if (cut_support_indices.size () == 0) { -// std::cout << "Could not find planes which exceed required minumum score (threshold " << min_cut_score_ << "), not cutting" << std::endl; +// std::cout << "Could not find planes which exceed required minimum score (threshold " << min_cut_score_ << "), not cutting" << std::endl; continue; } } @@ -303,7 +303,7 @@ pcl::CPCSegmentation::WeightedRandomSampleConsensus::computeModel (int) Eigen::VectorXf model_coefficients; unsigned skipped_count = 0; - // supress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! + // suppress infinite loops by just allowing 10 x maximum allowed iterations for invalid model parameters! const unsigned max_skip = max_iterations_ * 10; // Iterate diff --git a/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp index 34f55b5b671..72b6eec6f8f 100644 --- a/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp @@ -248,7 +248,7 @@ pcl::LCCPSegmentation::mergeSmallSegments () // After filtered Segments are deleted, compute completely new adjacency map // NOTE Recomputing the adjacency of every segment in every iteration is an easy but inefficient solution. - // Because the number of segments in an average scene is usually well below 1000, the time spend for noise filtering is still neglible in most cases + // Because the number of segments in an average scene is usually well below 1000, the time spend for noise filtering is still negligible in most cases computeSegmentAdjacency (); } // End while (Filtering) } @@ -349,7 +349,7 @@ pcl::LCCPSegmentation::recursiveSegmentGrowing (const VertexID &query_po sv_label_to_seg_label_map_[sv_label] = segment_label; seg_label_to_sv_list_map_[segment_label].insert (sv_label); - // Iterate through all neighbors of this supervoxel and check wether they should be merged with the current supervoxel + // Iterate through all neighbors of this supervoxel and check whether they should be merged with the current supervoxel std::pair out_edge_iterator_range; out_edge_iterator_range = boost::out_edges (query_point_id, sv_adjacency_list_); // adjacent vertices to node (*itr) in graph sv_adjacency_list_ for (OutEdgeIterator out_Edge_itr = out_edge_iterator_range.first; out_Edge_itr != out_edge_iterator_range.second; ++out_Edge_itr) @@ -385,7 +385,7 @@ pcl::LCCPSegmentation::applyKconvexity (const unsigned int k_arg) // Check all edges in the graph for k-convexity for (next_edge = edge_itr; edge_itr != edge_itr_end; edge_itr = next_edge) { - next_edge++; // next_edge iterator is neccessary, because removing an edge invalidates the iterator to the current edge + next_edge++; // next_edge iterator is necessary, because removing an edge invalidates the iterator to the current edge is_convex = sv_adjacency_list_[*edge_itr].is_convex; @@ -443,7 +443,7 @@ pcl::LCCPSegmentation::calculateConvexConnections (SupervoxelAdjacencyLi for (next_edge = edge_itr; edge_itr != edge_itr_end; edge_itr = next_edge) { - next_edge++; // next_edge iterator is neccessary, because removing an edge invalidates the iterator to the current edge + next_edge++; // next_edge iterator is necessary, because removing an edge invalidates the iterator to the current edge uint32_t source_sv_label = adjacency_list_arg[boost::source (*edge_itr, adjacency_list_arg)]; uint32_t target_sv_label = adjacency_list_arg[boost::target (*edge_itr, adjacency_list_arg)]; diff --git a/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp index b0fb6ca82a7..71112e44100 100644 --- a/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp @@ -68,7 +68,7 @@ pcl::OrganizedConnectedComponentSegmentation::findLabeledRegion Neighbor( 0, 1, labels->width ), Neighbor(-1, 1, labels->width - 1)}; - // find one pixel with other label in the neighborhood -> assume thats the one we came from + // find one pixel with other label in the neighborhood -> assume that's the one we came from int direction = -1; int x; int y; diff --git a/segmentation/include/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp index fadd1795195..bfe32493879 100644 --- a/segmentation/include/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/organized_multi_plane_segmentation.hpp @@ -317,7 +317,7 @@ pcl::OrganizedMultiPlaneSegmentation::refine (std::vec PointCloudLPtr& labels, std::vector& label_indices) { - //List of lables to grow, and index of model corresponding to each label + //List of labels to grow, and index of model corresponding to each label std::vector grow_labels; std::vector label_to_model; grow_labels.resize (label_indices.size (), false); diff --git a/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp b/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp index a49fa681657..a78cb1cc961 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp @@ -317,12 +317,12 @@ pcl::RegionGrowingRGB::findRegionsKNN (int index, int nghbr_num distances.resize (clusters_.size (), max_dist); int number_of_points = num_pts_in_segment_[index]; - //loop throug every point in this segment and check neighbours + //loop through every point in this segment and check neighbours for (int i_point = 0; i_point < number_of_points; i_point++) { int point_index = clusters_[index].indices[i_point]; int number_of_neighbours = static_cast (point_neighbours_[point_index].size ()); - //loop throug every neighbour of the current point, find out to which segment it belongs + //loop through every neighbour of the current point, find out to which segment it belongs //and if it belongs to neighbouring segment and is close enough then remember segment and its distance for (int i_nghbr = 0; i_nghbr < number_of_neighbours; i_nghbr++) { diff --git a/segmentation/include/pcl/segmentation/lccp_segmentation.h b/segmentation/include/pcl/segmentation/lccp_segmentation.h index b3887e762f2..bcba027912f 100644 --- a/segmentation/include/pcl/segmentation/lccp_segmentation.h +++ b/segmentation/include/pcl/segmentation/lccp_segmentation.h @@ -61,10 +61,10 @@ namespace pcl /** \brief Edge Properties stored in the adjacency graph.*/ struct EdgeProperties { - /** \brief Desribes the difference of normals of the two supervoxels being connected*/ + /** \brief Describes the difference of normals of the two supervoxels being connected*/ float normal_difference; - /** \brief Desribes if a connection is convex or concave*/ + /** \brief Describes if a connection is convex or concave*/ bool is_convex; /** \brief Describes if a connection is valid for the segment growing. Usually convex connections are and concave connection are not. Due to k-concavity a convex connection can be invalidated*/ @@ -301,7 +301,7 @@ namespace pcl /** \brief Normal Threshold in degrees [0,180] used for merging */ float concavity_tolerance_threshold_; - /** \brief Marks if valid grouping data (\ref sv_adjacency_list_, \ref sv_label_to_seg_label_map_, \ref processed_) is avaiable */ + /** \brief Marks if valid grouping data (\ref sv_adjacency_list_, \ref sv_label_to_seg_label_map_, \ref processed_) is available */ bool grouping_data_valid_; /** \brief Marks if supervoxels have been set by calling \ref setInputSupervoxels */ diff --git a/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h b/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h index a02a3c0a01c..d5ab2304be7 100644 --- a/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h +++ b/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h @@ -111,7 +111,7 @@ namespace pcl segment (pcl::PointCloud& labels, std::vector& label_indices) const; /** \brief Find the boundary points / contour of a connected component - * \param[in] start_idx the first (lowest) index of the connected component for which a boundary shoudl be returned + * \param[in] start_idx the first (lowest) index of the connected component for which a boundary should be returned * \param[in] labels the Label cloud produced by segmentation * \param[out] boundary_indices the indices of the boundary points for the label corresponding to start_idx */ diff --git a/segmentation/include/pcl/segmentation/sac_segmentation.h b/segmentation/include/pcl/segmentation/sac_segmentation.h index 41bc27d5ce4..c5e28e9bfd1 100644 --- a/segmentation/include/pcl/segmentation/sac_segmentation.h +++ b/segmentation/include/pcl/segmentation/sac_segmentation.h @@ -370,7 +370,7 @@ namespace pcl getNormalDistanceWeight () const { return (distance_weight_); } /** \brief Set the minimum opning angle for a cone model. - * \param min_angle the opening angle which we need minumum to validate a cone model. + * \param min_angle the opening angle which we need minimum to validate a cone model. * \param max_angle the opening angle which we need maximum to validate a cone model. */ inline void @@ -380,7 +380,7 @@ namespace pcl max_angle_ = max_angle; } - /** \brief Get the opening angle which we need minumum to validate a cone model. */ + /** \brief Get the opening angle which we need minimum to validate a cone model. */ inline void getMinMaxOpeningAngle (double &min_angle, double &max_angle) { diff --git a/segmentation/include/pcl/segmentation/supervoxel_clustering.h b/segmentation/include/pcl/segmentation/supervoxel_clustering.h index 1048fe590e7..05e6002752c 100644 --- a/segmentation/include/pcl/segmentation/supervoxel_clustering.h +++ b/segmentation/include/pcl/segmentation/supervoxel_clustering.h @@ -272,7 +272,7 @@ namespace pcl * Points that belong to the same supervoxel have the same color. * But this function doesn't guarantee that different segments will have different * color(it's random). Points that are unlabeled will be black - * \note This will expand the label_colors_ vector so that it can accomodate all labels + * \note This will expand the label_colors_ vector so that it can accommodate all labels */ PCL_DEPRECATED ("SupervoxelClustering::getColoredCloud is deprecated. Use the getLabeledCloud function instead. examples/segmentation/example_supervoxels.cpp shows how to use this to display and save with colorized labels.") typename pcl::PointCloud::Ptr @@ -297,7 +297,7 @@ namespace pcl * Points that belong to the same supervoxel have the same color. * But this function doesn't guarantee that different segments will have different * color(it's random). Points that are unlabeled will be black - * \note This will expand the label_colors_ vector so that it can accomodate all labels + * \note This will expand the label_colors_ vector so that it can accommodate all labels */ PCL_DEPRECATED ("SupervoxelClustering::getColoredVoxelCloud is deprecated. Use the getLabeledVoxelCloud function instead. examples/segmentation/example_supervoxels.cpp shows how to use this to display and save with colorized labels.") pcl::PointCloud::Ptr diff --git a/segmentation/src/supervoxel_clustering.cpp b/segmentation/src/supervoxel_clustering.cpp index da81d0b1f44..41cad71fc93 100644 --- a/segmentation/src/supervoxel_clustering.cpp +++ b/segmentation/src/supervoxel_clustering.cpp @@ -63,7 +63,7 @@ namespace pcl data_.xyz_[0] += new_point.x; data_.xyz_[1] += new_point.y; data_.xyz_[2] += new_point.z; - //Separate sums for r,g,b since we cant sum in uchars + //Separate sums for r,g,b since we can't sum in uchars data_.rgb_[0] += static_cast (new_point.r); data_.rgb_[1] += static_cast (new_point.g); data_.rgb_[2] += static_cast (new_point.b); @@ -78,7 +78,7 @@ namespace pcl data_.xyz_[0] += new_point.x; data_.xyz_[1] += new_point.y; data_.xyz_[2] += new_point.z; - //Separate sums for r,g,b since we cant sum in uchars + //Separate sums for r,g,b since we can't sum in uchars data_.rgb_[0] += static_cast (new_point.r); data_.rgb_[1] += static_cast (new_point.g); data_.rgb_[2] += static_cast (new_point.b); diff --git a/simulation/src/model.cpp b/simulation/src/model.cpp index 70d6126be03..39d6f17f16d 100644 --- a/simulation/src/model.cpp +++ b/simulation/src/model.cpp @@ -144,7 +144,7 @@ pcl::simulation::PolygonMeshModel::PolygonMeshModel (GLenum mode, pcl::PolygonMe apoly.colors_[4*j + 0] = newcloud.points[pt].r/255.0f; // Red apoly.colors_[4*j + 1] = newcloud.points[pt].g/255.0f; // Green apoly.colors_[4*j + 2] = newcloud.points[pt].b/255.0f; // Blue - apoly.colors_[4*j + 3] = 1.0f; // transparancy? unnecessary? + apoly.colors_[4*j + 3] = 1.0f; // transparency? unnecessary? } polygons.push_back (apoly); } diff --git a/simulation/src/range_likelihood.cpp b/simulation/src/range_likelihood.cpp index 3110d6b13ce..5c77cd3b1d1 100644 --- a/simulation/src/range_likelihood.cpp +++ b/simulation/src/range_likelihood.cpp @@ -505,7 +505,7 @@ costFunction3 (float ref_val,float depth_val) { // working range float min_dist = abs (ref_val - 0.7253f/(1.0360f - (depth_val))); - int lup = static_cast (ceil (min_dist*100)); // has resulution of 0.01m + int lup = static_cast (ceil (min_dist*100)); // has resolution of 0.01m if (lup > 300) { // implicitly this caps the cost if there is a hole in the model lup = 300; @@ -520,7 +520,7 @@ costFunction4(float ref_val,float depth_val) { float disparity_diff = abs( ( -0.7253f/ref_val +1.0360f ) - depth_val ); - int top_lup = static_cast (ceil (disparity_diff*300)); // has resulution of 0.001m + int top_lup = static_cast (ceil (disparity_diff*300)); // has resolution of 0.001m if (top_lup > 300) { top_lup =300; @@ -529,7 +529,7 @@ costFunction4(float ref_val,float depth_val) // bottom: //bottom = bottom_lookup( round(mu*1000+1)); - int bottom_lup = static_cast (ceil( (depth_val) * 300)); // has resulution of 0.001m + int bottom_lup = static_cast (ceil( (depth_val) * 300)); // has resolution of 0.001m if (bottom_lup > 300) { bottom_lup =300; diff --git a/simulation/tools/README_about_tools b/simulation/tools/README_about_tools index 60f26f1640e..5c4d778cf14 100644 --- a/simulation/tools/README_about_tools +++ b/simulation/tools/README_about_tools @@ -4,7 +4,7 @@ mfallon and hordurj march 2012 1. sim_viewer.cpp purpose: simulate in viewer which is almost the same as pcl_viewer status : use the mouse to drive around, and 'v' to capture a cloud. reads vtk and obj. - visualizes vtk and makes pcd of obj. conflict between RL and VTK means doesnt visualize/simulate properly + visualizes vtk and makes pcd of obj. conflict between RL and VTK means doesn't visualize/simulate properly was : range_pcd_viewer.cpp 2. sim_terminal_demo.cpp diff --git a/simulation/tools/sim_test_simple.cpp b/simulation/tools/sim_test_simple.cpp index c77987b576e..1c5aac5edfe 100644 --- a/simulation/tools/sim_test_simple.cpp +++ b/simulation/tools/sim_test_simple.cpp @@ -416,14 +416,14 @@ void display () boost::this_thread::sleep (boost::posix_time::microseconds (100000)); } - // doesnt work: + // doesn't work: // viewer->~PCLVisualizer(); // viewer.reset(); cout << "done\n"; - // Problem: vtk and opengl dont seem to play very well together - // vtk seems to misbehave after a little while and wont keep the window on the screen + // Problem: vtk and opengl don't seem to play very well together + // vtk seems to misbehave after a little while and won't keep the window on the screen // method1: kill with [x] - but eventually it crashes: //while (!viewer.wasStopped ()){ diff --git a/simulation/tools/sim_viewer.cpp b/simulation/tools/sim_viewer.cpp index 709453957d7..12f4e901107 100644 --- a/simulation/tools/sim_viewer.cpp +++ b/simulation/tools/sim_viewer.cpp @@ -392,7 +392,7 @@ boost::shared_ptr simpleVis (pcl::PointCloud< void capture (Eigen::Isometry3d pose_in, string point_cloud_fname) { - // No reference image - but this is kept for compatability with range_test_v2: + // No reference image - but this is kept for compatibility with range_test_v2: float* reference = new float[range_likelihood_->getRowHeight() * range_likelihood_->getColWidth()]; const float* depth_buffer = range_likelihood_->getDepthBuffer(); // Copy one image from our last as a reference. @@ -471,7 +471,7 @@ void capture (Eigen::Isometry3d pose_in, string point_cloud_fname) writer.writeBinary (point_cloud_fname, *pc_out); //cout << "finished writing file\n"; } - // Disabled all OpenCV stuff for now: dont want the dependency + // Disabled all OpenCV stuff for now: don't want the dependency /* bool demo_other_stuff = false; if (demo_other_stuff && write_cloud) diff --git a/simulation/tools/simulation_io.cpp b/simulation/tools/simulation_io.cpp index 1b6bfdb46d3..ca5b0707efc 100644 --- a/simulation/tools/simulation_io.cpp +++ b/simulation/tools/simulation_io.cpp @@ -97,7 +97,7 @@ pcl::simulation::SimExample::initializeGL (int argc, char** argv) void pcl::simulation::SimExample::doSim (Eigen::Isometry3d pose_in) { - // No reference image - but this is kept for compatability with range_test_v2: + // No reference image - but this is kept for compatibility with range_test_v2: float* reference = new float[rl_->getRowHeight() * rl_->getColWidth()]; const float* depth_buffer = rl_->getDepthBuffer(); // Copy one image from our last as a reference. diff --git a/stereo/include/pcl/stereo/stereo_matching.h b/stereo/include/pcl/stereo/stereo_matching.h index d3b7e969f74..0c6d3d0a6a7 100644 --- a/stereo/include/pcl/stereo/stereo_matching.h +++ b/stereo/include/pcl/stereo/stereo_matching.h @@ -458,8 +458,8 @@ namespace pcl radius_ = radius; }; - /** \brief setter for the spatial bandwith used for cost aggregation based on adaptive weights - * \param[in] gamma_s spatial bandwith used for cost aggregation based on adaptive weights + /** \brief setter for the spatial bandwidth used for cost aggregation based on adaptive weights + * \param[in] gamma_s spatial bandwidth used for cost aggregation based on adaptive weights */ void setGammaS (int gamma_s) @@ -467,8 +467,8 @@ namespace pcl gamma_s_ = gamma_s; }; - /** \brief setter for the color bandwith used for cost aggregation based on adaptive weights - * \param[in] gamma_c color bandwith used for cost aggregation based on adaptive weights + /** \brief setter for the color bandwidth used for cost aggregation based on adaptive weights + * \param[in] gamma_c color bandwidth used for cost aggregation based on adaptive weights */ void setGammaC (int gamma_c) diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_bezier.h b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_bezier.h index 29bdae93188..b55636b2d1b 100644 --- a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_bezier.h +++ b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_bezier.h @@ -1416,7 +1416,7 @@ class ON_CLASS ON_BezierCage order1 - [in] order2 - [in] Returns: - True if input was valid and creation succeded. + True if input was valid and creation succeeded. */ bool Create( int dim, diff --git a/surface/include/pcl/surface/bilateral_upsampling.h b/surface/include/pcl/surface/bilateral_upsampling.h index 555b2aef7e1..98e4e0bd1e1 100644 --- a/surface/include/pcl/surface/bilateral_upsampling.h +++ b/surface/include/pcl/surface/bilateral_upsampling.h @@ -48,7 +48,7 @@ namespace pcl /** \brief Bilateral filtering implementation, based on the following paper: * * Kopf, Johannes and Cohen, Michael F. and Lischinski, Dani and Uyttendaele, Matt - Joint Bilateral Upsampling, - * * ACM Transations in Graphics, July 2007 + * * ACM Transactions in Graphics, July 2007 * * Takes in a colored organized point cloud (i.e. PointXYZRGB or PointXYZRGBA), that might contain nan values for the * depth information, and it will return an upsampled version of this cloud, based on the formula: diff --git a/surface/include/pcl/surface/grid_projection.h b/surface/include/pcl/surface/grid_projection.h index ce5dd832dd7..48807e9d7cc 100644 --- a/surface/include/pcl/surface/grid_projection.h +++ b/surface/include/pcl/surface/grid_projection.h @@ -125,7 +125,7 @@ namespace pcl * points within the padding area,and do a weighted average. Say if the padding * size is 1, when we process cell (x,y,z), we will find union of input data points * from (x-1) to (x+1), (y-1) to (y+1), (z-1) to (z+1)(in total, 27 cells). In this - * way, even the cells itself doesnt contain any data points, we will stil process it + * way, even the cells itself doesn't contain any data points, we will still process it * because there are data points in the padding area. This can help us fix holes which * is smaller than the padding size. * \param padding_size The num of padding cells we want to create diff --git a/surface/include/pcl/surface/mls.h b/surface/include/pcl/surface/mls.h index c8973205880..1b8870060c2 100644 --- a/surface/include/pcl/surface/mls.h +++ b/surface/include/pcl/surface/mls.h @@ -175,7 +175,7 @@ namespace pcl * \brief Project a point using the specified method. * \param[in] pt The point to be project. * \param[in] method The projection method to be used. - * \param[in] required_neighbors The minimun number of neighbors required. + * \param[in] required_neighbors The minimum number of neighbors required. * \note If required_neighbors then any number of neighbors is allowed. * \note If required_neighbors is not satisfied it projects to the mls plane. * \return The MLSProjectionResults for the input data. @@ -186,7 +186,7 @@ namespace pcl /** * \brief Project the query point used to generate the mls surface about using the specified method. * \param[in] method The projection method to be used. - * \param[in] required_neighbors The minimun number of neighbors required. + * \param[in] required_neighbors The minimum number of neighbors required. * \note If required_neighbors then any number of neighbors is allowed. * \note If required_neighbors is not satisfied it projects to the mls plane. * \return The MLSProjectionResults for the input data. @@ -479,7 +479,7 @@ namespace pcl inline int getDilationIterations () const { return (dilation_iteration_num_); } - /** \brief Set wether the mls results should be stored for each point in the input cloud + /** \brief Set whether the mls results should be stored for each point in the input cloud * \param[in] True if the mls results should be stored, otherwise false. * \note The cache_mls_results_ is forced to true when using upsampling method VOXEL_GRID_DILATION or DISTINCT_CLOUD. * \note If memory consumption is a concern set to false when not using upsampling method VOXEL_GRID_DILATION or DISTINCT_CLOUD. @@ -505,7 +505,7 @@ namespace pcl /** \brief Get the MLSResults for input cloud * \note The results are only stored if setCacheMLSResults(true) was called or when using the upsampling method DISTINCT_CLOUD or VOXEL_GRID_DILATION. - * \note This vector is align with the input cloud indicies, so use getCorrespondingIndices to get the correct results when using output cloud indicies. + * \note This vector is align with the input cloud indices, so use getCorrespondingIndices to get the correct results when using output cloud indices. */ inline const std::vector& getMLSResults () const { return (mls_results_); } diff --git a/surface/src/3rdparty/opennurbs/opennurbs_archive.cpp b/surface/src/3rdparty/opennurbs/opennurbs_archive.cpp index b5574c2018e..b8fa37542c8 100644 --- a/surface/src/3rdparty/opennurbs/opennurbs_archive.cpp +++ b/surface/src/3rdparty/opennurbs/opennurbs_archive.cpp @@ -3839,7 +3839,7 @@ bool ON_BinaryArchive::WriteObjectUserData( const ON_Object& object ) { // 22 January 2004 Dale Lear // Disable crc checking when writing the - // unknow user data block. + // unknown user data block. // This has to be done so we don't get an extra // 32 bit CRC calculated on the block that // ON_UnknownUserData::Write() writes. The diff --git a/surface/src/on_nurbs/sequential_fitter.cpp b/surface/src/on_nurbs/sequential_fitter.cpp index e88d1eca44b..2a5677d3264 100644 --- a/surface/src/on_nurbs/sequential_fitter.cpp +++ b/surface/src/on_nurbs/sequential_fitter.cpp @@ -235,10 +235,10 @@ SequentialFitter::setCorners (pcl::PointIndices::Ptr &corners, bool flip_on_dema throw std::runtime_error ("[SequentialFitter::setCorners] Error: Empty or invalid pcl-point-cloud.\n"); if (corners->indices.size () < 4) - throw std::runtime_error ("[SequentialFitter::setCorners] Error: to few corners (<4)\n"); + throw std::runtime_error ("[SequentialFitter::setCorners] Error: too few corners (<4)\n"); if (corners->indices.size () > 4) - printf ("[SequentialFitter::setCorners] Warning: to many corners (>4)\n"); + printf ("[SequentialFitter::setCorners] Warning: too many corners (>4)\n"); bool flip = false; pcl::PointXYZRGB &pt0 = m_cloud->at (corners->indices[0]); diff --git a/test/common/test_eigen.cpp b/test/common/test_eigen.cpp index 2aac5c76616..c3bcc5e9758 100644 --- a/test/common/test_eigen.cpp +++ b/test/common/test_eigen.cpp @@ -607,7 +607,7 @@ inline void generateSymPosMatrix3x3 (Matrix& matrix) val2 = val1; val3 = val1; } - // 1%: 2 values are equal but none is set explicitely to 0 + // 1%: 2 values are equal but none is set explicitly to 0 else if (test_case == 1) { val2 = val3; diff --git a/test/filters/test_filters.cpp b/test/filters/test_filters.cpp index 352cb99fe2e..81771dadc52 100644 --- a/test/filters/test_filters.cpp +++ b/test/filters/test_filters.cpp @@ -1294,7 +1294,7 @@ TEST (VoxelGridCovariance, Filters) EXPECT_LE (fabs (output.points[neighbors.at (0)].y - output.points[centroidIdx].y), 0.02); EXPECT_LE (output.points[neighbors.at (0)].z - output.points[centroidIdx].z, 0.02 * 2); - // testing seach functions + // testing search functions grid.setSaveLeafLayout (false); grid.filter (output, true); diff --git a/test/io/test_io.cpp b/test/io/test_io.cpp index 6ee10e317b4..d6ba92d987f 100644 --- a/test/io/test_io.cpp +++ b/test/io/test_io.cpp @@ -941,7 +941,7 @@ TEST_F (PLYTest, LoadPLYFileColoredASCIIIntoBlob) EXPECT_EQ (cloud_blob.point_step, 16); EXPECT_EQ (cloud_blob.row_step, 16 * 4); EXPECT_EQ (cloud_blob.data.size(), 16 * 4); - // EXPECT_TRUE (cloud_blob.is_dense); // this is failing and it shouldnt? + // EXPECT_TRUE (cloud_blob.is_dense); // this is failing and it shouldn't? // scope blob data ps = cloud_blob.point_step; @@ -989,7 +989,7 @@ TEST_F (PLYTest, LoadPLYFileColoredASCIIIntoPolygonMesh) EXPECT_EQ (mesh.cloud.point_step, 16); EXPECT_EQ (mesh.cloud.row_step, 16 * 4); EXPECT_EQ (mesh.cloud.data.size(), 16 * 4); - // EXPECT_TRUE (mesh.cloud.is_dense); // this is failing and it shouldnt? + // EXPECT_TRUE (mesh.cloud.is_dense); // this is failing and it shouldn't? // scope blob data ps = mesh.cloud.point_step; @@ -1033,7 +1033,7 @@ TYPED_TEST (PLYPointCloudTest, LoadPLYFileColoredASCIIIntoPointCloud) EXPECT_EQ (cloud_rgb.height, 1); EXPECT_EQ (cloud_rgb.width, 4); EXPECT_EQ (cloud_rgb.points.size(), 4); - // EXPECT_TRUE (cloud_rgb.is_dense); // this is failing and it shouldnt? + // EXPECT_TRUE (cloud_rgb.is_dense); // this is failing and it shouldn't? // scope cloud data ASSERT_EQ (cloud_rgb[0].rgba, PLYTest::rgba_1_); diff --git a/test/io/test_octree_compression.cpp b/test/io/test_octree_compression.cpp index d2521d69d51..8b97fcaba85 100644 --- a/test/io/test_octree_compression.cpp +++ b/test/io/test_octree_compression.cpp @@ -167,7 +167,7 @@ TEST(PCL, OctreeDeCompressionFile) EXPECT_EQ(rv, 0) << " loadPCDFile " << pcd_file; EXPECT_GT((int) input_cloud_ptr->width , 0) << "invalid point cloud width from " << pcd_file; - EXPECT_GT((int) input_cloud_ptr->height, 0) << "invalid point cloud heigth from " << pcd_file; + EXPECT_GT((int) input_cloud_ptr->height, 0) << "invalid point cloud height from " << pcd_file; // iterate over compression profiles for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR; diff --git a/test/kdtree/test_kdtree.cpp b/test/kdtree/test_kdtree.cpp index c051e589019..1d35b66cfe1 100644 --- a/test/kdtree/test_kdtree.cpp +++ b/test/kdtree/test_kdtree.cpp @@ -64,7 +64,7 @@ struct MyPoint : public PointXYZ PointCloud cloud, cloud_big; -// Includ the implementation so that KdTree works +// Include the implementation so that KdTree works #include void diff --git a/test/registration/test_registration.cpp b/test/registration/test_registration.cpp index 02d9e13605a..64f5c929854 100644 --- a/test/registration/test_registration.cpp +++ b/test/registration/test_registration.cpp @@ -61,7 +61,7 @@ #include #include #include -// We need Histogram<2> to function, so we'll explicitely add kdtree_flann.hpp here +// We need Histogram<2> to function, so we'll explicitly add kdtree_flann.hpp here #include //(pcl::Histogram<2>) diff --git a/test/search/test_search.cpp b/test/search/test_search.cpp index 8d997fb6daa..15bb02ac79e 100644 --- a/test/search/test_search.cpp +++ b/test/search/test_search.cpp @@ -128,7 +128,7 @@ vector unorganized_dense_cloud_query_indices; vector unorganized_sparse_cloud_query_indices; vector organized_sparse_query_indices; -/** \briet test whether the result of a search containes unique point ids or not +/** \briet test whether the result of a search contains unique point ids or not * @param indices resulting indices from a search * @param name name of the search method that returned these distances * @return true if indices are unique, false otherwise diff --git a/test/surface/test_gp3.cpp b/test/surface/test_gp3.cpp index 258a1103cf0..032a5668597 100644 --- a/test/surface/test_gp3.cpp +++ b/test/surface/test_gp3.cpp @@ -226,7 +226,7 @@ TEST (PCL, UpdateMesh_With_TextureMapping) //tex_material.tex_Ns = 0.0f; //tex_material.tex_illum = 2; - //// set texture material paramaters + //// set texture material parameters //tm.setTextureMaterials(tex_material); //// set texture files diff --git a/tools/mesh2pcd.cpp b/tools/mesh2pcd.cpp index 1ab6bd48d2f..3e739cb64ce 100644 --- a/tools/mesh2pcd.cpp +++ b/tools/mesh2pcd.cpp @@ -58,7 +58,7 @@ printHelp (int, char **argv) { print_error ("Syntax is: %s input.{ply,obj} output.pcd \n", argv[0]); print_info (" where options are:\n"); - print_info (" -level X = tesselated sphere level (default: "); + print_info (" -level X = tessellated sphere level (default: "); print_value ("%d", default_tesselated_sphere_level); print_info (")\n"); print_info (" -resolution X = the sphere resolution in angle increments (default: "); diff --git a/tools/pcl_video.cpp b/tools/pcl_video.cpp index fb23741e562..eb381f40971 100644 --- a/tools/pcl_video.cpp +++ b/tools/pcl_video.cpp @@ -160,7 +160,7 @@ class Recorder tide::TrackEntry::Ptr track(new tide::TrackEntry(1, 1, "pointcloud2")); track->name("3D video"); track->codec_name("pcl::PCLPointCloud2"); - // Adding each level 1 element (only the first occurance, in the case of + // Adding each level 1 element (only the first occurrence, in the case of // clusters) to the index makes opening the file later much faster. segment.index.insert(std::make_pair(tracks.id(), segment.to_segment_offset(stream_.tellp()))); @@ -287,7 +287,7 @@ class Player tide::Segment segment; segment.read(stream); // The segment's date is stored as the number of nanoseconds since the - // start of the millenium. Boost::Date_Time is invaluable here. + // start of the millennium. Boost::Date_Time is invaluable here. bpt::ptime basis(boost::gregorian::date(2001, 1, 1)); bpt::time_duration sd(bpt::microseconds(segment.info.date() / 1000)); bpt::ptime seg_start(basis + sd); diff --git a/tools/png2pcd.cpp b/tools/png2pcd.cpp index 5d9595998fd..468e4338909 100644 --- a/tools/png2pcd.cpp +++ b/tools/png2pcd.cpp @@ -216,7 +216,7 @@ main (int argc, char** argv) } else { - print_error ("Unknow depth unit defined.\n"); + print_error ("Unknown depth unit defined.\n"); exit (-1); } } diff --git a/tools/virtual_scanner.cpp b/tools/virtual_scanner.cpp index 5dfcf797739..42518038143 100644 --- a/tools/virtual_scanner.cpp +++ b/tools/virtual_scanner.cpp @@ -108,7 +108,7 @@ main (int argc, char** argv) " -view_point : set the camera viewpoint from where the acquisition will take place\n" " -target_point : the target point that the camera should look at (default: 0, 0, 0)\n" " -organized <0|1> : create an organized, grid-like point cloud of width x height (1), or keep it unorganized with height = 1 (0)\n" - " -noise <0|1> : add gausian noise (1) or keep the model noiseless (0)\n" + " -noise <0|1> : add gaussian noise (1) or keep the model noiseless (0)\n" " -noise_std : use X times the standard deviation\n" ""); return (-1); diff --git a/tracking/include/pcl/tracking/pyramidal_klt.h b/tracking/include/pcl/tracking/pyramidal_klt.h index b15c60fee60..7eadd10d7f2 100644 --- a/tracking/include/pcl/tracking/pyramidal_klt.h +++ b/tracking/include/pcl/tracking/pyramidal_klt.h @@ -48,7 +48,7 @@ namespace pcl namespace tracking { /** Pyramidal Kanade Lucas Tomasi tracker. - * This is an implemntation of the Pyramidal Kanade Lucas Tomasi tracker that operates on + * This is an implementation of the Pyramidal Kanade Lucas Tomasi tracker that operates on * organized 3D keypoints with color/intensity information (this is the default behaviour but you * can alterate it by providing another operator as second template argument). It is an affine * tracker that iteratively computes the optical flow to find the best guess for a point p at t @@ -196,12 +196,12 @@ namespace pcl inline void setPointsToTrack (const pcl::PointCloud::ConstPtr& points); - /// \brief \return a pointer to the points succesfully tracked. + /// \brief \return a pointer to the points successfully tracked. inline pcl::PointCloud::ConstPtr getTrackedPoints () const { return (keypoints_); }; /** \brief \return the status of points to track. - * Status == 0 --> points succesfully tracked; + * Status == 0 --> points successfully tracked; * Status < 0 --> point is lost; * Status == -1 --> point is out of bond; * Status == -2 --> optical flow can not be computed for this point. @@ -209,7 +209,7 @@ namespace pcl inline pcl::PointIndicesConstPtr getPointsToTrackStatus () const { return (keypoints_status_); } - /** \brief Return the computed transfromation from tracked points. */ + /** \brief Return the computed transformation from tracked points. */ Eigen::Affine3f getResult () const { return (motion_); } @@ -279,7 +279,7 @@ namespace pcl * \param[out] win patch with interpolated intensity values * \param[out] grad_x_win patch with interpolated gradient along X values * \param[out] grad_y_win patch with interpolated gradient along Y values - * \param[out] covariance covariance matrix coefficents + * \param[out] covariance covariance matrix coefficients */ virtual void spatialGradient (const FloatImage& img, diff --git a/visualization/include/pcl/visualization/interactor_style.h b/visualization/include/pcl/visualization/interactor_style.h index 6b64fc5b944..74160f23bce 100644 --- a/visualization/include/pcl/visualization/interactor_style.h +++ b/visualization/include/pcl/visualization/interactor_style.h @@ -355,7 +355,7 @@ namespace pcl /** \brief Get camera parameters from a string vector. * \param[in] camera A string vector: * Clipping Range, Focal Point, Position, ViewUp, Distance, Field of View Y, Window Size, Window Pos. - * Values in each string are seperated by a ',' + * Values in each string are separated by a ',' */ bool getCameraParameters (const std::vector &camera); diff --git a/visualization/include/pcl/visualization/pcl_plotter.h b/visualization/include/pcl/visualization/pcl_plotter.h index 09acbd264c9..6b5f1e79f34 100644 --- a/visualization/include/pcl/visualization/pcl_plotter.h +++ b/visualization/include/pcl/visualization/pcl_plotter.h @@ -188,7 +188,7 @@ namespace pcl std::vector const &color = std::vector()); /** \brief Adds a plot based on a space/tab delimited table provided in a file - * \param[in] filename name of the file containing the table. 1st column represents the values of X-Axis. Rest of the columns represent the corresponding values in Y-Axes. First row of the file is concidered for naming/labling of the plot. The plot-names should not contain any space in between. + * \param[in] filename name of the file containing the table. 1st column represents the values of X-Axis. Rest of the columns represent the corresponding values in Y-Axes. First row of the file is considered for naming/labeling of the plot. The plot-names should not contain any space in between. * \param[in] type type of the graph plotted. vtkChart::LINE for line plot, vtkChart::BAR for bar plot, and vtkChart::POINTS for a scattered point plot */ void diff --git a/visualization/include/pcl/visualization/pcl_visualizer.h b/visualization/include/pcl/visualization/pcl_visualizer.h index b68b8ed1a01..3ae9a8d6f1f 100644 --- a/visualization/include/pcl/visualization/pcl_visualizer.h +++ b/visualization/include/pcl/visualization/pcl_visualizer.h @@ -2311,7 +2311,7 @@ namespace pcl vtkTexture* vtk_tex) const; /** \brief Get camera file for camera parameter saving/restoring from command line. - * Camera filename is calculated using sha1 value of all pathes of input .pcd files + * Camera filename is calculated using sha1 value of all paths of input .pcd files * \return empty string if failed. */ std::string diff --git a/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h b/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h index a2eae73a8f2..9c6fecd211d 100644 --- a/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h +++ b/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h @@ -179,7 +179,7 @@ namespace pcl ////////////////////////////////////////////////////////////////////////////////////// /** \brief Surface normal handler class for PointCloud geometry. Given an input * dataset, all data present in fields "normal_x", "normal_y", and "normal_z" is - * extracted and dislayed on screen as XYZ data. + * extracted and displayed on screen as XYZ data. * \author Radu B. Rusu * \ingroup visualization */ @@ -428,7 +428,7 @@ namespace pcl ////////////////////////////////////////////////////////////////////////////////////// /** \brief Surface normal handler class for PointCloud geometry. Given an input * dataset, all data present in fields "normal_x", "normal_y", and "normal_z" is - * extracted and dislayed on screen as XYZ data. + * extracted and displayed on screen as XYZ data. * \author Radu B. Rusu * \ingroup visualization */ diff --git a/visualization/include/pcl/visualization/point_picking_event.h b/visualization/include/pcl/visualization/point_picking_event.h index 6c03df979d8..7506bc84269 100644 --- a/visualization/include/pcl/visualization/point_picking_event.h +++ b/visualization/include/pcl/visualization/point_picking_event.h @@ -118,7 +118,7 @@ namespace pcl /** \brief For situations when multiple points are selected in a sequence, return the point coordinates. * \param[out] x1 the x coordinate of the first point that got selected by the user * \param[out] y1 the y coordinate of the first point that got selected by the user - * \param[out] z1 the z coordinate of the firts point that got selected by the user + * \param[out] z1 the z coordinate of the first point that got selected by the user * \param[out] x2 the x coordinate of the second point that got selected by the user * \param[out] y2 the y coordinate of the second point that got selected by the user * \param[out] z2 the z coordinate of the second point that got selected by the user diff --git a/visualization/include/pcl/visualization/simple_buffer_visualizer.h b/visualization/include/pcl/visualization/simple_buffer_visualizer.h index 75521c7c01d..d340a50db78 100644 --- a/visualization/include/pcl/visualization/simple_buffer_visualizer.h +++ b/visualization/include/pcl/visualization/simple_buffer_visualizer.h @@ -63,7 +63,7 @@ namespace pcl // load values into cloud updateValuesToDisplay(); - // check if we need to automatically handle the backgroud color + // check if we need to automatically handle the background color if(control_background_color_) { if(values_.back() < lowest_threshold_) @@ -155,7 +155,7 @@ namespace pcl } private: - /** \brief initialize ther buffer that stores the values to zero. + /** \brief initialize the buffer that stores the values to zero. * \note The size is set by private member nb_values_ which is in the range [2-308]. */ void @@ -210,13 +210,13 @@ namespace pcl */ int nb_values_; - /** \brief boolean used to know if we need to change the backgroud color in case of low values. */ + /** \brief boolean used to know if we need to change the background color in case of low values. */ bool control_background_color_; /** \brief threshold to turn the background orange if latest value is lower. */ float lowest_threshold_; - /** \brief boolean used to know if we need to change the backgroud color in case of low values. True means we do it ourselves. */ + /** \brief boolean used to know if we need to change the background color in case of low values. True means we do it ourselves. */ bool handle_y_scale_; /** \brief float tracking the minimal and maximal values ever observed. */ diff --git a/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.mm b/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.mm index 1030439346b..de8b1615870 100644 --- a/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.mm +++ b/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.mm @@ -144,7 +144,7 @@ - (void)windowWillClose:(NSNotification*)aNotification { [self breakEventLoop]; - // The NSWindow is closing, so prevent anyone from accidently using it + // The NSWindow is closing, so prevent anyone from accidentally using it renWin->SetRootWindow(NULL); } } diff --git a/visualization/include/pcl/visualization/vtk/vtkVertexBufferObject.h b/visualization/include/pcl/visualization/vtk/vtkVertexBufferObject.h index a124e0a134a..a8266f82a8b 100644 --- a/visualization/include/pcl/visualization/vtk/vtkVertexBufferObject.h +++ b/visualization/include/pcl/visualization/vtk/vtkVertexBufferObject.h @@ -84,7 +84,7 @@ class PCL_EXPORTS vtkVertexBufferObject : public vtkObject // - StreamRead specified once by R, queried a few times by A // - StreamCopy specified once by R, used a few times S // - StaticDraw specified once by A, used many times S - // - StaticRead specificed once by R, queried many times by A + // - StaticRead specified once by R, queried many times by A // - StaticCopy specified once by R, used many times S // - DynamicDraw respecified repeatedly by A, used many times S // - DynamicRead respecified repeatedly by R, queried many times by A diff --git a/visualization/src/interactor_style.cpp b/visualization/src/interactor_style.cpp index 94d6923f081..2839ba50121 100644 --- a/visualization/src/interactor_style.cpp +++ b/visualization/src/interactor_style.cpp @@ -236,7 +236,7 @@ pcl::visualization::PCLVisualizerInteractorStyle::setCameraParameters (const Eig window_size[0] = 2 * static_cast (intrinsics (0, 2)); window_size[1] = 2 * static_cast (intrinsics (1, 2)); - // Compute the vertical field of view based on the focal length and image heigh + // Compute the vertical field of view based on the focal length and image height double fovy = 2 * atan (window_size[1] / (2. * intrinsics (1, 1))) * 180.0 / M_PI; diff --git a/visualization/src/pcl_painter2D.cpp b/visualization/src/pcl_painter2D.cpp index 4d47290d84b..64ae7757dbd 100644 --- a/visualization/src/pcl_painter2D.cpp +++ b/visualization/src/pcl_painter2D.cpp @@ -364,7 +364,7 @@ pcl::visualization::PCLPainter2D::Paint (vtkContext2D *painter) //draw every figures for (size_t i = 0; i < figures_.size (); i++) { - figures_[i]->draw (painter); //thats it ;-) + figures_[i]->draw (painter); //that's it ;-) } return true; diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 44a734ecd14..3d77a7d2e31 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -3789,7 +3789,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere ( ico->SetSolidTypeToIcosahedron (); ico->Update (); - //tesselate cells from icosahedron + //tessellate cells from icosahedron vtkSmartPointer subdivide = vtkSmartPointer::New (); subdivide->SetNumberOfSubdivisions (tesselation_level); subdivide->SetInputConnection (ico->GetOutputPort ()); diff --git a/visualization/tools/openni_image.cpp b/visualization/tools/openni_image.cpp index 7607f4677b6..861ed72d540 100644 --- a/visualization/tools/openni_image.cpp +++ b/visualization/tools/openni_image.cpp @@ -330,7 +330,7 @@ class Writer { { boost::mutex::scoped_lock io_lock (io_mutex); - print_info ("Writing remaing %ld clouds in the buffer to disk...\n", buf_.getSize ()); + print_info ("Writing remaining %ld clouds in the buffer to disk...\n", buf_.getSize ()); } while (!buf_.isEmpty ()) { From b9916c3c31e234e11e865f7dde91ecab95de04c0 Mon Sep 17 00:00:00 2001 From: "luz.paz" Date: Thu, 15 Feb 2018 17:50:59 -0500 Subject: [PATCH 2/5] Follow-up typos --- 2d/include/pcl/2d/impl/morphology.hpp | 4 ++-- simulation/src/range_likelihood.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/2d/include/pcl/2d/impl/morphology.hpp b/2d/include/pcl/2d/impl/morphology.hpp index c2d82671c12..39a548bc21b 100644 --- a/2d/include/pcl/2d/impl/morphology.hpp +++ b/2d/include/pcl/2d/impl/morphology.hpp @@ -277,7 +277,7 @@ pcl::Morphology::subtractionBinary ( const pcl::PointCloud &input1, const pcl::PointCloud &input2) { - const int height = (input1.height < input2.hieght) ? input1.height : input2.height; + const int height = (input1.height < input2.height) ? input1.height : input2.height; const int width = (input1.width < input2.width) ? input1.width : input2.width; output.width = width; output.height = height; @@ -299,7 +299,7 @@ pcl::Morphology::unionBinary ( const pcl::PointCloud &input1, const pcl::PointCloud &input2) { - const int height = (input1.height < input2.hieght) ? input1.height : input2.height; + const int height = (input1.height < input2.height) ? input1.height : input2.height; const int width = (input1.width < input2.width) ? input1.width : input2.width; output.width = width; output.height = height; diff --git a/simulation/src/range_likelihood.cpp b/simulation/src/range_likelihood.cpp index 5c77cd3b1d1..e0e7e9b2687 100644 --- a/simulation/src/range_likelihood.cpp +++ b/simulation/src/range_likelihood.cpp @@ -539,7 +539,7 @@ costFunction4(float ref_val,float depth_val) float proportion = 0.999f; float lhood = proportion + (1-proportion)*(top/bottom); - // safety fix thats seems to be required due to opengl ayschronizate + // safety fix that seems to be required due to opengl asyschronizate // ask hordur about this if (bottom == 0) { From 83ce99dd68bd072111689440aefba2198cc17f29 Mon Sep 17 00:00:00 2001 From: "luz.paz" Date: Mon, 26 Feb 2018 06:38:55 -0500 Subject: [PATCH 3/5] Revisions --- gpu/octree/src/cuda/octree_iterator.hpp | 2 +- gpu/octree/src/utils/priority_octree_iterator.hpp | 2 +- simulation/src/range_likelihood.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/gpu/octree/src/cuda/octree_iterator.hpp b/gpu/octree/src/cuda/octree_iterator.hpp index 87fbfc45604..86753c262a5 100644 --- a/gpu/octree/src/cuda/octree_iterator.hpp +++ b/gpu/octree/src/cuda/octree_iterator.hpp @@ -118,7 +118,7 @@ namespace pcl { if (length > 1) { - lenght--; + length--; node_idx++; break; } diff --git a/gpu/octree/src/utils/priority_octree_iterator.hpp b/gpu/octree/src/utils/priority_octree_iterator.hpp index c3486add867..bcd616c6d8c 100644 --- a/gpu/octree/src/utils/priority_octree_iterator.hpp +++ b/gpu/octree/src/utils/priority_octree_iterator.hpp @@ -74,7 +74,7 @@ namespace pcl { if (length > 1) { - lenght--; + length--; node_idx++; break; } diff --git a/simulation/src/range_likelihood.cpp b/simulation/src/range_likelihood.cpp index e0e7e9b2687..dca919f0e5c 100644 --- a/simulation/src/range_likelihood.cpp +++ b/simulation/src/range_likelihood.cpp @@ -539,7 +539,7 @@ costFunction4(float ref_val,float depth_val) float proportion = 0.999f; float lhood = proportion + (1-proportion)*(top/bottom); - // safety fix that seems to be required due to opengl asyschronizate + // safety fix that seems to be required due to opengl asynchronization // ask hordur about this if (bottom == 0) { From 844babb33460abfb006ee3e037c8b912235640bb Mon Sep 17 00:00:00 2001 From: "luz.paz" Date: Mon, 26 Feb 2018 06:45:59 -0500 Subject: [PATCH 4/5] Found more typos --- features/include/pcl/features/brisk_2d.h | 2 +- features/include/pcl/features/cvfh.h | 4 ++-- features/include/pcl/features/impl/3dsc.hpp | 2 +- .../include/pcl/features/impl/fpfh_omp.hpp | 2 +- .../pcl/features/impl/moment_invariants.hpp | 4 ++-- features/include/pcl/features/impl/usc.hpp | 2 +- features/include/pcl/features/our_cvfh.h | 4 ++-- .../include/pcl/features/rops_estimation.h | 4 ++-- features/include/pcl/features/rsd.h | 2 +- features/include/pcl/features/spin_image.h | 2 +- features/include/pcl/features/usc.h | 2 +- gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h | 2 +- .../include/pcl/gpu/kinfu/marching_cubes.h | 8 ++++---- gpu/kinfu/src/cuda/maps.cu | 2 +- gpu/kinfu/src/internal.h | 16 ++++++++-------- .../pcl/gpu/kinfu_large_scale/marching_cubes.h | 6 +++--- gpu/kinfu_large_scale/src/cuda/maps.cu | 2 +- gpu/kinfu_large_scale/src/internal.h | 18 +++++++++--------- keypoints/include/pcl/keypoints/harris_2d.h | 2 +- search/include/pcl/search/impl/organized.hpp | 2 +- .../include/pcl/simulation/range_likelihood.h | 2 +- simulation/include/pcl/simulation/sum_reduce.h | 2 +- .../3rdparty/opennurbs/opennurbs_beam.h | 2 +- .../3rdparty/opennurbs/opennurbs_polyline.h | 2 +- test/features/test_shot_lrf_estimation.cpp | 2 +- 25 files changed, 49 insertions(+), 49 deletions(-) diff --git a/features/include/pcl/features/brisk_2d.h b/features/include/pcl/features/brisk_2d.h index 74cc1a00877..a58c24e5556 100644 --- a/features/include/pcl/features/brisk_2d.h +++ b/features/include/pcl/features/brisk_2d.h @@ -140,7 +140,7 @@ namespace pcl * * \note This should never be called by a regular user. We use a fixed type in PCL * (BRISKSignature512) and tampering with the parameters might lead to a different - * size descriptor which the user needs to accomodate in a new point type. + * size descriptor which the user needs to accommodate in a new point type. */ void generateKernel (std::vector &radius_list, diff --git a/features/include/pcl/features/cvfh.h b/features/include/pcl/features/cvfh.h index 1e2dfc6df6b..2ed5738ae6e 100644 --- a/features/include/pcl/features/cvfh.h +++ b/features/include/pcl/features/cvfh.h @@ -201,7 +201,7 @@ namespace pcl min_points_ = min; } - /** \brief Sets wether if the CVFH signatures should be normalized or not + /** \brief Sets whether if the CVFH signatures should be normalized or not * \param[in] normalize true if normalization is required, false otherwise */ inline void @@ -227,7 +227,7 @@ namespace pcl */ float leaf_size_; - /** \brief Wether to normalize the signatures or not. Default: false. */ + /** \brief Whether to normalize the signatures or not. Default: false. */ bool normalize_bins_; /** \brief Curvature threshold for removing normals. */ diff --git a/features/include/pcl/features/impl/3dsc.hpp b/features/include/pcl/features/impl/3dsc.hpp index e302173cf88..d1ca769ec5b 100644 --- a/features/include/pcl/features/impl/3dsc.hpp +++ b/features/include/pcl/features/impl/3dsc.hpp @@ -263,7 +263,7 @@ pcl::ShapeContext3DEstimation::computePoint ( PCL_ERROR ("Shape Context Error INF!\n"); if (w != w) PCL_ERROR ("Shape Context Error IND!\n"); - /// Accumulate w into correspondant Bin(j,k,l) + /// Accumulate w into correspondent Bin(j,k,l) desc[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j] += w; assert (desc[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j] >= 0); diff --git a/features/include/pcl/features/impl/fpfh_omp.hpp b/features/include/pcl/features/impl/fpfh_omp.hpp index c2904caab06..f3648d38b8f 100644 --- a/features/include/pcl/features/impl/fpfh_omp.hpp +++ b/features/include/pcl/features/impl/fpfh_omp.hpp @@ -108,7 +108,7 @@ pcl::FPFHEstimationOMP::computeFeature (PointCloud spfh_hist_lookup[p_idx] = i; } - // Intialize the array that will store the FPFH signature + // Initialize the array that will store the FPFH signature int nr_bins = nr_bins_f1_ + nr_bins_f2_ + nr_bins_f3_; nn_indices.clear(); diff --git a/features/include/pcl/features/impl/moment_invariants.hpp b/features/include/pcl/features/impl/moment_invariants.hpp index 639b2787115..9f4822fbc21 100644 --- a/features/include/pcl/features/impl/moment_invariants.hpp +++ b/features/include/pcl/features/impl/moment_invariants.hpp @@ -53,7 +53,7 @@ pcl::MomentInvariantsEstimation::computePointMomentInvarian // Estimate the XYZ centroid compute3DCentroid (cloud, indices, xyz_centroid_); - // Initalize the centralized moments + // Initialize the centralized moments float mu200 = 0, mu020 = 0, mu002 = 0, mu110 = 0, mu101 = 0, mu011 = 0; // Iterate over the nearest neighbors set @@ -86,7 +86,7 @@ pcl::MomentInvariantsEstimation::computePointMomentInvarian // Estimate the XYZ centroid compute3DCentroid (cloud, xyz_centroid_); - // Initalize the centralized moments + // Initialize the centralized moments float mu200 = 0, mu020 = 0, mu002 = 0, mu110 = 0, mu101 = 0, mu011 = 0; // Iterate over the nearest neighbors set diff --git a/features/include/pcl/features/impl/usc.hpp b/features/include/pcl/features/impl/usc.hpp index 633cb7b9a7e..6e2e38b0f2d 100644 --- a/features/include/pcl/features/impl/usc.hpp +++ b/features/include/pcl/features/impl/usc.hpp @@ -235,7 +235,7 @@ pcl::UniqueShapeContext::computePointDescriptor ( PCL_ERROR ("Shape Context Error INF!\n"); if (w != w) PCL_ERROR ("Shape Context Error IND!\n"); - /// Accumulate w into correspondant Bin(j,k,l) + /// Accumulate w into correspondent Bin(j,k,l) desc[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j] += w; assert (desc[(l*elevation_bins_*radius_bins_) + (k*radius_bins_) + j] >= 0); diff --git a/features/include/pcl/features/our_cvfh.h b/features/include/pcl/features/our_cvfh.h index 39a9333263d..60ef67a3aad 100644 --- a/features/include/pcl/features/our_cvfh.h +++ b/features/include/pcl/features/our_cvfh.h @@ -245,7 +245,7 @@ namespace pcl min_points_ = min; } - /** \brief Sets wether if the signatures should be normalized or not + /** \brief Sets whether the signatures should be normalized or not * \param[in] normalize true if normalization is required, false otherwise */ inline void @@ -335,7 +335,7 @@ namespace pcl */ float leaf_size_; - /** \brief Wether to normalize the signatures or not. Default: false. */ + /** \brief Whether to normalize the signatures or not. Default: false. */ bool normalize_bins_; /** \brief Curvature threshold for removing normals. */ diff --git a/features/include/pcl/features/rops_estimation.h b/features/include/pcl/features/rops_estimation.h index f8b2675b870..b35e7a38240 100644 --- a/features/include/pcl/features/rops_estimation.h +++ b/features/include/pcl/features/rops_estimation.h @@ -132,7 +132,7 @@ namespace pcl /** \brief This method crops all the triangles within the given radius of the given point. * \param[in] point point for which the local surface is computed - * \param[out] local_triangles strores the indices of the triangles that belong to the local surface + * \param[out] local_triangles stores the indices of the triangles that belong to the local surface * \param[out] local_points stores the indices of the points that belong to the local surface */ void @@ -141,7 +141,7 @@ namespace pcl /** \brief This method computes LRF (Local Reference Frame) matrix for the given point. * \param[in] point point for which the LRF is computed * \param[in] local_triangles list of triangles that represents the local surface of the point - * \paran[out] lrf_matrix strores computed LRF matrix for the given point + * \paran[out] lrf_matrix stores computed LRF matrix for the given point */ void computeLRF (const PointInT& point, const std::set & local_triangles, Eigen::Matrix3f& lrf_matrix) const; diff --git a/features/include/pcl/features/rsd.h b/features/include/pcl/features/rsd.h index b51e436f3d1..3d648c0a8ae 100644 --- a/features/include/pcl/features/rsd.h +++ b/features/include/pcl/features/rsd.h @@ -47,7 +47,7 @@ namespace pcl { /** \brief Transform a list of 2D matrices into a point cloud containing the values in a vector (Histogram). * Can be used to transform the 2D histograms obtained in \ref RSDEstimation into a point cloud. - * @note The template paramter N should be (greater or) equal to the product of the number of rows and columns. + * @note The template parameter N should be (greater or) equal to the product of the number of rows and columns. * \param[in] histograms2D the list of neighborhood 2D histograms * \param[out] histogramsPC the dataset containing the linearized matrices * \ingroup features diff --git a/features/include/pcl/features/spin_image.h b/features/include/pcl/features/spin_image.h index 79e9140d86c..abf4703a239 100644 --- a/features/include/pcl/features/spin_image.h +++ b/features/include/pcl/features/spin_image.h @@ -68,7 +68,7 @@ namespace pcl * different than feature estimation methods that extend \ref * FeatureFromNormals, which match the normals with the search surface. * - * With the default paramters, pcl::Histogram<153> is a good choice for PointOutT. + * With the default parameters, pcl::Histogram<153> is a good choice for PointOutT. * Of course the dimension of this descriptor must change to match the number * of bins set by the parameters. * diff --git a/features/include/pcl/features/usc.h b/features/include/pcl/features/usc.h index c6598df6947..de096b32b58 100644 --- a/features/include/pcl/features/usc.h +++ b/features/include/pcl/features/usc.h @@ -52,7 +52,7 @@ namespace pcl * - F. Tombari, S. Salti, L. Di Stefano, * "Unique Shape Context for 3D data description", * International Workshop on 3D Object Retrieval (3DOR 10) - - * in conjuction with ACM Multimedia 2010 + * in conjunction with ACM Multimedia 2010 * * The suggested PointOutT is pcl::UniqueShapeContext1960 * diff --git a/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h b/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h index 122383f5051..c7f8ddef475 100644 --- a/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h +++ b/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h @@ -281,7 +281,7 @@ namespace pcl /** \brief Camera movement threshold. TSDF is integrated iff a camera movement metric exceedes some value. */ float integration_metric_threshold_; - /** \brief ICP step is completelly disabled. Inly integratio now */ + /** \brief ICP step is completely disabled. Only integration now. */ bool disable_icp_; /** \brief Allocates all GPU internal buffers. diff --git a/gpu/kinfu/include/pcl/gpu/kinfu/marching_cubes.h b/gpu/kinfu/include/pcl/gpu/kinfu/marching_cubes.h index fa84b15eb1c..3e3a8b56094 100644 --- a/gpu/kinfu/include/pcl/gpu/kinfu/marching_cubes.h +++ b/gpu/kinfu/include/pcl/gpu/kinfu/marching_cubes.h @@ -76,8 +76,8 @@ namespace pcl /** \brief Runs marching cubes triangulation. * \param[in] tsdf - * \param[in] triangles_buffer Buffer for triangles. Its size determines max extracted triangles. If empty, it will be allocated with default size will be used. - * \return Array with triangles. Each 3 consequent poits belond to a single triangle. The returned array points to 'triangles_buffer' data. + * \param[in] triangles_buffer Buffer for triangles. Its size determines max extracted triangles. If empty, it will be allocated with default size to be used. + * \return Array with triangles. Each 3 consequent points belong to a single triangle. The returned array points to 'triangles_buffer' data. */ DeviceArray run(const TsdfVolume& tsdf, DeviceArray& triangles_buffer); @@ -86,13 +86,13 @@ namespace pcl /** \brief Edge table for marching cubes */ DeviceArray edgeTable_; - /** \brief Number of vertextes table for marching cubes */ + /** \brief Number of vertices table for marching cubes */ DeviceArray numVertsTable_; /** \brief Triangles table for marching cubes */ DeviceArray triTable_; - /** \brief Temporary buffer used by marching cubes (first row stores occuped voxes id, second number of vetexes, third poits offsets */ + /** \brief Temporary buffer used by marching cubes (first row stores occupied voxel id, second number of vertices, third points offsets */ DeviceArray2D occupied_voxels_buffer_; }; } diff --git a/gpu/kinfu/src/cuda/maps.cu b/gpu/kinfu/src/cuda/maps.cu index a336fee8d5a..5813e746d17 100644 --- a/gpu/kinfu/src/cuda/maps.cu +++ b/gpu/kinfu/src/cuda/maps.cu @@ -163,7 +163,7 @@ namespace pcl if (x < cols && y < rows) { - //vetexes + //vertices float3 vsrc, vdst = make_float3 (qnan, qnan, qnan); vsrc.x = vmap_src.ptr (y)[x]; diff --git a/gpu/kinfu/src/internal.h b/gpu/kinfu/src/internal.h index 6181d72c385..3af18d13f34 100644 --- a/gpu/kinfu/src/internal.h +++ b/gpu/kinfu/src/internal.h @@ -96,7 +96,7 @@ namespace pcl // Maps /** \brief Performs bilateral filtering of disparity map - * \param[in] src soruce map + * \param[in] src source map * \param[out] dst output map */ void @@ -152,7 +152,7 @@ namespace pcl /////////////////////////////////////////////////////////////////////////////////////////////////////////////////// // ICP - /** \brief (now it's exra code) Computes corespondances map + /** \brief (now it's extra code) Computes corespondances map * \param[in] vmap_g_curr current vertex map in global coo space * \param[in] nmap_g_curr current normals map in global coo space * \param[in] Rprev_inv inverse camera rotation at previous pose @@ -168,7 +168,7 @@ namespace pcl findCoresp (const MapArr& vmap_g_curr, const MapArr& nmap_g_curr, const Mat33& Rprev_inv, const float3& tprev, const Intr& intr, const MapArr& vmap_g_prev, const MapArr& nmap_g_prev, float distThres, float angleThres, PtrStepSz coresp); - /** \brief (now it's exra code) Computation Ax=b for ICP iteration + /** \brief (now it's extra code) Computation Ax=b for ICP iteration * \param[in] v_dst destination vertex map (previous frame cloud) * \param[in] n_dst destination normal map (previous frame normals) * \param[in] v_src source normal map (current frame cloud) @@ -289,7 +289,7 @@ namespace pcl const PtrStep& volume, MapArr& vmap, MapArr& nmap); /** \brief Renders 3D image of the scene - * \param[in] vmap vetex map + * \param[in] vmap vertex map * \param[in] nmap normals map * \param[in] light poase of light source * \param[out] dst buffer where image is generated @@ -413,16 +413,16 @@ namespace pcl void unbindTextures(); - /** \brief Scans tsdf volume and retrieves occuped voxes + /** \brief Scans tsdf volume and retrieves occupied voxels * \param[in] volume tsdf volume - * \param[out] occupied_voxels buffer for occuped voxels. The function fulfills first row with voxel ids and second row with number of vertextes. + * \param[out] occupied_voxels buffer for occupied voxels. The function fulfills first row with voxel ids and second row with number of vertices. * \return number of voxels in the buffer */ int getOccupiedVoxels(const PtrStep& volume, DeviceArray2D& occupied_voxels); /** \brief Computes total number of vertexes for all voxels and offsets of vertexes in final triangle array - * \param[out] occupied_voxels buffer with occuped voxels. The function fulfills 3nd only with offsets + * \param[out] occupied_voxels buffer with occupied voxels. The function fulfills 3nd only with offsets * \return total number of vertexes */ int @@ -430,7 +430,7 @@ namespace pcl /** \brief Generates final triangle array * \param[in] volume tsdf volume - * \param[in] occupied_voxels occuped voxel ids (first row), number of vertexes(second row), offsets(third row). + * \param[in] occupied_voxels occupied voxel ids (first row), number of vertexes(second row), offsets(third row). * \param[in] volume_size volume size in meters * \param[out] output triangle array */ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/marching_cubes.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/marching_cubes.h index b3198f5b6fa..b484d1849df 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/marching_cubes.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/marching_cubes.h @@ -81,7 +81,7 @@ namespace pcl /** \brief Runs marching cubes triangulation. * \param[in] tsdf * \param[in] triangles_buffer Buffer for triangles. Its size determines max extracted triangles. If empty, it will be allocated with default size will be used. - * \return Array with triangles. Each 3 consequent poits belond to a single triangle. The returned array points to 'triangles_buffer' data. + * \return Array with triangles. Each 3 consequent points belong to a single triangle. The returned array points to 'triangles_buffer' data. */ DeviceArray run(const TsdfVolume& tsdf, DeviceArray& triangles_buffer); @@ -90,13 +90,13 @@ namespace pcl /** \brief Edge table for marching cubes */ DeviceArray edgeTable_; - /** \brief Number of vertextes table for marching cubes */ + /** \brief Number of vertices table for marching cubes */ DeviceArray numVertsTable_; /** \brief Triangles table for marching cubes */ DeviceArray triTable_; - /** \brief Temporary buffer used by marching cubes (first row stores occuped voxes id, second number of vetexes, third poits offsets */ + /** \brief Temporary buffer used by marching cubes (first row stores occupied voxel id, second number of vertices, third points offsets */ DeviceArray2D occupied_voxels_buffer_; }; } diff --git a/gpu/kinfu_large_scale/src/cuda/maps.cu b/gpu/kinfu_large_scale/src/cuda/maps.cu index ef1f492747d..a33e96ffebd 100644 --- a/gpu/kinfu_large_scale/src/cuda/maps.cu +++ b/gpu/kinfu_large_scale/src/cuda/maps.cu @@ -176,7 +176,7 @@ namespace pcl if (x < cols && y < rows) { - //vetexes + //vertices float3 vsrc, vdst = make_float3 (qnan, qnan, qnan); vsrc.x = vmap_src.ptr (y)[x]; diff --git a/gpu/kinfu_large_scale/src/internal.h b/gpu/kinfu_large_scale/src/internal.h index d319f6881a0..db08cc6444b 100644 --- a/gpu/kinfu_large_scale/src/internal.h +++ b/gpu/kinfu_large_scale/src/internal.h @@ -61,7 +61,7 @@ namespace pcl // Maps /** \brief Performs bilateral filtering of disparity map - * \param[in] src soruce map + * \param[in] src source map * \param[out] dst output map */ void @@ -117,7 +117,7 @@ namespace pcl /////////////////////////////////////////////////////////////////////////////////////////////////////////////////// // ICP - /** \brief (now it's exra code) Computes corespondances map + /** \brief (now it's extra code) Computes corespondances map * \param[in] vmap_g_curr current vertex map in global coo space * \param[in] nmap_g_curr current normals map in global coo space * \param[in] Rprev_inv inverse camera rotation at previous pose @@ -133,7 +133,7 @@ namespace pcl findCoresp (const MapArr& vmap_g_curr, const MapArr& nmap_g_curr, const Mat33& Rprev_inv, const float3& tprev, const Intr& intr, const MapArr& vmap_g_prev, const MapArr& nmap_g_prev, float distThres, float angleThres, PtrStepSz coresp); - /** \brief (now it's exra code) Computation Ax=b for ICP iteration + /** \brief (now it's extra code) Computation Ax=b for ICP iteration * \param[in] v_dst destination vertex map (previous frame cloud) * \param[in] n_dst destination normal map (previous frame normals) * \param[in] v_src source normal map (current frame cloud) @@ -429,24 +429,24 @@ namespace pcl void unbindTextures(); - /** \brief Scans tsdf volume and retrieves occuped voxes + /** \brief Scans tsdf volume and retrieves occupied voxels * \param[in] volume tsdf volume - * \param[out] occupied_voxels buffer for occuped voxels. The function fulfills first row with voxel ids and second row with number of vertextes. + * \param[out] occupied_voxels buffer for occupied voxels. The function fulfills first row with voxel ids and second row with number of vertices. * \return number of voxels in the buffer */ int getOccupiedVoxels(const PtrStep& volume, DeviceArray2D& occupied_voxels); - /** \brief Computes total number of vertexes for all voxels and offsets of vertexes in final triangle array - * \param[out] occupied_voxels buffer with occuped voxels. The function fulfills 3nd only with offsets - * \return total number of vertexes + /** \brief Computes total number of vertices for all voxels and offsets of vertices in final triangle array + * \param[out] occupied_voxels buffer with occupied voxels. The function fulfills 3nd only with offsets + * \return total number of vertices */ int computeOffsetsAndTotalVertexes(DeviceArray2D& occupied_voxels); /** \brief Generates final triangle array * \param[in] volume tsdf volume - * \param[in] occupied_voxels occuped voxel ids (first row), number of vertexes(second row), offsets(third row). + * \param[in] occupied_voxels occupied voxel ids (first row), number of vertices(second row), offsets(third row). * \param[in] volume_size volume size in meters * \param[out] output triangle array */ diff --git a/keypoints/include/pcl/keypoints/harris_2d.h b/keypoints/include/pcl/keypoints/harris_2d.h index cfe08a55294..a966307033b 100644 --- a/keypoints/include/pcl/keypoints/harris_2d.h +++ b/keypoints/include/pcl/keypoints/harris_2d.h @@ -160,7 +160,7 @@ namespace pcl bool refine_; /// non maximas suppression bool nonmax_; - /// cornerness computation methode + /// cornerness computation method ResponseMethod method_; /// number of threads to be used unsigned int threads_; diff --git a/search/include/pcl/search/impl/organized.hpp b/search/include/pcl/search/impl/organized.hpp index 15f80724f34..ba79e38f8ff 100644 --- a/search/include/pcl/search/impl/organized.hpp +++ b/search/include/pcl/search/impl/organized.hpp @@ -153,7 +153,7 @@ pcl::search::OrganizedNeighbor::nearestKSearch (const PointT &query, testPoint (query, k, results, yBegin * input_->width + xBegin); else // point lys { - // find the box that touches the image border -> dont waste time evaluating boxes that are completely outside the image! + // find the box that touches the image border -> don't waste time evaluating boxes that are completely outside the image! int dist = std::numeric_limits::max (); if (xBegin < 0) diff --git a/simulation/include/pcl/simulation/range_likelihood.h b/simulation/include/pcl/simulation/range_likelihood.h index 3a075027f8d..72d3e4b3079 100644 --- a/simulation/include/pcl/simulation/range_likelihood.h +++ b/simulation/include/pcl/simulation/range_likelihood.h @@ -224,7 +224,7 @@ namespace pcl float camera_cy_; // min and max range of the rgbd sensor - // everything outside this doesnt appear in depth images + // everything outside this doesn't appear in depth images float z_near_; float z_far_; diff --git a/simulation/include/pcl/simulation/sum_reduce.h b/simulation/include/pcl/simulation/sum_reduce.h index 4b3ab43e6db..bf53ac395a1 100644 --- a/simulation/include/pcl/simulation/sum_reduce.h +++ b/simulation/include/pcl/simulation/sum_reduce.h @@ -26,7 +26,7 @@ namespace pcl { /** \brief Implements a parallel summation of float arrays using GLSL. * The input array is provided as a float texture and the summation - * is performed over set number of levels, where each level halfs each + * is performed over set number of levels, where each level halves each * dimension. * * \author Hordur Johannsson diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_beam.h b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_beam.h index 88707a79007..f5111d1ed30 100644 --- a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_beam.h +++ b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_beam.h @@ -7,7 +7,7 @@ 2d xy profile to 3d world space. Parameters: P - [in] start or end of path - T - [in] unit tanget to path + T - [in] unit tangent to path U - [in] unit up vector perpendicular to T Normal - [in] optional unit vector with Normal->z > 0 that defines the unit normal to the miter plane. diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_polyline.h b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_polyline.h index e04377293dd..a4cffe61b58 100644 --- a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_polyline.h +++ b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_polyline.h @@ -41,7 +41,7 @@ class ON_CLASS ON_Polyline : public ON_3dPointArray // Description: // Create a regular polygon circumscribe about a circle. - // The midpoints of the polygon's edges will be tanget to the + // The midpoints of the polygon's edges will be tangent to the // circle. // Parameters: // circle - [in] diff --git a/test/features/test_shot_lrf_estimation.cpp b/test/features/test_shot_lrf_estimation.cpp index 2226551f299..fd25d0727f2 100644 --- a/test/features/test_shot_lrf_estimation.cpp +++ b/test/features/test_shot_lrf_estimation.cpp @@ -84,7 +84,7 @@ TEST (PCL, SHOTLocalReferenceFrameEstimation) EXPECT_TRUE (pcl_isnan (bunny_LRF.at (24).x_axis[0])); // Expected Results - // point 15: tanget disambiguation + // point 15: tangent disambiguation //float point_15_conf = 0; Eigen::Vector3f point_15_x (-0.849213f, 0.528016f, 0.00593846f); Eigen::Vector3f point_15_y (0.274564f, 0.451135f, -0.849171f); From c0560036d39578fff8757e3368c313ed31716e1e Mon Sep 17 00:00:00 2001 From: "luz.paz" Date: Mon, 26 Feb 2018 06:46:18 -0500 Subject: [PATCH 5/5] source typos --- gpu/features/src/vfh.cu | 4 ++-- gpu/features/test/data_source.hpp | 6 +++--- .../include/pcl/gpu/kinfu_large_scale/cyclical_buffer.h | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/gpu/features/src/vfh.cu b/gpu/features/src/vfh.cu index 008c62d0227..0278a3b4cda 100644 --- a/gpu/features/src/vfh.cu +++ b/gpu/features/src/vfh.cu @@ -238,10 +238,10 @@ void pcl::device::VFHEstimationImpl::compute(DeviceArray& featu cudaSafeCall( cudaGetDeviceProperties(&prop, device) ); int total = static_cast (indices.empty() ? points.size() : indices.size()); - int total_lenght_in_blocks = (total + VfhDevice::CTA_SIZE - 1) / VfhDevice::CTA_SIZE; + int total_length_in_blocks = (total + VfhDevice::CTA_SIZE - 1) / VfhDevice::CTA_SIZE; int block = VfhDevice::CTA_SIZE; - int grid = min(total_lenght_in_blocks, prop.multiProcessorCount * prop.maxThreadsPerMultiProcessor / VfhDevice::CTA_SIZE); + int grid = min(total_length_in_blocks, prop.multiProcessorCount * prop.maxThreadsPerMultiProcessor / VfhDevice::CTA_SIZE); DeviceArray2D global_buffer(grid, VfhDevice::FSize); diff --git a/gpu/features/test/data_source.hpp b/gpu/features/test/data_source.hpp index 2bc1839d42d..87457f707b7 100644 --- a/gpu/features/test/data_source.hpp +++ b/gpu/features/test/data_source.hpp @@ -35,8 +35,8 @@ */ -#ifndef PCL_GPU_FEATURES_TEST_DATA_SORUCE_HPP_ -#define PCL_GPU_FEATURES_TEST_DATA_SORUCE_HPP_ +#ifndef PCL_GPU_FEATURES_TEST_DATA_SOURCE_HPP_ +#define PCL_GPU_FEATURES_TEST_DATA_SOURCE_HPP_ #include @@ -210,4 +210,4 @@ namespace pcl } } -#endif /* PCL_GPU_FEATURES_TEST_DATA_SORUCE_HPP_ */ +#endif /* PCL_GPU_FEATURES_TEST_DATA_SOURCE_HPP_ */ diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/cyclical_buffer.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/cyclical_buffer.h index 2c8da2789fa..09d13a6b6ae 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/cyclical_buffer.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/cyclical_buffer.h @@ -105,7 +105,7 @@ namespace pcl } /** \brief Check if shifting needs to be performed, returns true if so. - Shifting is considered needed if the target point is farther than distance_treshold_. + Shifting is considered needed if the target point is farther than distance_threshold_. The target point is located at distance_camera_point on the local Z axis of the camera. * \param[in] volume pointer to the TSDFVolume living in GPU * \param[in] cam_pose global pose of the camera in the world