Skip to content

Commit

Permalink
retrieve and use map stop lines in out of lane (not working)
Browse files Browse the repository at this point in the history
Signed-off-by: Maxime CLEMENT <[email protected]>
  • Loading branch information
maxime-clem committed Dec 6, 2024
1 parent 3231bbf commit a8146ec
Show file tree
Hide file tree
Showing 7 changed files with 162 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
ignore_behind_ego: false # if true, objects behind the ego vehicle are ignored

action: # action to insert in the trajectory if an object causes a conflict at an overlap
use_map_stop_lines: true # if true, try to stop at stop lines defined in the vector map
precision: 0.1 # [m] precision when inserting a stop pose in the trajectory
longitudinal_distance_buffer: 1.5 # [m] safety distance buffer to keep in front of the ego vehicle
lateral_distance_buffer: 1.0 # [m] safety distance buffer to keep on the side of the ego vehicle
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include "types.hpp"

#include <autoware/motion_utils/marker/virtual_wall_marker_creator.hpp>
#include <autoware/motion_velocity_planner_common/planner_data.hpp>
#include <autoware/universe_utils/geometry/boost_polygon_utils.hpp>
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/ros/marker_helper.hpp>
Expand Down Expand Up @@ -123,7 +124,7 @@ size_t add_stop_line_markers(
{
auto debug_marker = get_base_marker();
debug_marker.type = visualization_msgs::msg::Marker::LINE_STRIP;
debug_marker.ns = "stop_lines";
debug_marker.ns = "object_stop_lines";
const auto & add_lanelets_markers = [&](const auto & lanelets) {
for (const auto & ll : lanelets) {
debug_marker.points.clear();
Expand Down Expand Up @@ -154,6 +155,30 @@ size_t add_stop_line_markers(
return max_id;
}

void add_stop_line_markers(
visualization_msgs::msg::MarkerArray & debug_marker_array,
const std::vector<StopPoint> & map_stop_points, const double z)
{
auto debug_marker = get_base_marker();
debug_marker.type = visualization_msgs::msg::Marker::LINE_LIST;
debug_marker.ns = "ego_stop_lines";
debug_marker.color = universe_utils::createMarkerColor(0.5, 0.0, 0.7, 1.0);
geometry_msgs::msg::Point p1;
geometry_msgs::msg::Point p2;
p1.z = p2.z = z;
for (const auto & stop_point : map_stop_points) {
for (auto i = 0UL; i + 1 < stop_point.stop_line.size(); ++i) {
p1.x = stop_point.stop_line[i].x();
p1.y = stop_point.stop_line[i].y();
p2.x = stop_point.stop_line[i + 1].x();
p2.y = stop_point.stop_line[i + 1].y();
debug_marker.points.push_back(p1);
debug_marker.points.push_back(p2);
}
}
debug_marker_array.markers.push_back(debug_marker);
}

void add_out_lanelets(
visualization_msgs::msg::MarkerArray & marker_array, visualization_msgs::msg::Marker base_marker,
const lanelet::ConstLanelets & out_lanelets)
Expand Down Expand Up @@ -244,6 +269,8 @@ visualization_msgs::msg::MarkerArray create_debug_marker_array(
debug_data.prev_stop_line = add_stop_line_markers(
debug_marker_array, ego_data.stop_lines_rtree, z, debug_data.prev_stop_line);

add_stop_line_markers(debug_marker_array, ego_data.map_stop_points, z);

return debug_marker_array;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,7 @@ void OutOfLaneModule::init_parameters(rclcpp::Node & node)
getOrDeclareParameter<bool>(node, ns_ + ".objects.ignore_behind_ego");

pp.precision = getOrDeclareParameter<double>(node, ns_ + ".action.precision");
pp.use_map_stop_lines = getOrDeclareParameter<bool>(node, ns_ + ".action.use_map_stop_lines");
pp.min_decision_duration = getOrDeclareParameter<double>(node, ns_ + ".action.min_duration");
pp.lon_dist_buffer =
getOrDeclareParameter<double>(node, ns_ + ".action.longitudinal_distance_buffer");
Expand Down Expand Up @@ -130,6 +131,7 @@ void OutOfLaneModule::update_parameters(const std::vector<rclcpp::Parameter> & p
updateParam(parameters, ns_ + ".objects.ignore_behind_ego", pp.objects_ignore_behind_ego);

updateParam(parameters, ns_ + ".action.precision", pp.precision);
updateParam(parameters, ns_ + ".action.use_map_stop_lines", pp.use_map_stop_lines);
updateParam(parameters, ns_ + ".action.min_duration", pp.min_decision_duration);
updateParam(parameters, ns_ + ".action.longitudinal_distance_buffer", pp.lon_dist_buffer);
updateParam(parameters, ns_ + ".action.lateral_distance_buffer", pp.lat_dist_buffer);
Expand Down Expand Up @@ -272,6 +274,20 @@ VelocityPlanningResult OutOfLaneModule::plan(

stopwatch.tic("calculate_slowdown_point");
auto slowdown_pose = out_of_lane::calculate_slowdown_point(ego_data, out_of_lane_data, params_);
if (slowdown_pose && params_.use_map_stop_lines) {
// try to use a map stop line ahead of the stop pose
ego_data.map_stop_points = planner_data->calculate_map_stop_points(ego_data.trajectory_points);
auto stop_arc_length =
motion_utils::calcSignedArcLength(ego_data.trajectory_points, 0LU, slowdown_pose->position);
for (const auto & stop_point : ego_data.map_stop_points) {
if (
stop_point.ego_trajectory_arc_length < stop_arc_length &&
stop_point.ego_trajectory_arc_length >= ego_data.min_stop_arc_length) {
slowdown_pose = stop_point.ego_stop_pose;
stop_arc_length = stop_point.ego_trajectory_arc_length;
}
}
}
const auto calculate_slowdown_point_us = stopwatch.toc("calculate_slowdown_point");

// reuse previous stop pose if there is no new one or if its velocity is not higher than the new
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef TYPES_HPP_
#define TYPES_HPP_

#include <autoware/motion_velocity_planner_common/planner_data.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <autoware/universe_utils/geometry/boost_geometry.hpp>

Expand Down Expand Up @@ -66,6 +67,7 @@ struct PlannerParam
double precision; // [m] precision when inserting a stop pose in the trajectory
double
min_decision_duration; // [s] duration needed before a stop or slowdown point can be removed
bool use_map_stop_lines; // if true, try to stop at stop lines defined in the map

// ego dimensions used to create its polygon footprint
double front_offset; // [m] front offset (from vehicle info)
Expand Down Expand Up @@ -112,7 +114,9 @@ struct EgoData
std::vector<lanelet::BasicPolygon2d>
trajectory_footprints; // ego footprints along the filtered trajectory

StopLinesRtree stop_lines_rtree;
StopLinesRtree stop_lines_rtree; // rtree with the stop lines for other vehicles
std::vector<StopPoint>
map_stop_points; // ego stop points (and their corresponding stop lines) taken from the map
};

/// @brief data related to an out of lane trajectory point
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_perception_msgs/msg/traffic_light_group.hpp>
#include <autoware_perception_msgs/msg/traffic_light_group_array.hpp>
#include <autoware_planning_msgs/msg/trajectory_point.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <nav_msgs/msg/occupancy_grid.hpp>
#include <nav_msgs/msg/odometry.hpp>
Expand All @@ -43,6 +44,7 @@
#include <map>
#include <memory>
#include <optional>
#include <vector>

namespace autoware::motion_velocity_planner
{
Expand All @@ -51,6 +53,14 @@ struct TrafficSignalStamped
builtin_interfaces::msg::Time stamp;
autoware_perception_msgs::msg::TrafficLightGroup signal;
};

struct StopPoint
{
double ego_trajectory_arc_length{}; // [m] arc length along the ego trajectory
geometry_msgs::msg::Pose
ego_stop_pose; // intersection between the trajectory and a map stop line
lanelet::BasicLineString2d stop_line; // stop line from the map
};
struct PlannerData
{
explicit PlannerData(rclcpp::Node & node)
Expand Down Expand Up @@ -83,30 +93,23 @@ struct PlannerData
// parameters
autoware::vehicle_info_utils::VehicleInfo vehicle_info_;

/**
*@fn
*@brief queries the traffic signal information of given Id. if keep_last_observation = true,
*recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation
*/
/// @brief queries the traffic signal information of given Id. if keep_last_observation = true,
/// @details recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation
[[nodiscard]] std::optional<TrafficSignalStamped> get_traffic_signal(
const lanelet::Id id, const bool keep_last_observation = false) const
{
const auto & traffic_light_id_map =
keep_last_observation ? traffic_light_id_map_last_observed_ : traffic_light_id_map_raw_;
if (traffic_light_id_map.count(id) == 0) {
return std::nullopt;
}
return std::make_optional<TrafficSignalStamped>(traffic_light_id_map.at(id));
}
const lanelet::Id id, const bool keep_last_observation = false) const;

/// @brief calculate the minimum distance needed by ego to decelerate to the given velocity
/// @param [in] target_velocity [m/s] target velocity
/// @return [m] distance needed to reach the target velocity
[[nodiscard]] std::optional<double> calculate_min_deceleration_distance(
const double target_velocity) const
{
return motion_utils::calcDecelDistWithJerkAndAccConstraints(
current_odometry.twist.twist.linear.x, target_velocity,
current_acceleration.accel.accel.linear.x, velocity_smoother_->getMinDecel(),
std::abs(velocity_smoother_->getMinJerk()), velocity_smoother_->getMinJerk());
}
const double target_velocity) const;

/// @brief calculate possible stop points along the current trajectory where it intersects with
/// stop lines
/// @param [in] trajectory ego trajectory
/// @return stop points taken from the map
[[nodiscard]] std::vector<StopPoint> calculate_map_stop_points(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & trajectory) const;
};
} // namespace autoware::motion_velocity_planner

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<depend>autoware_behavior_velocity_planner_common</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
// Copyright 2024 Autoware Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <autoware/motion_utils/trajectory/interpolation.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware/motion_velocity_planner_common/planner_data.hpp>
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware_lanelet2_extension/utility/query.hpp>

#include <boost/geometry.hpp>
#include <boost/geometry/algorithms/envelope.hpp>

#include <lanelet2_core/geometry/BoundingBox.h>
#include <lanelet2_core/geometry/LineString.h>
#include <lanelet2_core/primitives/BoundingBox.h>

namespace autoware::motion_velocity_planner
{
std::optional<TrafficSignalStamped> PlannerData::get_traffic_signal(
const lanelet::Id id, const bool keep_last_observation) const
{
const auto & traffic_light_id_map =
keep_last_observation ? traffic_light_id_map_last_observed_ : traffic_light_id_map_raw_;
if (traffic_light_id_map.count(id) == 0) {
return std::nullopt;
}
return std::make_optional<TrafficSignalStamped>(traffic_light_id_map.at(id));
}

std::optional<double> PlannerData::calculate_min_deceleration_distance(
const double target_velocity) const
{
return motion_utils::calcDecelDistWithJerkAndAccConstraints(
current_odometry.twist.twist.linear.x, target_velocity,
current_acceleration.accel.accel.linear.x, velocity_smoother_->getMinDecel(),
std::abs(velocity_smoother_->getMinJerk()), velocity_smoother_->getMinJerk());
}

std::vector<StopPoint> PlannerData::calculate_map_stop_points(
const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & trajectory) const
{
std::vector<StopPoint> stop_points;
if (!route_handler) {
return stop_points;
}
universe_utils::LineString2d trajectory_ls;
for (const auto & p : trajectory) {
trajectory_ls.emplace_back(p.pose.position.x, p.pose.position.y);
}
const auto candidates = route_handler->getLaneletMapPtr()->laneletLayer.search(
boost::geometry::return_envelope<lanelet::BoundingBox2d>(trajectory_ls));
for (const auto & candidate : candidates) {
const auto stop_lines = lanelet::utils::query::stopLinesLanelet(candidate);
for (const auto & stop_line : stop_lines) {
const auto stop_line_2d = lanelet::utils::to2D(stop_line).basicLineString();
universe_utils::MultiPoint2d intersections;
boost::geometry::intersection(trajectory_ls, stop_line_2d, intersections);
for (const auto & intersection : intersections) {
const auto p =
geometry_msgs::msg::Point().set__x(intersection.x()).set__y(intersection.y());
const auto stop_line_arc_length = motion_utils::calcSignedArcLength(trajectory, 0UL, p);
StopPoint sp;
sp.ego_trajectory_arc_length = stop_line_arc_length - vehicle_info_.front_overhang_m;
if (sp.ego_trajectory_arc_length < 0.0) {
continue;
}
sp.ego_stop_pose =
motion_utils::calcInterpolatedPose(trajectory, sp.ego_trajectory_arc_length);
stop_points.push_back(sp);
}
}
}
return stop_points;
}
} // namespace autoware::motion_velocity_planner

0 comments on commit a8146ec

Please sign in to comment.