Skip to content

Commit 5aa747b

Browse files
authored
refactor(universe_utils/motion_utils)!: add autoware namespace (#7594)
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent d677314 commit 5aa747b

File tree

629 files changed

+4210
-4170
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

629 files changed

+4210
-4170
lines changed

common/autoware_grid_map_utils/test/benchmark.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ int main(int argc, char * argv[])
4646
result_file
4747
<< "#Size PolygonVertices PolygonIndexes grid_map_utils_constructor grid_map_utils_iteration "
4848
"grid_map_constructor grid_map_iteration\n";
49-
autoware_universe_utils::StopWatch<std::chrono::milliseconds> stopwatch;
49+
autoware::universe_utils::StopWatch<std::chrono::milliseconds> stopwatch;
5050

5151
constexpr auto nb_iterations = 10;
5252
constexpr auto polygon_side_vertices =

common/autoware_motion_utils/include/autoware/motion_utils/constants.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,9 @@
1515
#ifndef AUTOWARE__MOTION_UTILS__CONSTANTS_HPP_
1616
#define AUTOWARE__MOTION_UTILS__CONSTANTS_HPP_
1717

18-
namespace autoware_motion_utils
18+
namespace autoware::motion_utils
1919
{
2020
constexpr double overlap_threshold = 0.1;
21-
} // namespace autoware_motion_utils
21+
} // namespace autoware::motion_utils
2222

2323
#endif // AUTOWARE__MOTION_UTILS__CONSTANTS_HPP_

common/autoware_motion_utils/include/autoware/motion_utils/distance/distance.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -22,12 +22,12 @@
2222
#include <tuple>
2323
#include <vector>
2424

25-
namespace autoware_motion_utils
25+
namespace autoware::motion_utils
2626
{
2727
std::optional<double> calcDecelDistWithJerkAndAccConstraints(
2828
const double current_vel, const double target_vel, const double current_acc, const double acc_min,
2929
const double jerk_acc, const double jerk_dec);
3030

31-
} // namespace autoware_motion_utils
31+
} // namespace autoware::motion_utils
3232

3333
#endif // AUTOWARE__MOTION_UTILS__DISTANCE__DISTANCE_HPP_

common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
#include <string>
2525
#include <vector>
2626

27-
namespace autoware_motion_utils
27+
namespace autoware::motion_utils
2828
{
2929
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
3030
using autoware_adapi_v1_msgs::msg::VelocityFactor;
@@ -49,6 +49,6 @@ class VelocityFactorInterface
4949
VelocityFactor velocity_factor_{};
5050
};
5151

52-
} // namespace autoware_motion_utils
52+
} // namespace autoware::motion_utils
5353

5454
#endif // AUTOWARE__MOTION_UTILS__FACTOR__VELOCITY_FACTOR_INTERFACE_HPP_

common/autoware_motion_utils/include/autoware/motion_utils/marker/marker_helper.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121

2222
#include <string>
2323

24-
namespace autoware_motion_utils
24+
namespace autoware::motion_utils
2525
{
2626
using geometry_msgs::msg::Pose;
2727

@@ -48,6 +48,6 @@ visualization_msgs::msg::MarkerArray createDeletedSlowDownVirtualWallMarker(
4848

4949
visualization_msgs::msg::MarkerArray createDeletedDeadLineVirtualWallMarker(
5050
const rclcpp::Time & now, const int32_t id);
51-
} // namespace autoware_motion_utils
51+
} // namespace autoware::motion_utils
5252

5353
#endif // AUTOWARE__MOTION_UTILS__MARKER__MARKER_HELPER_HPP_

common/autoware_motion_utils/include/autoware/motion_utils/marker/virtual_wall_marker_creator.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
#include <unordered_map>
2626
#include <vector>
2727

28-
namespace autoware_motion_utils
28+
namespace autoware::motion_utils
2929
{
3030

3131
/// @brief type of virtual wall associated with different marker styles and namespace
@@ -76,6 +76,6 @@ class VirtualWallMarkerCreator
7676
/// @param now current time to be used for displaying the markers
7777
visualization_msgs::msg::MarkerArray create_markers(const rclcpp::Time & now = rclcpp::Time());
7878
};
79-
} // namespace autoware_motion_utils
79+
} // namespace autoware::motion_utils
8080

8181
#endif // AUTOWARE__MOTION_UTILS__MARKER__VIRTUAL_WALL_MARKER_CREATOR_HPP_

common/autoware_motion_utils/include/autoware/motion_utils/resample/resample.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121

2222
#include <vector>
2323

24-
namespace autoware_motion_utils
24+
namespace autoware::motion_utils
2525
{
2626
/**
2727
* @brief A resampling function for a path(points). Note that in a default setting, position xy are
@@ -234,6 +234,6 @@ autoware_planning_msgs::msg::Trajectory resampleTrajectory(
234234
const bool use_akima_spline_for_xy = false, const bool use_lerp_for_z = true,
235235
const bool use_zero_order_hold_for_twist = true,
236236
const bool resample_input_trajectory_stop_point = true);
237-
} // namespace autoware_motion_utils
237+
} // namespace autoware::motion_utils
238238

239239
#endif // AUTOWARE__MOTION_UTILS__RESAMPLE__RESAMPLE_HPP_

common/autoware_motion_utils/include/autoware/motion_utils/resample/resample_utils.hpp

+13-13
Original file line numberDiff line numberDiff line change
@@ -42,17 +42,17 @@ bool validate_size(const T & points)
4242
template <class T>
4343
bool validate_resampling_range(const T & points, const std::vector<double> & resampling_intervals)
4444
{
45-
const double points_length = autoware_motion_utils::calcArcLength(points);
45+
const double points_length = autoware::motion_utils::calcArcLength(points);
4646
return points_length >= resampling_intervals.back();
4747
}
4848

4949
template <class T>
5050
bool validate_points_duplication(const T & points)
5151
{
5252
for (size_t i = 0; i < points.size() - 1; ++i) {
53-
const auto & curr_pt = autoware_universe_utils::getPoint(points.at(i));
54-
const auto & next_pt = autoware_universe_utils::getPoint(points.at(i + 1));
55-
const double ds = autoware_universe_utils::calcDistance2d(curr_pt, next_pt);
53+
const auto & curr_pt = autoware::universe_utils::getPoint(points.at(i));
54+
const auto & next_pt = autoware::universe_utils::getPoint(points.at(i + 1));
55+
const double ds = autoware::universe_utils::calcDistance2d(curr_pt, next_pt);
5656
if (ds < close_s_threshold) {
5757
return false;
5858
}
@@ -67,27 +67,27 @@ bool validate_arguments(const T & input_points, const std::vector<double> & resa
6767
// Check size of the arguments
6868
if (!validate_size(input_points)) {
6969
RCLCPP_DEBUG(get_logger(), "invalid argument: The number of input points is less than 2");
70-
autoware_universe_utils::print_backtrace();
70+
autoware::universe_utils::print_backtrace();
7171
return false;
7272
}
7373
if (!validate_size(resampling_intervals)) {
7474
RCLCPP_DEBUG(
7575
get_logger(), "invalid argument: The number of resampling intervals is less than 2");
76-
autoware_universe_utils::print_backtrace();
76+
autoware::universe_utils::print_backtrace();
7777
return false;
7878
}
7979

8080
// Check resampling range
8181
if (!validate_resampling_range(input_points, resampling_intervals)) {
8282
RCLCPP_DEBUG(get_logger(), "invalid argument: resampling interval is longer than input points");
83-
autoware_universe_utils::print_backtrace();
83+
autoware::universe_utils::print_backtrace();
8484
return false;
8585
}
8686

8787
// Check duplication
8888
if (!validate_points_duplication(input_points)) {
8989
RCLCPP_DEBUG(get_logger(), "invalid argument: input points has some duplicated points");
90-
autoware_universe_utils::print_backtrace();
90+
autoware::universe_utils::print_backtrace();
9191
return false;
9292
}
9393

@@ -100,23 +100,23 @@ bool validate_arguments(const T & input_points, const double resampling_interval
100100
// Check size of the arguments
101101
if (!validate_size(input_points)) {
102102
RCLCPP_DEBUG(get_logger(), "invalid argument: The number of input points is less than 2");
103-
autoware_universe_utils::print_backtrace();
103+
autoware::universe_utils::print_backtrace();
104104
return false;
105105
}
106106

107107
// check resampling interval
108-
if (resampling_interval < autoware_motion_utils::overlap_threshold) {
108+
if (resampling_interval < autoware::motion_utils::overlap_threshold) {
109109
RCLCPP_DEBUG(
110110
get_logger(), "invalid argument: resampling interval is less than %f",
111-
autoware_motion_utils::overlap_threshold);
112-
autoware_universe_utils::print_backtrace();
111+
autoware::motion_utils::overlap_threshold);
112+
autoware::universe_utils::print_backtrace();
113113
return false;
114114
}
115115

116116
// Check duplication
117117
if (!validate_points_duplication(input_points)) {
118118
RCLCPP_DEBUG(get_logger(), "invalid argument: input points has some duplicated points");
119-
autoware_universe_utils::print_backtrace();
119+
autoware::universe_utils::print_backtrace();
120120
return false;
121121
}
122122

common/autoware_motion_utils/include/autoware/motion_utils/trajectory/conversion.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323

2424
#include <vector>
2525

26-
namespace autoware_motion_utils
26+
namespace autoware::motion_utils
2727
{
2828
using TrajectoryPoints = std::vector<autoware_planning_msgs::msg::TrajectoryPoint>;
2929

@@ -115,6 +115,6 @@ inline tier4_planning_msgs::msg::PathWithLaneId convertToPathWithLaneId(
115115
return output;
116116
}
117117

118-
} // namespace autoware_motion_utils
118+
} // namespace autoware::motion_utils
119119

120120
#endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__CONVERSION_HPP_

common/autoware_motion_utils/include/autoware/motion_utils/trajectory/interpolation.hpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
#include <algorithm>
2626
#include <limits>
2727

28-
namespace autoware_motion_utils
28+
namespace autoware::motion_utils
2929
{
3030
/**
3131
* @brief An interpolation function that finds the closest interpolated point on the trajectory from
@@ -73,24 +73,24 @@ geometry_msgs::msg::Pose calcInterpolatedPose(const T & points, const double tar
7373
}
7474

7575
if (points.size() < 2 || target_length < 0.0) {
76-
return autoware_universe_utils::getPose(points.front());
76+
return autoware::universe_utils::getPose(points.front());
7777
}
7878

7979
double accumulated_length = 0;
8080
for (size_t i = 0; i < points.size() - 1; ++i) {
81-
const auto & curr_pose = autoware_universe_utils::getPose(points.at(i));
82-
const auto & next_pose = autoware_universe_utils::getPose(points.at(i + 1));
83-
const double length = autoware_universe_utils::calcDistance3d(curr_pose, next_pose);
81+
const auto & curr_pose = autoware::universe_utils::getPose(points.at(i));
82+
const auto & next_pose = autoware::universe_utils::getPose(points.at(i + 1));
83+
const double length = autoware::universe_utils::calcDistance3d(curr_pose, next_pose);
8484
if (accumulated_length + length > target_length) {
8585
const double ratio = (target_length - accumulated_length) / std::max(length, 1e-6);
86-
return autoware_universe_utils::calcInterpolatedPose(curr_pose, next_pose, ratio);
86+
return autoware::universe_utils::calcInterpolatedPose(curr_pose, next_pose, ratio);
8787
}
8888
accumulated_length += length;
8989
}
9090

91-
return autoware_universe_utils::getPose(points.back());
91+
return autoware::universe_utils::getPose(points.back());
9292
}
9393

94-
} // namespace autoware_motion_utils
94+
} // namespace autoware::motion_utils
9595

9696
#endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__INTERPOLATION_HPP_

common/autoware_motion_utils/include/autoware/motion_utils/trajectory/path_with_lane_id.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020

2121
#include <optional>
2222
#include <utility>
23-
namespace autoware_motion_utils
23+
namespace autoware::motion_utils
2424
{
2525
std::optional<std::pair<size_t, size_t>> getPathIndexRangeWithLaneId(
2626
const tier4_planning_msgs::msg::PathWithLaneId & path, const int64_t target_lane_id);
@@ -41,6 +41,6 @@ size_t findNearestSegmentIndexFromLaneId(
4141
tier4_planning_msgs::msg::PathWithLaneId convertToRearWheelCenter(
4242
const tier4_planning_msgs::msg::PathWithLaneId & path, const double rear_to_cog,
4343
const bool enable_last_point_compensation = true);
44-
} // namespace autoware_motion_utils
44+
} // namespace autoware::motion_utils
4545

4646
#endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__PATH_WITH_LANE_ID_HPP_

0 commit comments

Comments
 (0)