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(lane_departure_checker): add angle limitation to lane_departure_chacker #1034

Merged
merged 4 commits into from
Jun 3, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -12,3 +12,4 @@
max_lateral_deviation: 2.0
max_longitudinal_deviation: 2.0
max_yaw_deviation_deg: 60.0
delta_yaw_threshold_for_closest_point: 1.570 #M_PI/2.0, delta yaw thres for closest point
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <rosidl_runtime_cpp/message_initialization.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>
#include <tier4_autoware_utils/geometry/pose_deviation.hpp>
#include <tier4_autoware_utils/tier4_autoware_utils.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_auto_planning_msgs/msg/had_map_route.hpp>
Expand Down Expand Up @@ -55,6 +56,7 @@ struct Param
double max_lateral_deviation;
double max_longitudinal_deviation;
double max_yaw_deviation_deg;
double delta_yaw_threshold_for_closest_point;
};

struct Input
Expand Down Expand Up @@ -98,7 +100,8 @@ class LaneDepartureChecker
std::shared_ptr<vehicle_info_util::VehicleInfo> vehicle_info_ptr_;

static PoseDeviation calcTrajectoryDeviation(
const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose);
const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose,
const double yaw_threshold);

//! This function assumes the input trajectory is sampled dense enough
static TrajectoryPoints resampleTrajectory(const Trajectory & trajectory, const double interval);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,22 +56,14 @@ bool isInAnyLane(const lanelet::ConstLanelets & candidate_lanelets, const Point2
return false;
}

size_t findNearestIndex(const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose)
size_t findNearestIndexWithSoftYawConstraints(
const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose, const double yaw_threshold)
{
std::vector<double> distances;
distances.reserve(trajectory.points.size());
std::transform(
trajectory.points.cbegin(), trajectory.points.cend(), std::back_inserter(distances),
[&](const TrajectoryPoint & p) {
const auto p1 = tier4_autoware_utils::fromMsg(p.pose.position).to_2d();
const auto p2 = tier4_autoware_utils::fromMsg(pose.position).to_2d();
return boost::geometry::distance(p1, p2);
});

const auto min_itr = std::min_element(distances.cbegin(), distances.cend());
const auto min_idx = static_cast<size_t>(std::distance(distances.cbegin(), min_itr));

return min_idx;
const auto nearest_idx_optional = tier4_autoware_utils::findNearestIndex(
trajectory.points, pose, std::numeric_limits<double>::max(), yaw_threshold);
return nearest_idx_optional
? *nearest_idx_optional
: tier4_autoware_utils::findNearestIndex(trajectory.points, pose.position);
}

LinearRing2d createHullFromFootprints(const std::vector<LinearRing2d> & footprints)
Expand Down Expand Up @@ -116,8 +108,9 @@ Output LaneDepartureChecker::update(const Input & input)

tier4_autoware_utils::StopWatch<std::chrono::milliseconds> stop_watch;

output.trajectory_deviation =
calcTrajectoryDeviation(*input.reference_trajectory, input.current_pose->pose);
output.trajectory_deviation = calcTrajectoryDeviation(
*input.reference_trajectory, input.current_pose->pose,
param_.delta_yaw_threshold_for_closest_point);
output.processing_time_map["calcTrajectoryDeviation"] = stop_watch.toc(true);

{
Expand Down Expand Up @@ -152,9 +145,9 @@ Output LaneDepartureChecker::update(const Input & input)
}

PoseDeviation LaneDepartureChecker::calcTrajectoryDeviation(
const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose)
const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose, const double yaw_threshold)
{
const auto nearest_idx = findNearestIndex(trajectory, pose);
const auto nearest_idx = findNearestIndexWithSoftYawConstraints(trajectory, pose, yaw_threshold);
return tier4_autoware_utils::calcPoseDeviation(trajectory.points.at(nearest_idx).pose, pose);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -134,6 +134,8 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o
param_.max_lateral_deviation = declare_parameter("max_lateral_deviation", 1.0);
param_.max_longitudinal_deviation = declare_parameter("max_longitudinal_deviation", 1.0);
param_.max_yaw_deviation_deg = declare_parameter("max_yaw_deviation_deg", 30.0);
param_.delta_yaw_threshold_for_closest_point =
declare_parameter("delta_yaw_threshold_for_closest_point", 90.0);

// Parameter Callback
set_param_res_ =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,9 +96,11 @@ visualization_msgs::msg::MarkerArray StopLineModule::createVirtualWallMarkerArra
visualization_msgs::msg::MarkerArray wall_marker;
const auto p_front = tier4_autoware_utils::calcOffsetPose(
*debug_data_.stop_pose, debug_data_.base_link2front, 0.0, 0.0);
appendMarkerArray(
tier4_autoware_utils::createStopVirtualWallMarker(p_front, "stopline", now, module_id_), now,
&wall_marker);
if (state_ == State::APPROACH) {
appendMarkerArray(
tier4_autoware_utils::createStopVirtualWallMarker(p_front, "stopline", now, module_id_), now,
&wall_marker);
}
return wall_marker;
}
} // namespace behavior_velocity_planner