Skip to content

Commit

Permalink
dekita
Browse files Browse the repository at this point in the history
Signed-off-by: Yuki Takagi <[email protected]>
  • Loading branch information
yuki-takagi-66 committed Apr 11, 2024
1 parent b05bd5c commit df5f1f0
Show file tree
Hide file tree
Showing 5 changed files with 120 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -125,6 +125,7 @@
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/input/acceleration" to="/localization/acceleration"/>
<remap from="~/input/objects" to="/perception/object_recognition/objects"/>
<remap from="~/input/vector_map" to="/map/vector_map"/>
<remap from="~/output/trajectory" to="$(var interface_output_topic)"/>
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
<remap from="~/output/velocity_limit" to="/planning/scenario_planning/max_velocity_candidates"/>
Expand Down Expand Up @@ -174,6 +175,7 @@
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/input/acceleration" to="/localization/acceleration"/>
<remap from="~/input/objects" to="/perception/object_recognition/objects"/>
<remap from="~/input/vector_map" to="/map/vector_map"/>
<remap from="~/output/trajectory" to="obstacle_cruise/trajectory"/>
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
<remap from="~/output/velocity_limit" to="/planning/scenario_planning/max_velocity_candidates"/>
Expand All @@ -198,6 +200,7 @@
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/input/acceleration" to="/localization/acceleration"/>
<remap from="~/input/objects" to="/perception/object_recognition/objects"/>
<remap from="~/input/vector_map" to="/map/vector_map"/>
<remap from="~/output/trajectory" to="$(var interface_output_topic)"/>
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
<remap from="~/output/velocity_limit" to="/planning/scenario_planning/max_velocity_candidates"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include "obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp"
#include "obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp"
#include "obstacle_cruise_planner/type_alias.hpp"
#include "route_handler/route_handler.hpp"
#include "signal_processing/lowpass_filter_1d.hpp"
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
#include "tier4_autoware_utils/system/stop_watch.hpp"
Expand Down Expand Up @@ -136,11 +137,15 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
rclcpp::Subscription<PredictedObjects>::SharedPtr objects_sub_;
rclcpp::Subscription<Odometry>::SharedPtr odom_sub_;
rclcpp::Subscription<AccelWithCovarianceStamped>::SharedPtr acc_sub_;
rclcpp::Subscription<HADMapBin>::SharedPtr lanelet_map_sub_;

// data for callback functions
PredictedObjects::ConstSharedPtr objects_ptr_{nullptr};
Odometry::ConstSharedPtr ego_odom_ptr_{nullptr};
AccelWithCovarianceStamped::ConstSharedPtr ego_accel_ptr_{nullptr};
HADMapBin::ConstSharedPtr vector_map_ptr_{nullptr};

std::shared_ptr<route_handler::RouteHandler> route_handler_;

// Vehicle Parameters
VehicleInfo vehicle_info_;
Expand Down Expand Up @@ -198,6 +203,9 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
// consideration for the current ego pose
bool enable_to_consider_current_pose{false};
double time_to_convergence{1.5};
bool work_as_pseudo_occulusion{false};

Check warning on line 206 in planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (occulusion)

Check warning on line 206 in planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (occulusion)
double max_obj_vel_for_pseudo_occulusion{0.0};

Check warning on line 207 in planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (occulusion)

Check warning on line 207 in planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (occulusion)
std::vector<lanelet::Id> focus_intersections_for_pseudo_occulusion{};

Check warning on line 208 in planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (occulusion)

Check warning on line 208 in planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (occulusion)
};
BehaviorDeterminationParam behavior_determination_param_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include "autoware_adapi_v1_msgs/msg/planning_behavior.hpp"
#include "autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp"
#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp"
#include "autoware_auto_perception_msgs/msg/predicted_object.hpp"
#include "autoware_auto_perception_msgs/msg/predicted_objects.hpp"
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
Expand All @@ -38,6 +39,7 @@
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
using autoware_adapi_v1_msgs::msg::VelocityFactor;
using autoware_adapi_v1_msgs::msg::VelocityFactorArray;
using autoware_auto_mapping_msgs::msg::HADMapBin;
using autoware_auto_perception_msgs::msg::ObjectClassification;
using autoware_auto_perception_msgs::msg::PredictedObject;
using autoware_auto_perception_msgs::msg::PredictedObjects;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
<remap from="~/input/trajectory" to="$(var input_trajectory)"/>
<remap from="~/input/odometry" to="$(var input_odometry)"/>
<remap from="~/input/objects" to="$(var input_objects)"/>
<remap from="~/input/vector_map" to="$(var input_map)"/>

<!-- output -->
<remap from="~/output/trajectory" to="$(var output_trajectory)"/>
Expand Down
107 changes: 106 additions & 1 deletion planning/obstacle_cruise_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,18 +16,63 @@

#include "motion_utils/resample/resample.hpp"
#include "motion_utils/trajectory/tmp_conversion.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "object_recognition_utils/predicted_path_utils.hpp"
#include "obstacle_cruise_planner/polygon_utils.hpp"
#include "obstacle_cruise_planner/utils.hpp"
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"
#include "tier4_autoware_utils/ros/update_param.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp>

#include <boost/format.hpp>
#include <boost/geometry/algorithms/correct.hpp>
#include <boost/geometry/algorithms/intersects.hpp>

#include <lanelet2_core/geometry/LineString.h>
#include <lanelet2_core/geometry/Polygon.h>

#include <algorithm>
#include <chrono>

#define debug(var) \
do { \
std::cerr << __LINE__ << ", " << __func__ << ", " << #var << ": "; \
view(var); \
} while (0)
template <typename T>
void view(T e)
{
std::cerr << e << std::endl;
}
template <typename T>
void view(const std::vector<T> & v)
{
for (const auto & e : v) {
std::cerr << e << " ";
}
std::cerr << std::endl;
}
template <typename T>
void view(const std::vector<std::vector<T>> & vv)
{
for (const auto & v : vv) {
view(v);
}
}
#define line() \
{ \
std::cerr << __LINE__ << ", " << __func__ << std::endl; \
}
#define line_with_file() \
{ \
std::cerr << "(" << __FILE__ << ") " << __func__ << ": " << __LINE__ << std::endl; \
}

namespace
{
VelocityLimitClearCommand createVelocityLimitClearCommandMessage(
Expand Down Expand Up @@ -275,6 +320,14 @@ ObstacleCruisePlannerNode::BehaviorDeterminationParam::BehaviorDeterminationPara
"behavior_determination.consider_current_pose.enable_to_consider_current_pose");
time_to_convergence = node.declare_parameter<double>(
"behavior_determination.consider_current_pose.time_to_convergence");
work_as_pseudo_occulusion = node.declare_parameter<bool>(

Check warning on line 323 in planning/obstacle_cruise_planner/src/node.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (occulusion)

Check warning on line 323 in planning/obstacle_cruise_planner/src/node.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (occulusion)
"behavior_determination.slow_down.pseudo_occulusion.enable_function");

Check warning on line 324 in planning/obstacle_cruise_planner/src/node.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (occulusion)

Check warning on line 324 in planning/obstacle_cruise_planner/src/node.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (occulusion)
if (work_as_pseudo_occulusion) {

Check warning on line 325 in planning/obstacle_cruise_planner/src/node.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (occulusion)

Check warning on line 325 in planning/obstacle_cruise_planner/src/node.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (occulusion)
max_obj_vel_for_pseudo_occulusion = node.declare_parameter<double>(
"behavior_determination.slow_down.pseudo_occulusion.max_obj_vel");
focus_intersections_for_pseudo_occulusion = node.declare_parameter<std::vector<lanelet::Id>>(
"behavior_determination.slow_down.pseudo_occulusion.focus_intersections");
}
}

void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
Expand Down Expand Up @@ -335,6 +388,17 @@ void ObstacleCruisePlannerNode::BehaviorDeterminationParam::onParam(
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.consider_current_pose.time_to_convergence",
time_to_convergence);
tier4_autoware_utils::updateParam<bool>(
parameters, "behavior_determination.slow_down.pseudo_occulusion.enable_function",
work_as_pseudo_occulusion);
if (work_as_pseudo_occulusion) {
tier4_autoware_utils::updateParam<double>(
parameters, "behavior_determination.slow_down.pseudo_occulusion.max_obj_vel",
max_obj_vel_for_pseudo_occulusion);
tier4_autoware_utils::updateParam<std::vector<lanelet::Id>>(
parameters, "behavior_determination.slow_down.pseudo_occulusion.focus_intersections",
focus_intersections_for_pseudo_occulusion);
}
}

ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & node_options)
Expand All @@ -357,6 +421,9 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions &
acc_sub_ = create_subscription<AccelWithCovarianceStamped>(
"~/input/acceleration", rclcpp::QoS{1},
[this](const AccelWithCovarianceStamped::ConstSharedPtr msg) { ego_accel_ptr_ = msg; });
lanelet_map_sub_ = create_subscription<HADMapBin>(
"~/input/vector_map", rclcpp::QoS(10).transient_local(),
[this](const HADMapBin::ConstSharedPtr msg) { vector_map_ptr_ = msg; });

// publisher
trajectory_pub_ = create_publisher<Trajectory>("~/output/trajectory", 1);
Expand Down Expand Up @@ -486,9 +553,11 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms
const auto traj_points = motion_utils::convertToTrajectoryPointArray(*msg);

// check if subscribed variables are ready
if (traj_points.empty() || !ego_odom_ptr_ || !ego_accel_ptr_ || !objects_ptr_) {
if (
traj_points.empty() || !ego_odom_ptr_ || !ego_accel_ptr_ || !objects_ptr_ || !vector_map_ptr_) {
return;
}
route_handler_ = std::make_shared<route_handler::RouteHandler>(*vector_map_ptr_);

stop_watch_.tic(__func__);
*debug_data_ptr_ = DebugData();
Expand Down Expand Up @@ -1130,6 +1199,42 @@ std::optional<SlowDownObstacle> ObstacleCruisePlannerNode::createSlowDownObstacl
return std::nullopt;
}

const auto is_occulusion_object = [&]() {
if (
std::hypot(obstacle.twist.linear.x, obstacle.twist.linear.y) >
behavior_determination_param_.max_obj_vel_for_pseudo_occulusion + 1e-6) {
line();
return false;
}

if (motion_utils::calcLateralOffset(traj_points, obstacle.pose.position) > 0.0) {
line();
return true;
}

for (const auto & id :
behavior_determination_param_.focus_intersections_for_pseudo_occulusion) {
if (id == 0) {
continue;
}
const auto intersection_poly =
lanelet::utils::to2D(route_handler_->getLaneletMapPtr()->polygonLayer.get(id))
.basicPolygon();
if (
boost::geometry::within(obstacle_poly, intersection_poly) ||
boost::geometry::intersects(obstacle_poly, intersection_poly)) {
line();
return true;
}
}
line();
return false;
};

if (behavior_determination_param_.work_as_pseudo_occulusion && !is_occulusion_object()) {
return std::nullopt;
}

// calculate front collision point
double front_min_dist = std::numeric_limits<double>::max();
geometry_msgs::msg::Point front_collision_point;
Expand Down

0 comments on commit df5f1f0

Please sign in to comment.