12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
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"
16
17
17
18
#include " motion_utils/resample/resample.hpp"
18
19
#include " motion_utils/trajectory/conversion.hpp"
@@ -90,19 +91,19 @@ OptimizationTrajectoryBasedCenterline::generate_centerline_with_optimization(
90
91
91
92
// extract path with lane id from lanelets
92
93
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
+ }();
98
99
pub_raw_path_with_lane_id_->publish (raw_path_with_lane_id);
99
100
RCLCPP_INFO (node.get_logger (), " Calculated raw path with lane id and published." );
100
101
101
102
// convert path with lane id to path
102
103
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
+ }();
106
107
pub_raw_path_->publish (raw_path);
107
108
RCLCPP_INFO (node.get_logger (), " Converted to path and published." );
108
109
@@ -120,9 +121,9 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra
120
121
{
121
122
// convert to trajectory points
122
123
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
+ }();
126
127
127
128
// create an instance of elastic band and model predictive trajectory.
128
129
const auto eb_path_smoother_ptr =
@@ -132,23 +133,25 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra
132
133
133
134
// NOTE: The optimization is executed every valid_optimized_traj_points_num points.
134
135
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;
136
138
137
139
// NOTE: num_initial_optimization exists to make the both optimizations stable since they may use
138
140
// warm start.
139
141
constexpr int num_initial_optimization = 2 ;
140
142
141
143
std::vector<TrajectoryPoint> whole_optimized_traj_points;
142
144
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
+ {
144
147
// calculate virtual ego pose for the optimization
145
148
constexpr int virtual_ego_pose_offset_idx = 1 ;
146
149
const auto virtual_ego_pose =
147
150
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 ;
152
155
153
156
// smooth trajectory by elastic band in the path_smoother package
154
157
const auto smoothed_traj_points =
@@ -168,7 +171,7 @@ std::vector<TrajectoryPoint> OptimizationTrajectoryBasedCenterline::optimize_tra
168
171
if (dist < 0.5 ) {
169
172
const std::vector<TrajectoryPoint> extracted_whole_optimized_traj_points{
170
173
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 };
172
175
whole_optimized_traj_points = extracted_whole_optimized_traj_points;
173
176
break ;
174
177
}
0 commit comments