Skip to content

Commit

Permalink
Merge pull request #11 from mpowelson/feature/clang_format
Browse files Browse the repository at this point in the history
Add Clang Formatting
  • Loading branch information
marip8 authored Jan 16, 2020
2 parents ae1834e + b73adba commit bad06a9
Show file tree
Hide file tree
Showing 48 changed files with 803 additions and 831 deletions.
68 changes: 68 additions & 0 deletions .clang-format
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
---
BasedOnStyle: Google
AccessModifierOffset: -2
AlignEscapedNewlinesLeft: false
AlignTrailingComments: true
AlignAfterOpenBracket: Align
AllowAllParametersOfDeclarationOnNextLine: false
AllowShortFunctionsOnASingleLine: true
AllowShortIfStatementsOnASingleLine: false
AllowShortLoopsOnASingleLine: false
AllowShortLoopsOnASingleLine: false
AlwaysBreakBeforeMultilineStrings: false
AlwaysBreakTemplateDeclarations: true
BinPackArguments: false
BinPackParameters: false
BreakBeforeBinaryOperators: false
BreakBeforeTernaryOperators: false
BreakConstructorInitializersBeforeComma: true
ColumnLimit: 120
ConstructorInitializerAllOnOneLineOrOnePerLine: true
ConstructorInitializerIndentWidth: 2
ContinuationIndentWidth: 4
Cpp11BracedListStyle: false
DerivePointerBinding: false
ExperimentalAutoDetectBinPacking: false
IndentCaseLabels: true
IndentFunctionDeclarationAfterType: false
IndentWidth: 2
MaxEmptyLinesToKeep: 1
NamespaceIndentation: None
ObjCSpaceBeforeProtocolList: true
PenaltyBreakBeforeFirstCallParameter: 19
PenaltyBreakComment: 60
PenaltyBreakFirstLessLess: 1000
PenaltyBreakString: 1
PenaltyExcessCharacter: 1000
PenaltyReturnTypeOnItsOwnLine: 90
PointerBindsToType: true
SortIncludes: false
SpaceAfterControlStatementKeyword: true
SpaceAfterCStyleCast: false
SpaceBeforeAssignmentOperators: true
SpaceInEmptyParentheses: false
SpacesBeforeTrailingComments: 2
SpacesInAngles: false
SpacesInCStyleCastParentheses: false
SpacesInParentheses: false
Standard: Auto
TabWidth: 2
UseTab: Never

# Configure each individual brace in BraceWrapping
BreakBeforeBraces: Custom

# Control of individual brace wrapping cases
BraceWrapping: {
AfterClass: 'true'
AfterControlStatement: 'true'
AfterEnum : 'true'
AfterFunction : 'true'
AfterNamespace : 'true'
AfterStruct : 'true'
AfterUnion : 'true'
BeforeCatch : 'true'
BeforeElse : 'true'
IndentBraces : 'false'
}
...
2 changes: 2 additions & 0 deletions .run-clang-format
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
#!/bin/bash
find . -type f -regex '.*\.\(cpp\|hpp\|cc\|cxx\|h\|hxx\)' -exec clang-format-8 -style=file -i {} \;
12 changes: 12 additions & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,18 @@ env:

jobs:
include:
- os: linux
dist: bionic
language: cpp
env:
- ROS_DISTRO="melodic"
- CLANG_FORMAT_CHECK=file
- CLANG_FORMAT_VERSION=8
- AFTER_SCRIPT=""
- BADGE=clang-format
cache:
directories:
- $HOME/.ccache
- os: linux
dist: xenial
language: cpp
Expand Down
54 changes: 24 additions & 30 deletions opp_area_selection/include/opp_area_selection/area_selector.h
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
/*
/*
* Copyright 2019 Southwest Research Institute
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
*
* http://www.apache.org/licenses/LICENSE-2.0
*
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
Expand All @@ -29,56 +29,50 @@

namespace opp_area_selection
{

struct FittedPlane
{
Eigen::Vector3d normal = Eigen::Vector3d::UnitZ();
Eigen::Vector3d origin = Eigen::Vector3d::Zero();
};

/**
* @brief The AreaSelector class takes a set of 3D points defining a closed polygon and attempts to identify which points
* in a published point cloud lie within the bounds of that polygon. The class fits a plane to the input points, projects the
* input points/polygon onto the fitted plane, extrudes a volume defined by the projected polygon to the extents of the searched
* point cloud, and finds the points in the searched point cloud within the volume. If multiple clusters of points are found, the
* cluster closest to the centroid of the input points is selected.
* @brief The AreaSelector class takes a set of 3D points defining a closed polygon and attempts to identify which
* points in a published point cloud lie within the bounds of that polygon. The class fits a plane to the input points,
* projects the input points/polygon onto the fitted plane, extrudes a volume defined by the projected polygon to the
* extents of the searched point cloud, and finds the points in the searched point cloud within the volume. If multiple
* clusters of points are found, the cluster closest to the centroid of the input points is selected.
*/
class AreaSelector
{
public:
/**
* @brief AreaSelector class constructor
*/
AreaSelector()
{
}
AreaSelector() {}

/**
* @brief Finds the points that lie within the selection boundary
* @param roi_cloud_msg
* @return Returns false if there are less than 3 selection boundary points or if there are no search points; otherwise returns true.
* @return Returns false if there are less than 3 selection boundary points or if there are no search points;
* otherwise returns true.
*/
std::vector<int> getRegionOfInterest(
const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
const std::vector<Eigen::Vector3d>& points,
const AreaSelectorParameters& params);
std::vector<int> getRegionOfInterest(const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
const std::vector<Eigen::Vector3d>& points,
const AreaSelectorParameters& params);

protected:
boost::optional<FittedPlane> fitPlaneToPoints(
const std::vector<Eigen::Vector3d>& points,
const AreaSelectorParameters& params);
boost::optional<FittedPlane> fitPlaneToPoints(const std::vector<Eigen::Vector3d>& points,
const AreaSelectorParameters& params);

pcl::PointCloud<pcl::PointXYZ>::Ptr projectPointsOntoPlane(
const std::vector<Eigen::Vector3d>& points,
const FittedPlane& plane);
pcl::PointCloud<pcl::PointXYZ>::Ptr projectPointsOntoPlane(const std::vector<Eigen::Vector3d>& points,
const FittedPlane& plane);

std::vector<int> getPointsInROI(
const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
const pcl::PointCloud<pcl::PointXYZ>::Ptr proj_sel_points,
const FittedPlane& plane,
const AreaSelectorParameters& params);
std::vector<int> getPointsInROI(const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
const pcl::PointCloud<pcl::PointXYZ>::Ptr proj_sel_points,
const FittedPlane& plane,
const AreaSelectorParameters& params);
};

} // namespace opp_area_selection
} // namespace opp_area_selection

#endif // OPP_AREA_SELECTION_AREA_SELECTOR_H
#endif // OPP_AREA_SELECTION_AREA_SELECTOR_H
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
/*
/*
* Copyright 2019 Southwest Research Institute
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
*
* http://www.apache.org/licenses/LICENSE-2.0
*
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
Expand All @@ -21,7 +21,6 @@

namespace opp_area_selection
{

struct AreaSelectorParameters
{
double cluster_tolerance = 0.25;
Expand All @@ -33,10 +32,8 @@ struct AreaSelectorParameters
int region_growing_nneighbors = 10;
double region_growing_smoothness = 5.0;
double region_growing_curvature = 1.0;

};

} // namespace opp_area_selection

#endif // OPP_AREA_SELECTION_AREA_SELECTOR_PARAMETERS_H
} // namespace opp_area_selection

#endif // OPP_AREA_SELECTION_AREA_SELECTOR_PARAMETERS_H
17 changes: 7 additions & 10 deletions opp_area_selection/include/opp_area_selection/filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,27 +21,24 @@

namespace opp_area_selection
{

namespace data_filtering
{

template <typename PointT>
using Cloud = typename pcl::PointCloud<PointT>;

template <typename PointT>
using CloudPtr = typename Cloud<PointT>::Ptr;

template <typename PointT>
bool planeFit(
const CloudPtr<PointT> input_cloud,
Cloud<PointT>& output_cloud,
pcl::ModelCoefficients::Ptr plane_coefficients,
const double threshold = 0.025);
bool planeFit(const CloudPtr<PointT> input_cloud,
Cloud<PointT>& output_cloud,
pcl::ModelCoefficients::Ptr plane_coefficients,
const double threshold = 0.025);

} // end namespace data_filtering
} // end namespace data_filtering

} // end namespace opp_area_selection
} // end namespace opp_area_selection

#include "opp_area_selection/filter_impl.h"

#endif // OPP_AREA_SELECTION_FILTER_H
#endif // OPP_AREA_SELECTION_FILTER_H
19 changes: 10 additions & 9 deletions opp_area_selection/include/opp_area_selection/filter_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,18 +28,16 @@

namespace opp_area_selection
{

namespace data_filtering
{

template<typename PointT>
template <typename PointT>
bool planeFit(const CloudPtr<PointT> input_cloud,
Cloud<PointT>& output_cloud,
pcl::ModelCoefficients::Ptr plane_coefficients,
const double threshold)
{
pcl::ExtractIndices<PointT> extract;
pcl::PointIndices::Ptr plane_inliers (new pcl::PointIndices);
pcl::PointIndices::Ptr plane_inliers(new pcl::PointIndices);
pcl::SACSegmentation<PointT> seg;

// Set segmentation parameters
Expand All @@ -52,12 +50,15 @@ bool planeFit(const CloudPtr<PointT> input_cloud,
// Extract best fit cylinder inliers and calculate cylinder coefficients
seg.segment(*plane_inliers, *plane_coefficients);

if(plane_inliers->indices.size() == 0)
if (plane_inliers->indices.size() == 0)
{
ROS_ERROR("Unable to fit a plane to the data");
return false;
}
ROS_DEBUG_NAMED("[a5::data_filtering]", "Plane fit: %lu input points, %lu output points", input_cloud->points.size(), plane_inliers->indices.size());
ROS_DEBUG_NAMED("[a5::data_filtering]",
"Plane fit: %lu input points, %lu output points",
input_cloud->points.size(),
plane_inliers->indices.size());

// Create new point cloud from
extract.setInputCloud(input_cloud);
Expand All @@ -68,8 +69,8 @@ bool planeFit(const CloudPtr<PointT> input_cloud,
return true;
}

} // end namespace data_filtering
} // end namespace data_filtering

} // end namespace opp_area_selection
} // end namespace opp_area_selection

#endif // OPP_AREA_SELECTION_FILTER_IMPL_H
#endif // OPP_AREA_SELECTION_FILTER_IMPL_H
Loading

0 comments on commit bad06a9

Please sign in to comment.