Skip to content

Commit 1f6c264

Browse files
authored
refactor(path_optimizer, velocity_smoother)!: prefix package and namespace with autoware (#7354)
* chore(autoware_velocity_smoother): update namespace Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(autoware_path_optimizer): update namespace Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent e6b56a4 commit 1f6c264

File tree

47 files changed

+94
-94
lines changed

Some content is hidden

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

47 files changed

+94
-94
lines changed

launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@
6262
<group>
6363
<group if="$(eval &quot;'$(var motion_path_planner_type)' == 'path_optimizer'&quot;)">
6464
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
65-
<composable_node pkg="autoware_path_optimizer" plugin="autoware_path_optimizer::PathOptimizer" name="path_optimizer" namespace="">
65+
<composable_node pkg="autoware_path_optimizer" plugin="autoware::path_optimizer::PathOptimizer" name="path_optimizer" namespace="">
6666
<!-- topic remap -->
6767
<remap from="~/input/path" to="path_smoother/path"/>
6868
<remap from="~/input/odometry" to="/localization/kinematic_state"/>

launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
<!-- motion velocity smoother -->
2828
<group>
2929
<node_container pkg="rclcpp_components" exec="component_container" name="velocity_smoother_container" namespace="">
30-
<composable_node pkg="autoware_velocity_smoother" plugin="autoware_velocity_smoother::VelocitySmootherNode" name="velocity_smoother" namespace="">
30+
<composable_node pkg="autoware_velocity_smoother" plugin="autoware::velocity_smoother::VelocitySmootherNode" name="velocity_smoother" namespace="">
3131
<param name="algorithm_type" value="$(var velocity_smoother_type)"/>
3232
<param from="$(var common_param_path)"/>
3333
<param from="$(var nearest_search_param_path)"/>

planning/autoware_behavior_velocity_planner/src/node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -310,7 +310,7 @@ void BehaviorVelocityPlannerNode::onParam()
310310
// constructed. It would be required if it was a callback. std::lock_guard<std::mutex>
311311
// lock(mutex_);
312312
planner_data_.velocity_smoother_ =
313-
std::make_unique<autoware_velocity_smoother::AnalyticalJerkConstrainedSmoother>(*this);
313+
std::make_unique<autoware::velocity_smoother::AnalyticalJerkConstrainedSmoother>(*this);
314314
planner_data_.velocity_smoother_->setWheelBase(planner_data_.vehicle_info_.wheel_base_m);
315315
}
316316

planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,7 @@ struct PlannerData
8888
bool is_simulation = false;
8989

9090
// velocity smoother
91-
std::shared_ptr<autoware_velocity_smoother::SmootherBase> velocity_smoother_;
91+
std::shared_ptr<autoware::velocity_smoother::SmootherBase> velocity_smoother_;
9292
// route handler
9393
std::shared_ptr<route_handler::RouteHandler> route_handler_;
9494
// parameters

planning/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,7 @@ bool smoothPath(
8282
traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest);
8383

8484
if (external_v_limit) {
85-
autoware_velocity_smoother::trajectory_utils::applyMaximumVelocityLimit(
85+
autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit(
8686
traj_resampled_closest, traj_smoothed.size(), external_v_limit->max_velocity, traj_smoothed);
8787
}
8888
out_path = motion_utils::convertToPathWithLaneId<TrajectoryPoints>(traj_smoothed);

planning/autoware_path_optimizer/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ target_include_directories(autoware_path_optimizer
4141

4242
# register node
4343
rclcpp_components_register_node(autoware_path_optimizer
44-
PLUGIN "autoware_path_optimizer::PathOptimizer"
44+
PLUGIN "autoware::path_optimizer::PathOptimizer"
4545
EXECUTABLE path_optimizer_node
4646
)
4747

planning/autoware_path_optimizer/include/autoware_path_optimizer/common_structs.hpp

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

28-
namespace autoware_path_optimizer
28+
namespace autoware::path_optimizer
2929
{
3030
struct ReferencePoint;
3131
struct Bounds;
@@ -153,6 +153,6 @@ struct EgoNearestParam
153153
double dist_threshold{0.0};
154154
double yaw_threshold{0.0};
155155
};
156-
} // namespace autoware_path_optimizer
156+
} // namespace autoware::path_optimizer
157157

158158
#endif // AUTOWARE_PATH_OPTIMIZER__COMMON_STRUCTS_HPP_

planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp

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

28-
namespace autoware_path_optimizer
28+
namespace autoware::path_optimizer
2929
{
3030
MarkerArray getDebugMarker(
3131
const DebugData & debug_data,
3232
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & optimized_points,
3333
const vehicle_info_util::VehicleInfo & vehicle_info, const bool publish_extra_marker);
34-
} // namespace autoware_path_optimizer
34+
} // namespace autoware::path_optimizer
3535
#endif // AUTOWARE_PATH_OPTIMIZER__DEBUG_MARKER_HPP_

planning/autoware_path_optimizer/include/autoware_path_optimizer/mpt_optimizer.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434
#include <utility>
3535
#include <vector>
3636

37-
namespace autoware_path_optimizer
37+
namespace autoware::path_optimizer
3838
{
3939
struct Bounds
4040
{
@@ -308,5 +308,5 @@ class MPTOptimizer
308308
size_t getNumberOfSlackVariables() const;
309309
std::optional<double> calcNormalizedAvoidanceCost(const ReferencePoint & ref_point) const;
310310
};
311-
} // namespace autoware_path_optimizer
311+
} // namespace autoware::path_optimizer
312312
#endif // AUTOWARE_PATH_OPTIMIZER__MPT_OPTIMIZER_HPP_

planning/autoware_path_optimizer/include/autoware_path_optimizer/node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@
3333
#include <string>
3434
#include <vector>
3535

36-
namespace autoware_path_optimizer
36+
namespace autoware::path_optimizer
3737
{
3838
class PathOptimizer : public rclcpp::Node
3939
{
@@ -141,6 +141,6 @@ class PathOptimizer : public rclcpp::Node
141141

142142
std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
143143
};
144-
} // namespace autoware_path_optimizer
144+
} // namespace autoware::path_optimizer
145145

146146
#endif // AUTOWARE_PATH_OPTIMIZER__NODE_HPP_

planning/autoware_path_optimizer/include/autoware_path_optimizer/replan_checker.hpp

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

27-
namespace autoware_path_optimizer
27+
namespace autoware::path_optimizer
2828
{
2929
class ReplanChecker
3030
{
@@ -66,6 +66,6 @@ class ReplanChecker
6666
bool isPathGoalChanged(
6767
const PlannerData & planner_data, const std::vector<TrajectoryPoint> & prev_traj_points) const;
6868
};
69-
} // namespace autoware_path_optimizer
69+
} // namespace autoware::path_optimizer
7070

7171
#endif // AUTOWARE_PATH_OPTIMIZER__REPLAN_CHECKER_HPP_

planning/autoware_path_optimizer/include/autoware_path_optimizer/state_equation_generator.hpp

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

25-
namespace autoware_path_optimizer
25+
namespace autoware::path_optimizer
2626
{
2727
struct ReferencePoint;
2828

@@ -58,5 +58,5 @@ class StateEquationGenerator
5858
std::unique_ptr<VehicleModelInterface> vehicle_model_ptr_;
5959
mutable std::shared_ptr<TimeKeeper> time_keeper_ptr_;
6060
};
61-
} // namespace autoware_path_optimizer
61+
} // namespace autoware::path_optimizer
6262
#endif // AUTOWARE_PATH_OPTIMIZER__STATE_EQUATION_GENERATOR_HPP_

planning/autoware_path_optimizer/include/autoware_path_optimizer/type_alias.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@
2828
#include "tier4_debug_msgs/msg/string_stamped.hpp"
2929
#include "visualization_msgs/msg/marker_array.hpp"
3030

31-
namespace autoware_path_optimizer
31+
namespace autoware::path_optimizer
3232
{
3333
// std_msgs
3434
using std_msgs::msg::Header;
@@ -45,6 +45,6 @@ using visualization_msgs::msg::MarkerArray;
4545
// debug
4646
using tier4_debug_msgs::msg::Float64Stamped;
4747
using tier4_debug_msgs::msg::StringStamped;
48-
} // namespace autoware_path_optimizer
48+
} // namespace autoware::path_optimizer
4949

5050
#endif // AUTOWARE_PATH_OPTIMIZER__TYPE_ALIAS_HPP_

planning/autoware_path_optimizer/include/autoware_path_optimizer/utils/geometry_utils.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -39,13 +39,13 @@
3939
namespace tier4_autoware_utils
4040
{
4141
template <>
42-
geometry_msgs::msg::Point getPoint(const autoware_path_optimizer::ReferencePoint & p);
42+
geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p);
4343

4444
template <>
45-
geometry_msgs::msg::Pose getPose(const autoware_path_optimizer::ReferencePoint & p);
45+
geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint & p);
4646
} // namespace tier4_autoware_utils
4747

48-
namespace autoware_path_optimizer
48+
namespace autoware::path_optimizer
4949
{
5050
namespace geometry_utils
5151
{
@@ -68,5 +68,5 @@ bool isOutsideDrivableAreaFromRectangleFootprint(
6868
const vehicle_info_util::VehicleInfo & vehicle_info,
6969
const bool use_footprint_polygon_for_outside_drivable_area_check);
7070
} // namespace geometry_utils
71-
} // namespace autoware_path_optimizer
71+
} // namespace autoware::path_optimizer
7272
#endif // AUTOWARE_PATH_OPTIMIZER__UTILS__GEOMETRY_UTILS_HPP_

planning/autoware_path_optimizer/include/autoware_path_optimizer/utils/trajectory_utils.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -38,16 +38,16 @@
3838
namespace tier4_autoware_utils
3939
{
4040
template <>
41-
geometry_msgs::msg::Point getPoint(const autoware_path_optimizer::ReferencePoint & p);
41+
geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p);
4242

4343
template <>
44-
geometry_msgs::msg::Pose getPose(const autoware_path_optimizer::ReferencePoint & p);
44+
geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint & p);
4545

4646
template <>
47-
double getLongitudinalVelocity(const autoware_path_optimizer::ReferencePoint & p);
47+
double getLongitudinalVelocity(const autoware::path_optimizer::ReferencePoint & p);
4848
} // namespace tier4_autoware_utils
4949

50-
namespace autoware_path_optimizer
50+
namespace autoware::path_optimizer
5151
{
5252
namespace trajectory_utils
5353
{
@@ -214,5 +214,5 @@ void insertStopPoint(
214214
std::vector<TrajectoryPoint> & traj_points, const geometry_msgs::msg::Pose & input_stop_pose,
215215
const size_t stop_seg_idx);
216216
} // namespace trajectory_utils
217-
} // namespace autoware_path_optimizer
217+
} // namespace autoware::path_optimizer
218218
#endif // AUTOWARE_PATH_OPTIMIZER__UTILS__TRAJECTORY_UTILS_HPP_

planning/autoware_path_optimizer/src/debug_marker.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818

1919
#include "visualization_msgs/msg/marker_array.hpp"
2020

21-
namespace autoware_path_optimizer
21+
namespace autoware::path_optimizer
2222
{
2323
using tier4_autoware_utils::appendMarkerArray;
2424
using tier4_autoware_utils::createDefaultMarker;
@@ -432,4 +432,4 @@ MarkerArray getDebugMarker(
432432

433433
return marker_array;
434434
}
435-
} // namespace autoware_path_optimizer
435+
} // namespace autoware::path_optimizer

planning/autoware_path_optimizer/src/mpt_optimizer.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929
#include <optional>
3030
#include <tuple>
3131

32-
namespace autoware_path_optimizer
32+
namespace autoware::path_optimizer
3333
{
3434
namespace
3535
{
@@ -1783,4 +1783,4 @@ std::optional<double> MPTOptimizer::calcNormalizedAvoidanceCost(
17831783
}
17841784
return std::clamp(-negative_avoidance_cost / mpt_param_.max_avoidance_cost, 0.0, 1.0);
17851785
}
1786-
} // namespace autoware_path_optimizer
1786+
} // namespace autoware::path_optimizer

planning/autoware_path_optimizer/src/node.cpp

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

28-
namespace autoware_path_optimizer
28+
namespace autoware::path_optimizer
2929
{
3030
namespace
3131
{
@@ -666,7 +666,7 @@ void PathOptimizer::publishDebugData(const Header & header) const
666666

667667
time_keeper_ptr_->toc(__func__, " ");
668668
}
669-
} // namespace autoware_path_optimizer
669+
} // namespace autoware::path_optimizer
670670

671671
#include "rclcpp_components/register_node_macro.hpp"
672-
RCLCPP_COMPONENTS_REGISTER_NODE(autoware_path_optimizer::PathOptimizer)
672+
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::path_optimizer::PathOptimizer)

planning/autoware_path_optimizer/src/replan_checker.cpp

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

2222
#include <vector>
2323

24-
namespace autoware_path_optimizer
24+
namespace autoware::path_optimizer
2525
{
2626
ReplanChecker::ReplanChecker(rclcpp::Node * node, const EgoNearestParam & ego_nearest_param)
2727
: ego_nearest_param_(ego_nearest_param), logger_(node->get_logger().get_child("replan_checker"))
@@ -212,4 +212,4 @@ bool ReplanChecker::isPathGoalChanged(
212212

213213
return true;
214214
}
215-
} // namespace autoware_path_optimizer
215+
} // namespace autoware::path_optimizer

planning/autoware_path_optimizer/src/state_equation_generator.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616

1717
#include "autoware_path_optimizer/mpt_optimizer.hpp"
1818

19-
namespace autoware_path_optimizer
19+
namespace autoware::path_optimizer
2020
{
2121
// state equation: x = B u + W (u includes x_0)
2222
// NOTE: Originally, x_t+1 = Ad x_t + Bd u + Wd.
@@ -69,4 +69,4 @@ Eigen::VectorXd StateEquationGenerator::predict(
6969
{
7070
return mat.B * U + mat.W;
7171
}
72-
} // namespace autoware_path_optimizer
72+
} // namespace autoware::path_optimizer

planning/autoware_path_optimizer/src/utils/geometry_utils.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@
3636
#include <stack>
3737
#include <vector>
3838

39-
namespace autoware_path_optimizer
39+
namespace autoware::path_optimizer
4040
{
4141
namespace bg = boost::geometry;
4242
using tier4_autoware_utils::LinearRing2d;
@@ -207,4 +207,4 @@ bool isOutsideDrivableAreaFromRectangleFootprint(
207207
return false;
208208
}
209209
} // namespace geometry_utils
210-
} // namespace autoware_path_optimizer
210+
} // namespace autoware::path_optimizer

planning/autoware_path_optimizer/src/utils/trajectory_utils.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -36,25 +36,25 @@
3636
namespace tier4_autoware_utils
3737
{
3838
template <>
39-
geometry_msgs::msg::Point getPoint(const autoware_path_optimizer::ReferencePoint & p)
39+
geometry_msgs::msg::Point getPoint(const autoware::path_optimizer::ReferencePoint & p)
4040
{
4141
return p.pose.position;
4242
}
4343

4444
template <>
45-
geometry_msgs::msg::Pose getPose(const autoware_path_optimizer::ReferencePoint & p)
45+
geometry_msgs::msg::Pose getPose(const autoware::path_optimizer::ReferencePoint & p)
4646
{
4747
return p.pose;
4848
}
4949

5050
template <>
51-
double getLongitudinalVelocity(const autoware_path_optimizer::ReferencePoint & p)
51+
double getLongitudinalVelocity(const autoware::path_optimizer::ReferencePoint & p)
5252
{
5353
return p.longitudinal_velocity_mps;
5454
}
5555
} // namespace tier4_autoware_utils
5656

57-
namespace autoware_path_optimizer
57+
namespace autoware::path_optimizer
5858
{
5959
namespace trajectory_utils
6060
{
@@ -242,4 +242,4 @@ void insertStopPoint(
242242
traj_points.insert(traj_points.begin() + stop_seg_idx + 1, additional_traj_point);
243243
}
244244
} // namespace trajectory_utils
245-
} // namespace autoware_path_optimizer
245+
} // namespace autoware::path_optimizer

planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@ TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory)
4242
planning_test_utils_dir + "/config/test_nearest_search.param.yaml", "--params-file",
4343
path_optimizer_dir + "/config/path_optimizer.param.yaml"});
4444

45-
auto test_target_node = std::make_shared<autoware_path_optimizer::PathOptimizer>(node_options);
45+
auto test_target_node = std::make_shared<autoware::path_optimizer::PathOptimizer>(node_options);
4646

4747
// publish necessary topics from test_manager
4848
test_manager->publishOdometry(test_target_node, "path_optimizer/input/odometry");

planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra
130130
const auto eb_path_smoother_ptr =
131131
path_smoother::ElasticBandSmoother(create_node_options()).getElasticBandSmoother();
132132
const auto mpt_optimizer_ptr =
133-
autoware_path_optimizer::PathOptimizer(create_node_options()).getMPTOptimizer();
133+
autoware::path_optimizer::PathOptimizer(create_node_options()).getMPTOptimizer();
134134

135135
// NOTE: The optimization is executed every valid_optimized_traj_points_num points.
136136
constexpr int valid_optimized_traj_points_num = 10;
@@ -158,7 +158,7 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra
158158

159159
// road collision avoidance by model predictive trajectory in the autoware_path_optimizer
160160
// package
161-
const autoware_path_optimizer::PlannerData planner_data{
161+
const autoware::path_optimizer::PlannerData planner_data{
162162
raw_path.header, smoothed_traj_points, raw_path.left_bound, raw_path.right_bound,
163163
virtual_ego_pose};
164164
const auto optimized_traj_points = mpt_optimizer_ptr->optimizeTrajectory(planner_data);

planning/autoware_velocity_smoother/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ target_link_libraries(${PROJECT_NAME}_node
4141
)
4242

4343
rclcpp_components_register_node(${PROJECT_NAME}_node
44-
PLUGIN "autoware_velocity_smoother::VelocitySmootherNode"
44+
PLUGIN "autoware::velocity_smoother::VelocitySmootherNode"
4545
EXECUTABLE velocity_smoother_node
4646
)
4747

0 commit comments

Comments
 (0)