Skip to content

Commit

Permalink
refactor(motion_utils): apply clang-tidy result (autowarefoundation#5829
Browse files Browse the repository at this point in the history
)

Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
  • Loading branch information
zulfaqar-azmi-t4 authored and karishma1911 committed May 28, 2024
1 parent 2352840 commit 8923ce1
Show file tree
Hide file tree
Showing 14 changed files with 69 additions and 88 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,11 @@
#include <geometry_msgs/msg/pose.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <functional>
#include <string>
#include <unordered_map>
#include <vector>

namespace motion_utils
{

Expand All @@ -38,7 +40,7 @@ struct VirtualWall
double longitudinal_offset{};
bool is_driving_forward{true};
};
typedef std::vector<VirtualWall> VirtualWalls;
using VirtualWalls = std::vector<VirtualWall>;

/// @brief class to manage the creation of virtual wall markers
/// @details creates both ADD and DELETE markers
Expand All @@ -55,8 +57,8 @@ class VirtualWallMarkerCreator
const rclcpp::Time & now, const int32_t id, const double longitudinal_offset,
const std::string & ns_prefix, const bool is_driving_forward)>;

VirtualWalls virtual_walls;
std::unordered_map<std::string, MarkerCount> marker_count_per_namespace;
VirtualWalls virtual_walls_;
std::unordered_map<std::string, MarkerCount> marker_count_per_namespace_;

/// @brief internal cleanup: clear the stored markers and remove unused namespace from the map
void cleanup();
Expand Down
12 changes: 5 additions & 7 deletions common/motion_utils/include/motion_utils/resample/resample.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,10 @@
#ifndef MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_
#define MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_

#include "autoware_auto_planning_msgs/msg/path.hpp"
#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp"
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
#include "autoware_auto_planning_msgs/msg/detail/path__struct.hpp"
#include "autoware_auto_planning_msgs/msg/detail/path_with_lane_id__struct.hpp"
#include "autoware_auto_planning_msgs/msg/detail/trajectory__struct.hpp"

#include <algorithm>
#include <limits>
#include <stdexcept>
#include <vector>

namespace motion_utils
Expand Down Expand Up @@ -187,7 +184,8 @@ autoware_auto_planning_msgs::msg::Path resamplePath(
autoware_auto_planning_msgs::msg::Path resamplePath(
const autoware_auto_planning_msgs::msg::Path & input_path, const double resample_interval,
const bool use_akima_spline_for_xy = false, const bool use_lerp_for_z = true,
const bool use_zero_order_hold_for_v = true, const bool resample_input_path_stop_point = true);
const bool use_zero_order_hold_for_twist = true,
const bool resample_input_path_stop_point = true);

/**
* @brief A resampling function for a trajectory. Note that in a default setting, position xy are
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,26 +23,19 @@

namespace resample_utils
{
constexpr double CLOSE_S_THRESHOLD = 1e-6;
constexpr double close_s_threshold = 1e-6;

template <class T>
bool validate_size(const T & points)
{
if (points.size() < 2) {
return false;
}
return true;
return points.size() >= 2;
}

template <class T>
bool validate_resampling_range(const T & points, const std::vector<double> & resampling_intervals)
{
const double points_length = motion_utils::calcArcLength(points);
if (points_length < resampling_intervals.back()) {
return false;
}

return true;
return points_length >= resampling_intervals.back();
}

template <class T>
Expand All @@ -52,7 +45,7 @@ bool validate_points_duplication(const T & points)
const auto & curr_pt = tier4_autoware_utils::getPoint(points.at(i));
const auto & next_pt = tier4_autoware_utils::getPoint(points.at(i + 1));
const double ds = tier4_autoware_utils::calcDistance2d(curr_pt, next_pt);
if (ds < CLOSE_S_THRESHOLD) {
if (ds < close_s_threshold) {
return false;
}
}
Expand All @@ -67,7 +60,8 @@ bool validate_arguments(const T & input_points, const std::vector<double> & resa
if (!validate_size(input_points)) {
std::cerr << "The number of input points is less than 2" << std::endl;
return false;
} else if (!validate_size(resampling_intervals)) {
}
if (!validate_size(resampling_intervals)) {
std::cerr << "The number of resampling intervals is less than 2" << std::endl;
return false;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,16 +16,12 @@
#define MOTION_UTILS__TRAJECTORY__INTERPOLATION_HPP_

#include "tier4_autoware_utils/geometry/geometry.hpp"
#include "tier4_autoware_utils/math/constants.hpp"

#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp"
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
#include "autoware_auto_planning_msgs/msg/detail/path_with_lane_id__struct.hpp"
#include "autoware_auto_planning_msgs/msg/detail/trajectory__struct.hpp"

#include <algorithm>
#include <limits>
#include <optional>
#include <stdexcept>
#include <vector>

namespace motion_utils
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef MOTION_UTILS__TRAJECTORY__PATH_WITH_LANE_ID_HPP_
#define MOTION_UTILS__TRAJECTORY__PATH_WITH_LANE_ID_HPP_

#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp"
#include "autoware_auto_planning_msgs/msg/detail/path_with_lane_id__struct.hpp"
#include <geometry_msgs/msg/point.hpp>

#include <optional>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef MOTION_UTILS__TRAJECTORY__TMP_CONVERSION_HPP_
#define MOTION_UTILS__TRAJECTORY__TMP_CONVERSION_HPP_

#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp"
#include "autoware_auto_planning_msgs/msg/detail/trajectory__struct.hpp"
#include "autoware_auto_planning_msgs/msg/detail/trajectory_point__struct.hpp"

#include <vector>

Expand Down
60 changes: 29 additions & 31 deletions common/motion_utils/include/motion_utils/trajectory/trajectory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,11 +130,11 @@ std::optional<bool> isDrivingForwardWithTwist(const T & points_with_twist)
if (points_with_twist.size() == 1) {
if (0.0 < tier4_autoware_utils::getLongitudinalVelocity(points_with_twist.front())) {
return true;
} else if (0.0 > tier4_autoware_utils::getLongitudinalVelocity(points_with_twist.front())) {
}
if (0.0 > tier4_autoware_utils::getLongitudinalVelocity(points_with_twist.front())) {
return false;
} else {
return std::nullopt;
}
return std::nullopt;
}

return isDrivingForward(points_with_twist);
Expand Down Expand Up @@ -401,12 +401,12 @@ double calcLongitudinalOffsetToSegment(
const bool throw_exception = false)
{
if (seg_idx >= points.size() - 1) {
const std::out_of_range e("Segment index is invalid.");
const auto error_message{"Segment index is invalid."};
tier4_autoware_utils::print_backtrace();
if (throw_exception) {
throw e;
throw std::out_of_range(error_message);
}
std::cerr << e.what() << std::endl;
std::cerr << error_message << std::endl;
return std::nan("");
}

Expand All @@ -424,12 +424,12 @@ double calcLongitudinalOffsetToSegment(
}

if (seg_idx >= overlap_removed_points.size() - 1) {
const std::runtime_error e("Same points are given.");
const auto error_message{"Same points are given."};
tier4_autoware_utils::print_backtrace();
if (throw_exception) {
throw e;
throw std::runtime_error(error_message);
}
std::cerr << e.what() << std::endl;
std::cerr << error_message << std::endl;
return std::nan("");
}

Expand Down Expand Up @@ -581,12 +581,12 @@ double calcLateralOffset(
}

if (overlap_removed_points.size() == 1) {
const std::runtime_error e("Same points are given.");
const auto error_message{"Same points are given."};
tier4_autoware_utils::print_backtrace();
if (throw_exception) {
throw e;
throw std::runtime_error(error_message);
}
std::cerr << e.what() << std::endl;
std::cerr << error_message << std::endl;
return std::nan("");
}

Expand Down Expand Up @@ -643,12 +643,12 @@ double calcLateralOffset(
}

if (overlap_removed_points.size() == 1) {
const std::runtime_error e("Same points are given.");
const auto error_message{"Same points are given."};
tier4_autoware_utils::print_backtrace();
if (throw_exception) {
throw e;
throw std::runtime_error(error_message);
}
std::cerr << e.what() << std::endl;
std::cerr << error_message << std::endl;
return std::nan("");
}

Expand Down Expand Up @@ -968,17 +968,17 @@ std::vector<std::pair<double, double>> calcCurvatureAndArcLength(const T & point
{
// Note that arclength is for the segment, not the sum.
std::vector<std::pair<double, double>> curvature_arc_length_vec;
curvature_arc_length_vec.push_back(std::pair(0.0, 0.0));
curvature_arc_length_vec.emplace_back(0.0, 0.0);
for (size_t i = 1; i < points.size() - 1; ++i) {
const auto p1 = tier4_autoware_utils::getPoint(points.at(i - 1));
const auto p2 = tier4_autoware_utils::getPoint(points.at(i));
const auto p3 = tier4_autoware_utils::getPoint(points.at(i + 1));
const double curvature = tier4_autoware_utils::calcCurvature(p1, p2, p3);
const double arc_length = tier4_autoware_utils::calcDistance2d(points.at(i - 1), points.at(i)) +
tier4_autoware_utils::calcDistance2d(points.at(i), points.at(i + 1));
curvature_arc_length_vec.push_back(std::pair(curvature, arc_length));
curvature_arc_length_vec.emplace_back(curvature, arc_length);
}
curvature_arc_length_vec.push_back(std::pair(0.0, 0.0));
curvature_arc_length_vec.emplace_back(0.0, 0.0);

return curvature_arc_length_vec;
}
Expand Down Expand Up @@ -1046,12 +1046,12 @@ std::optional<geometry_msgs::msg::Point> calcLongitudinalOffsetPoint(
}

if (points.size() - 1 < src_idx) {
const auto e = std::out_of_range("Invalid source index");
const auto error_message{"Invalid source index"};
tier4_autoware_utils::print_backtrace();
if (throw_exception) {
throw e;
throw std::out_of_range(error_message);
}
std::cerr << e.what() << std::endl;
std::cerr << error_message << std::endl;
return {};
}

Expand Down Expand Up @@ -1171,12 +1171,12 @@ std::optional<geometry_msgs::msg::Pose> calcLongitudinalOffsetPose(
}

if (points.size() - 1 < src_idx) {
const auto e = std::out_of_range("Invalid source index");
const auto error_message{"Invalid source index"};
tier4_autoware_utils::print_backtrace();
if (throw_exception) {
throw e;
throw std::out_of_range(error_message);
}
std::cerr << e.what() << std::endl;
std::cerr << error_message << std::endl;
return {};
}

Expand Down Expand Up @@ -2041,9 +2041,8 @@ size_t findFirstNearestIndexWithSoftConstraints(
if (squared_dist_threshold < squared_dist || yaw_threshold < std::abs(yaw)) {
if (is_within_constraints) {
break;
} else {
continue;
}
continue;
}

if (min_squared_dist <= squared_dist) {
Expand Down Expand Up @@ -2073,9 +2072,8 @@ size_t findFirstNearestIndexWithSoftConstraints(
if (squared_dist_threshold < squared_dist) {
if (is_within_constraints) {
break;
} else {
continue;
}
continue;
}

if (min_squared_dist <= squared_dist) {
Expand Down Expand Up @@ -2386,12 +2384,12 @@ double calcYawDeviation(
}

if (overlap_removed_points.size() <= 1) {
const std::runtime_error e("points size is less than 2");
const auto error_message{"points size is less than 2"};
tier4_autoware_utils::print_backtrace();
if (throw_exception) {
throw e;
throw std::runtime_error(error_message);
}
std::cerr << e.what() << std::endl;
std::cerr << error_message << std::endl;
return 0.0;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include <nav_msgs/msg/odometry.hpp>

#include <deque>
#include <memory>

namespace motion_utils
{
Expand Down
3 changes: 2 additions & 1 deletion common/motion_utils/src/distance/distance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -262,7 +262,8 @@ std::optional<double> calcDecelDistWithJerkAndAccConstraints(
if (t_during_min_acc > epsilon) {
return calcDecelDistPlanType1(
current_vel, target_vel, current_acc, acc_min, jerk_acc, jerk_dec, t_during_min_acc);
} else if (is_decel_needed || current_acc > epsilon) {
}
if (is_decel_needed || current_acc > epsilon) {
return calcDecelDistPlanType2(current_vel, target_vel, current_acc, jerk_acc, jerk_dec);
}

Expand Down
6 changes: 2 additions & 4 deletions common/motion_utils/src/marker/marker_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,12 @@

#include "motion_utils/marker/marker_helper.hpp"

#include "motion_utils/resample/resample_utils.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"

#include <visualization_msgs/msg/marker_array.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>

#include <functional>
#include <visualization_msgs/msg/marker_array.hpp>

using tier4_autoware_utils::appendMarkerArray;
using tier4_autoware_utils::createDefaultMarker;
using tier4_autoware_utils::createDeletedDefaultMarker;
using tier4_autoware_utils::createMarkerColor;
Expand Down
Loading

0 comments on commit 8923ce1

Please sign in to comment.