We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent da0df3e commit b48b416Copy full SHA for b48b416
planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/footprint.cpp
@@ -79,9 +79,9 @@ void make_ego_footprint_rtree(EgoData & ego_data, const PlannerParam & params)
79
for (auto i = 0UL; i < ego_data.trajectory_footprints.size(); ++i) {
80
const auto box = boost::geometry::return_envelope<autoware::universe_utils::Box2d>(
81
ego_data.trajectory_footprints[i]);
82
- rtree_nodes.push_back(std::make_pair(box, i));
+ rtree_nodes.emplace_back(box, i);
83
}
84
- ego_data.rtree = Rtree(rtree_nodes);
+ ego_data.rtree = Rtree(std::move(rtree_nodes));
85
86
87
} // namespace autoware::motion_velocity_planner::dynamic_obstacle_stop
0 commit comments