Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: v0.3.19 rebase #1540

Merged
merged 12 commits into from
Sep 18, 2024
Merged
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "tier4_autoware_utils/geometry/boost_geometry.hpp"

#include <lanelet2_extension/utility/utilities.hpp>
#include <scene_module/virtual_traffic_light/manager.hpp>
#include <tier4_autoware_utils/math/unit_conversion.hpp>

Expand Down Expand Up @@ -81,11 +84,28 @@ VirtualTrafficLightModuleManager::VirtualTrafficLightModuleManager(rclcpp::Node
void VirtualTrafficLightModuleManager::launchNewModules(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path)
{
tier4_autoware_utils::LineString2d ego_path_linestring;
for (const auto & path_point : path.points) {
ego_path_linestring.push_back(
tier4_autoware_utils::fromMsg(path_point.point.pose.position).to_2d());
}

for (const auto & m : getRegElemMapOnPath<VirtualTrafficLight>(
path, planner_data_->route_handler_->getLaneletMapPtr())) {
const auto stop_line_opt = m.first->getStopLine();
if (!stop_line_opt) {
RCLCPP_FATAL(
logger_, "No stop line at virtual_traffic_light_reg_elem_id = %ld, please fix the map!",
m.first->id());
continue;
}

// Use lanelet_id to unregister module when the route is changed
const auto module_id = m.second.id();
if (!isModuleRegistered(module_id)) {
if (
!isModuleRegistered(module_id) &&
boost::geometry::intersects(
ego_path_linestring, lanelet::utils::to2D(stop_line_opt.value()).basicLineString())) {
registerModule(std::make_shared<VirtualTrafficLightModule>(
module_id, *m.first, m.second, planner_param_,
logger_.get_child("virtual_traffic_light_module"), clock_));
Expand Down
37 changes: 20 additions & 17 deletions planning/obstacle_avoidance_planner/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -343,26 +343,29 @@ std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolate2DTraj
const auto monotonic_base_yaw = convertEulerAngleToMonotonic(base_yaw);

// spline interpolation
const auto interpolated_x = interpolation::slerp(base_s, base_x, new_s);
const auto interpolated_y = interpolation::slerp(base_s, base_y, new_s);
const auto interpolated_yaw = interpolation::slerp(base_s, monotonic_base_yaw, new_s);

for (size_t i = 0; i < interpolated_x.size(); i++) {
if (std::isnan(interpolated_x[i]) || std::isnan(interpolated_y[i])) {
return std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint>{};
std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolated_points;
try {
const auto interpolated_x = interpolation::slerp(base_s, base_x, new_s);
const auto interpolated_y = interpolation::slerp(base_s, base_y, new_s);
const auto interpolated_yaw = interpolation::slerp(base_s, monotonic_base_yaw, new_s);

for (size_t i = 0; i < interpolated_x.size(); i++) {
if (std::isnan(interpolated_x[i]) || std::isnan(interpolated_y[i])) {
return std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint>{};
}
}
}

std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> interpolated_points;
for (size_t i = 0; i < interpolated_x.size(); i++) {
autoware_auto_planning_msgs::msg::TrajectoryPoint point;
point.pose.position.x = interpolated_x[i];
point.pose.position.y = interpolated_y[i];
point.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(
tier4_autoware_utils::normalizeRadian(interpolated_yaw[i]));
interpolated_points.push_back(point);
for (size_t i = 0; i < interpolated_x.size(); i++) {
autoware_auto_planning_msgs::msg::TrajectoryPoint point;
point.pose.position.x = interpolated_x[i];
point.pose.position.y = interpolated_y[i];
point.pose.orientation = tier4_autoware_utils::createQuaternionFromYaw(
tier4_autoware_utils::normalizeRadian(interpolated_yaw[i]));
interpolated_points.push_back(point);
}
} catch (const std::invalid_argument & e) {
return std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint>{};
}

return interpolated_points;
}

Expand Down
Loading