Skip to content

Commit 1ae1873

Browse files
committed
fix(autoware_static_centerline_generator): fix clang-tidy issues
Signed-off-by: Esteve Fernandez <esteve.fernandez@tier4.jp>
1 parent f5a9d80 commit 1ae1873

9 files changed

+154
-170
lines changed

planning/static_centerline_generator/CMakeLists.txt

+11-7
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@ find_package(rosidl_default_generators REQUIRED)
99
find_package(std_msgs REQUIRED)
1010

1111
rosidl_generate_interfaces(
12-
autoware_static_centerline_generator
12+
${PROJECT_NAME}
1313
"srv/LoadMap.srv"
1414
"srv/PlanRoute.srv"
1515
"srv/PlanPath.srv"
@@ -19,21 +19,25 @@ rosidl_generate_interfaces(
1919

2020
autoware_package()
2121

22-
ament_auto_add_executable(main
23-
src/main.cpp
22+
ament_auto_add_library(${PROJECT_NAME}_node SHARED
2423
src/static_centerline_generator_node.cpp
2524
src/centerline_source/optimization_trajectory_based_centerline.cpp
2625
src/centerline_source/bag_ego_trajectory_based_centerline.cpp
2726
src/utils.cpp
2827
)
2928

29+
rclcpp_components_register_node(${PROJECT_NAME}_node
30+
PLUGIN "autoware::static_centerline_generator::StaticCenterlineGeneratorNode"
31+
EXECUTABLE ${PROJECT_NAME}_exe
32+
)
33+
3034
if(${rosidl_cmake_VERSION} VERSION_LESS 2.5.0)
31-
rosidl_target_interfaces(main
32-
autoware_static_centerline_generator "rosidl_typesupport_cpp")
35+
rosidl_target_interfaces(${PROJECT_NAME}_node
36+
${PROJECT_NAME} "rosidl_typesupport_cpp")
3337
else()
3438
rosidl_get_typesupport_target(
35-
cpp_typesupport_target autoware_static_centerline_generator "rosidl_typesupport_cpp")
36-
target_link_libraries(main "${cpp_typesupport_target}")
39+
cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
40+
target_link_libraries(${PROJECT_NAME}_node "${cpp_typesupport_target}")
3741
endif()
3842

3943
ament_auto_package(

planning/static_centerline_generator/include/static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
16-
#define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
15+
#ifndef \
16+
STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
17+
#define \
18+
STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
1719

1820
#include "rclcpp/rclcpp.hpp"
1921
#include "route_handler/route_handler.hpp"

planning/static_centerline_generator/include/static_centerline_generator/static_centerline_generator_node.hpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,8 @@
1919
#include "autoware_static_centerline_generator/srv/plan_path.hpp"
2020
#include "autoware_static_centerline_generator/srv/plan_route.hpp"
2121
#include "rclcpp/rclcpp.hpp"
22-
#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp"
22+
#include \
23+
"static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp"
2324
#include "static_centerline_generator/type_alias.hpp"
2425
#include "vehicle_info_util/vehicle_info_util.hpp"
2526

@@ -89,7 +90,8 @@ class StaticCenterlineGeneratorNode : public rclcpp::Node
8990
std::pair<int, int> traj_range_indices_{0, 0};
9091
std::optional<CenterlineWithRoute> centerline_with_route_{std::nullopt};
9192

92-
enum class CenterlineSource {
93+
enum class CenterlineSource
94+
{
9395
OptimizationTrajectoryBase = 0,
9496
BagEgoTrajectoryBase,
9597
};

planning/static_centerline_generator/launch/static_centerline_generator.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@
5555
</node>
5656

5757
<!-- optimize path -->
58-
<node pkg="autoware_static_centerline_generator" exec="main" name="autoware_static_centerline_generator">
58+
<node pkg="autoware_static_centerline_generator" exec="autoware_static_centerline_generator_exe" name="autoware_static_centerline_generator">
5959
<remap from="lanelet2_map_topic" to="$(var lanelet2_map_topic)"/>
6060
<remap from="input_centerline" to="~/input_centerline"/>
6161
<remap from="output_whole_centerline" to="~/output_whole_centerline"/>

planning/static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -49,9 +49,10 @@ std::vector<TrajectoryPoint> generate_centerline_with_bag(rclcpp::Node & node)
4949
constexpr double epsilon = 1e-1;
5050
if (
5151
std::abs(centerline_traj_points.back().pose.position.x - ros_msg->pose.pose.position.x) <
52-
epsilon &&
52+
epsilon &&
5353
std::abs(centerline_traj_points.back().pose.position.y - ros_msg->pose.pose.position.y) <
54-
epsilon) {
54+
epsilon)
55+
{
5556
continue;
5657
}
5758
}

planning/static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp

+22-19
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp"
15+
#include \
16+
"static_centerline_generator/centerline_source/optimization_trajectory_based_centerline.hpp"
1617

1718
#include "motion_utils/resample/resample.hpp"
1819
#include "motion_utils/trajectory/conversion.hpp"
@@ -90,19 +91,19 @@ OptimizationTrajectoryBasedCenterline::generate_centerline_with_optimization(
9091

9192
// extract path with lane id from lanelets
9293
const auto raw_path_with_lane_id = [&]() {
93-
const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id(
94-
route_handler, route_lanelets, start_center_pose, ego_nearest_dist_threshold,
95-
ego_nearest_yaw_threshold);
96-
return motion_utils::resamplePath(non_resampled_path_with_lane_id, behavior_path_interval);
97-
}();
94+
const auto non_resampled_path_with_lane_id = utils::get_path_with_lane_id(
95+
route_handler, route_lanelets, start_center_pose, ego_nearest_dist_threshold,
96+
ego_nearest_yaw_threshold);
97+
return motion_utils::resamplePath(non_resampled_path_with_lane_id, behavior_path_interval);
98+
}();
9899
pub_raw_path_with_lane_id_->publish(raw_path_with_lane_id);
99100
RCLCPP_INFO(node.get_logger(), "Calculated raw path with lane id and published.");
100101

101102
// convert path with lane id to path
102103
const auto raw_path = [&]() {
103-
const auto non_resampled_path = convert_to_path(raw_path_with_lane_id);
104-
return motion_utils::resamplePath(non_resampled_path, behavior_vel_interval);
105-
}();
104+
const auto non_resampled_path = convert_to_path(raw_path_with_lane_id);
105+
return motion_utils::resamplePath(non_resampled_path, behavior_vel_interval);
106+
}();
106107
pub_raw_path_->publish(raw_path);
107108
RCLCPP_INFO(node.get_logger(), "Converted to path and published.");
108109

@@ -120,9 +121,9 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra
120121
{
121122
// convert to trajectory points
122123
const auto raw_traj_points = [&]() {
123-
const auto raw_traj = convert_to_trajectory(raw_path);
124-
return motion_utils::convertToTrajectoryPointArray(raw_traj);
125-
}();
124+
const auto raw_traj = convert_to_trajectory(raw_path);
125+
return motion_utils::convertToTrajectoryPointArray(raw_traj);
126+
}();
126127

127128
// create an instance of elastic band and model predictive trajectory.
128129
const auto eb_path_smoother_ptr =
@@ -132,23 +133,25 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra
132133

133134
// NOTE: The optimization is executed every valid_optimized_traj_points_num points.
134135
constexpr int valid_optimized_traj_points_num = 10;
135-
const int traj_segment_num = raw_traj_points.size() / valid_optimized_traj_points_num;
136+
const int traj_segment_num = static_cast<int>(raw_traj_points.size()) /
137+
valid_optimized_traj_points_num;
136138

137139
// NOTE: num_initial_optimization exists to make the both optimizations stable since they may use
138140
// warm start.
139141
constexpr int num_initial_optimization = 2;
140142

141143
std::vector<TrajectoryPoint> whole_optimized_traj_points;
142144
for (int virtual_ego_pose_idx = -num_initial_optimization;
143-
virtual_ego_pose_idx < traj_segment_num; ++virtual_ego_pose_idx) {
145+
virtual_ego_pose_idx < traj_segment_num; ++virtual_ego_pose_idx)
146+
{
144147
// calculate virtual ego pose for the optimization
145148
constexpr int virtual_ego_pose_offset_idx = 1;
146149
const auto virtual_ego_pose =
147150
raw_traj_points
148-
.at(
149-
valid_optimized_traj_points_num * std::max(virtual_ego_pose_idx, 0) +
150-
virtual_ego_pose_offset_idx)
151-
.pose;
151+
.at(
152+
valid_optimized_traj_points_num * std::max(virtual_ego_pose_idx, 0) +
153+
virtual_ego_pose_offset_idx)
154+
.pose;
152155

153156
// smooth trajectory by elastic band in the path_smoother package
154157
const auto smoothed_traj_points =
@@ -168,7 +171,7 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra
168171
if (dist < 0.5) {
169172
const std::vector<TrajectoryPoint> extracted_whole_optimized_traj_points{
170173
whole_optimized_traj_points.begin(),
171-
whole_optimized_traj_points.begin() + std::max(j, 1UL) - 1};
174+
whole_optimized_traj_points.begin() + static_cast<long>(std::max(j, 1UL)) - 1};
172175
whole_optimized_traj_points = extracted_whole_optimized_traj_points;
173176
break;
174177
}

planning/static_centerline_generator/src/main.cpp

-40
This file was deleted.

0 commit comments

Comments
 (0)