Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore: remove unnecessary comments for uncrustify #431

Merged
merged 1 commit into from
Feb 22, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <vector>

// *INDENT-OFF*
#include "compare_map_segmentation/voxel_based_approximate_compare_map_filter_nodelet.hpp"
// *INDENT-ON*

#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/search/kdtree.h>
#include <pcl/segmentation/segment_differences.h>

#include <vector>

namespace compare_map_segmentation
{
using pointcloud_preprocessor::get_param;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,16 +81,13 @@ class OccupancyGridMapOutlierFilterComponent : public rclcpp::Node
private:
class Debugger
{
// *INDENT-OFF*
public:
// *INDENT-ON*
explicit Debugger(OccupancyGridMapOutlierFilterComponent & node);
void publishOutlier(const PclPointCloud & input, const Header & header);
void publishHighConfidence(const PclPointCloud & input, const Header & header);
void publishLowConfidence(const PclPointCloud & input, const Header & header);
// *INDENT-OFF*

private:
// *INDENT-ON*
void transformToBaseLink(
const PclPointCloud & input, const Header & header, PointCloud2 & output);
rclcpp::Publisher<PointCloud2>::SharedPtr outlier_pointcloud_pub_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,12 @@
#define MOTION_VELOCITY_SMOOTHER__MOTION_VELOCITY_SMOOTHER_NODE_HPP_

#include "motion_velocity_smoother/resample.hpp"
#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp"
#include "motion_velocity_smoother/smoother/jerk_filtered_smoother.hpp"
#include "motion_velocity_smoother/smoother/l2_pseudo_jerk_smoother.hpp"
#include "motion_velocity_smoother/smoother/linf_pseudo_jerk_smoother.hpp"
#include "motion_velocity_smoother/smoother/smoother_base.hpp"
#include "motion_velocity_smoother/trajectory_utils.hpp"
#include "osqp_interface/osqp_interface.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"
Expand All @@ -43,12 +46,6 @@
#include <tuple>
#include <vector>

// *INDENT-OFF*
#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp"
// *INDENT-ON*
#include "motion_velocity_smoother/smoother/smoother_base.hpp"
#include "motion_velocity_smoother/trajectory_utils.hpp"

namespace motion_velocity_smoother
{
using autoware_auto_planning_msgs::msg::Trajectory;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@
// See the License for the specific language governing permissions and
// limitations under the License.

// *INDENT-OFF*
#ifndef MOTION_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER_HPP_ // NOLINT
#define MOTION_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER_HPP_ // NOLINT
// *INDENT-ON*

#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp"
#include "motion_velocity_smoother/smoother/smoother_base.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"
#include "tier4_autoware_utils/trajectory/trajectory.hpp"
Expand All @@ -28,11 +28,6 @@
#include <utility>
#include <vector>

// *INDENT-OFF*
#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp"
// *INDENT-ON*
#include "motion_velocity_smoother/smoother/smoother_base.hpp"

namespace motion_velocity_smoother
{
class AnalyticalJerkConstrainedSmoother : public SmootherBase
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

// *INDENT-OFF*
#ifndef MOTION_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__VELOCITY_PLANNING_UTILS_HPP_ // NOLINT
#define MOTION_VELOCITY_SMOOTHER__SMOOTHER__ANALYTICAL_JERK_CONSTRAINED_SMOOTHER__VELOCITY_PLANNING_UTILS_HPP_ // NOLINT
// *INDENT-ON*

#include "motion_velocity_smoother/linear_interpolation.hpp"
#include "rclcpp/rclcpp.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp"

#include <algorithm>
#include <string>
#include <tuple>
#include <utility>
#include <vector>

// *INDENT-OFF*
#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp"
// *INDENT-ON*

namespace
{
using TrajectoryPoints = std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint>;
Expand Down Expand Up @@ -544,14 +542,12 @@ bool AnalyticalJerkConstrainedSmoother::calcEnoughDistForDecel(
const double a0 = trajectory.at(start_index).acceleration_mps2;
const double jerk_acc = std::abs(planning_jerk);
const double jerk_dec = planning_jerk;
// *INDENT-OFF*
auto calcMinAcc = [&params](const double planning_jerk) {
if (planning_jerk < params.backward.min_jerk_mild_stop) {
return params.backward.min_acc;
}
return params.backward.min_acc_mild_stop;
};
// *INDENT-ON*
const double min_acc = calcMinAcc(planning_jerk);
type = 0;
times.clear();
Expand Down Expand Up @@ -589,14 +585,12 @@ bool AnalyticalJerkConstrainedSmoother::applyDecelVelocityFilter(
const double a0 = output_trajectory.at(decel_start_index).acceleration_mps2;
const double jerk_acc = std::abs(planning_jerk);
const double jerk_dec = planning_jerk;
// *INDENT-OFF*
auto calcMinAcc = [&params](const double planning_jerk) {
if (planning_jerk < params.backward.min_jerk_mild_stop) {
return params.backward.min_acc;
}
return params.backward.min_acc_mild_stop;
};
// *INDENT-ON*
const double min_acc = calcMinAcc(planning_jerk);

if (!analytical_velocity_planning_utils::calcStopVelocityWithConstantJerkAccLimit(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,11 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp"

#include <algorithm>
#include <vector>

// *INDENT-OFF*
#include "motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp"
// *INDENT-ON*

namespace motion_velocity_smoother
{
namespace analytical_velocity_planning_utils
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

// *INDENT-OFF*
#ifndef LASERSCAN_TO_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_
#define LASERSCAN_TO_OCCUPANCY_GRID_MAP__UPDATER__OCCUPANCY_GRID_MAP_BINARY_BAYES_FILTER_UPDATER_HPP_
// *INDENT-ON*

#include "laserscan_to_occupancy_grid_map/updater/occupancy_grid_map_updater_interface.hpp"

Expand Down