Skip to content

Commit

Permalink
Merge branch 'main' into chore/pointpainting_launcher
Browse files Browse the repository at this point in the history
  • Loading branch information
miursh authored Feb 20, 2024
2 parents 19e0e5b + dd52489 commit 81a84ca
Show file tree
Hide file tree
Showing 6 changed files with 68 additions and 58 deletions.
15 changes: 6 additions & 9 deletions .github/CODEOWNERS
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@ common/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp
common/tier4_control_rviz_plugin/** taiki.tanaka@tier4.jp
common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp
common/tier4_debug_rviz_plugin/** takayuki.murooka@tier4.jp
common/tier4_debug_tools/** ryohsuke.mitsudome@tier4.jp
common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp takamasa.horibe@tier4.jp
common/tier4_logging_level_configure_rviz_plugin/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takamasa.horibe@tier4.jp
common/tier4_perception_rviz_plugin/** yukihiro.saito@tier4.jp
Expand Down Expand Up @@ -124,11 +123,11 @@ perception/detection_by_tracker/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp
perception/elevation_map_loader/** kosuke.takeuchi@tier4.jp taichi.higashide@tier4.jp
perception/euclidean_cluster/** yukihiro.saito@tier4.jp
perception/ground_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp
perception/image_projection_based_fusion/** dai.nguyen@tier4.jp kotaro.uetake@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp
perception/image_projection_based_fusion/** dai.nguyen@tier4.jp koji.minoda@tier4.jp kotaro.uetake@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp
perception/lidar_apollo_instance_segmentation/** yukihiro.saito@tier4.jp
perception/lidar_apollo_segmentation_tvm/** ambroise.vincent@arm.com xinyu.wang@tier4.jp
perception/lidar_apollo_segmentation_tvm_nodes/** ambroise.vincent@arm.com xinyu.wang@tier4.jp
perception/lidar_centerpoint/** kenzo.lobos@tier4.jp
perception/lidar_centerpoint/** kenzo.lobos@tier4.jp koji.minoda@tier4.jp
perception/lidar_centerpoint_tvm/** carl.liu@autocore.ai xinyu.wang@tier4.jp
perception/map_based_prediction/** kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yoshi.ri@tier4.jp
perception/multi_object_tracker/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp
Expand Down Expand Up @@ -192,10 +191,9 @@ planning/motion_velocity_smoother/** fumiya.watanabe@tier4.jp makoto.kurihara@ti
planning/objects_of_interest_marker_interface/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp zulfaqar.azmi@tier4.jp
planning/obstacle_avoidance_planner/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp
planning/obstacle_stop_planner/** berkay@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
planning/obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp
planning/path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp
planning/planning_debug_tools/** taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
planning/planning_test_utils/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp
planning/planning_topic_converter/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp
planning/planning_validator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp
Expand All @@ -209,12 +207,12 @@ planning/sampling_based_planner/sampler_common/** maxime.clement@tier4.jp
planning/scenario_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
planning/static_centerline_optimizer/** kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp
planning/surround_obstacle_checker/** satoshi.ota@tier4.jp
sensing/gnss_poser/** koji.minoda@tier4.jp yamato.ando@tier4.jp
sensing/gnss_poser/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
sensing/image_diagnostics/** dai.nguyen@tier4.jp
sensing/image_transport_decompressor/** yukihiro.saito@tier4.jp
sensing/imu_corrector/** koji.minoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
sensing/livox/livox_tag_filter/** ryohsuke.mitsudome@tier4.jp
sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp
sensing/pointcloud_preprocessor/** abrahammonrroy@yahoo.com kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp
sensing/radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp
sensing/radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp
sensing/radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp
Expand Down Expand Up @@ -242,8 +240,7 @@ system/system_error_monitor/** fumihito.ito@tier4.jp
system/system_monitor/** fumihito.ito@tier4.jp tetsuhiro.kawaguchi@tier4.jp
system/topic_state_monitor/** ryohsuke.mitsudome@tier4.jp
system/velodyne_monitor/** fumihito.ito@tier4.jp
tools/simulator_test/simulator_compatibility_test/** shpark@morai.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp
vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp
vehicle/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp
vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp
vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp
vehicle/steer_offset_estimator/** taiki.tanaka@tier4.jp
Expand Down
1 change: 1 addition & 0 deletions planning/mission_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
<maintainer email="ryohsuke.mitsudome@tier4.jp">Ryohsuke Mitsudome</maintainer>
<maintainer email="takamasa.horibe@tier4.jp">Takamasa Horibe</maintainer>
<maintainer email="takayuki.murooka@tier4.jp">Takayuki Murooka</maintainer>
<maintainer email="mamoru.sobue@tier4.jp">Mamoru Sobue</maintainer>
<license>Apache License 2.0</license>

<author email="ryohsuke.mitsudome@tier4.jp">Ryohsuke Mitsudome</author>
Expand Down
54 changes: 23 additions & 31 deletions planning/mission_planner/src/lanelet2_plugins/default_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,7 +195,6 @@ PlannerPlugin::MarkerArray DefaultPlanner::visualize(const LaneletRoute & route)
{
lanelet::ConstLanelets route_lanelets;
lanelet::ConstLanelets end_lanelets;
lanelet::ConstLanelets normal_lanelets;
lanelet::ConstLanelets goal_lanelets;

for (const auto & route_section : route.segments) {
Expand All @@ -210,16 +209,14 @@ PlannerPlugin::MarkerArray DefaultPlanner::visualize(const LaneletRoute & route)
}
}

std_msgs::msg::ColorRGBA cl_route;
std_msgs::msg::ColorRGBA cl_ll_borders;
std_msgs::msg::ColorRGBA cl_end;
std_msgs::msg::ColorRGBA cl_normal;
std_msgs::msg::ColorRGBA cl_goal;
set_color(&cl_route, 0.8, 0.99, 0.8, 0.15);
set_color(&cl_goal, 0.2, 0.4, 0.4, 0.05);
set_color(&cl_end, 0.2, 0.2, 0.4, 0.05);
set_color(&cl_normal, 0.2, 0.4, 0.2, 0.05);
set_color(&cl_ll_borders, 1.0, 1.0, 1.0, 0.999);
const std_msgs::msg::ColorRGBA cl_route =
tier4_autoware_utils::createMarkerColor(0.8, 0.99, 0.8, 0.15);
const std_msgs::msg::ColorRGBA cl_ll_borders =
tier4_autoware_utils::createMarkerColor(0.2, 0.4, 0.4, 0.05);
const std_msgs::msg::ColorRGBA cl_end =
tier4_autoware_utils::createMarkerColor(0.2, 0.2, 0.4, 0.05);
const std_msgs::msg::ColorRGBA cl_goal =
tier4_autoware_utils::createMarkerColor(1.0, 1.0, 1.0, 0.999);

visualization_msgs::msg::MarkerArray route_marker_array;
insert_marker_array(
Expand All @@ -231,9 +228,6 @@ PlannerPlugin::MarkerArray DefaultPlanner::visualize(const LaneletRoute & route)
insert_marker_array(
&route_marker_array,
lanelet::visualization::laneletsAsTriangleMarkerArray("end_lanelets", end_lanelets, cl_end));
insert_marker_array(
&route_marker_array, lanelet::visualization::laneletsAsTriangleMarkerArray(
"normal_lanelets", normal_lanelets, cl_normal));
insert_marker_array(
&route_marker_array,
lanelet::visualization::laneletsAsTriangleMarkerArray("goal_lanelets", goal_lanelets, cl_goal));
Expand Down Expand Up @@ -270,23 +264,18 @@ visualization_msgs::msg::MarkerArray DefaultPlanner::visualize_debug_footprint(
return msg;
}

bool DefaultPlanner::check_goal_footprint(
bool DefaultPlanner::check_goal_footprint_inside_lanes(
const lanelet::ConstLanelet & current_lanelet,
const lanelet::ConstLanelet & combined_prev_lanelet,
const tier4_autoware_utils::Polygon2d & goal_footprint, double & next_lane_length,
const double search_margin)
{
std::vector<tier4_autoware_utils::Point2d> points_intersection;

// check if goal footprint is in current lane
boost::geometry::intersection(
goal_footprint, combined_prev_lanelet.polygon2d().basicPolygon(), points_intersection);
if (points_intersection.empty()) {
if (boost::geometry::within(goal_footprint, combined_prev_lanelet.polygon2d().basicPolygon())) {
return true;
}
points_intersection.clear();

// check if goal footprint is in between many lanelets
// check if goal footprint is in between many lanelets in depth-first search manner
for (const auto & next_lane : routing_graph_ptr_->following(current_lanelet)) {
next_lane_length += lanelet::utils::getLaneletLength2d(next_lane);
lanelet::ConstLanelets lanelets;
Expand All @@ -295,17 +284,20 @@ bool DefaultPlanner::check_goal_footprint(
lanelet::ConstLanelet combined_lanelets =
combine_lanelets_with_shoulder(lanelets, shoulder_lanelets_);

// if next lanelet length longer than vehicle longitudinal offset
// if next lanelet length is longer than vehicle longitudinal offset
if (vehicle_info_.max_longitudinal_offset_m + search_margin < next_lane_length) {
next_lane_length -= lanelet::utils::getLaneletLength2d(next_lane);
boost::geometry::intersection(
goal_footprint, combined_lanelets.polygon2d().basicPolygon(), points_intersection);
if (points_intersection.empty()) {
// and if the goal_footprint is within the (accumulated) combined_lanelets, terminate the
// query
if (boost::geometry::within(goal_footprint, combined_lanelets.polygon2d().basicPolygon())) {
return true;
}
points_intersection.clear();
} else { // if next lanelet length shorter than vehicle longitudinal offset -> recursive call
if (!check_goal_footprint(next_lane, combined_lanelets, goal_footprint, next_lane_length)) {
// if not, iteration continues to next next_lane, and this subtree is terminated
} else { // if next lanelet length is shorter than vehicle longitudinal offset, check the
// overlap with the polygon including the next_lane(s) until the additional lanes get
// longer than ego vehicle length
if (!check_goal_footprint_inside_lanes(
next_lane, combined_lanelets, goal_footprint, next_lane_length)) {
next_lane_length -= lanelet::utils::getLaneletLength2d(next_lane);
continue;
} else {
Expand Down Expand Up @@ -352,13 +344,13 @@ bool DefaultPlanner::is_goal_valid(

double next_lane_length = 0.0;
// combine calculated route lanelets
lanelet::ConstLanelet combined_prev_lanelet =
const lanelet::ConstLanelet combined_prev_lanelet =
combine_lanelets_with_shoulder(path_lanelets, shoulder_lanelets_);

// check if goal footprint exceeds lane when the goal isn't in parking_lot
if (
param_.check_footprint_inside_lanes &&
!check_goal_footprint(
!check_goal_footprint_inside_lanes(
closest_lanelet, combined_prev_lanelet, polygon_footprint, next_lane_length) &&
!is_in_parking_lot(
lanelet::utils::query::getAllParkingLots(lanelet_map_ptr_),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,13 +71,38 @@ class DefaultPlanner : public mission_planner::PlannerPlugin

void initialize_common(rclcpp::Node * node);
void map_callback(const HADMapBin::ConstSharedPtr msg);
bool check_goal_footprint(

/**
* @brief check if the goal_footprint is within the combined lanelet of route_lanelets plus the
* succeeding lanelets around the goal
* @attention this function will terminate when the accumulated search length from the initial
* current_lanelet exceeds max_longitudinal_offset_m + search_margin, so under normal assumptions
* (i.e. the map is composed of finite elements of practically normal sized lanelets), it is
* assured to terminate
* @param current_lanelet the start lanelet to begin recursive query
* @param combined_prev_lanelet initial entire route_lanelets plus the small consecutive lanelets
* around the goal during the query
* @param next_lane_length the accumulated total length from the start lanelet of the search to
* the lanelet of current goal query
*/
bool check_goal_footprint_inside_lanes(
const lanelet::ConstLanelet & current_lanelet,
const lanelet::ConstLanelet & combined_prev_lanelet,
const tier4_autoware_utils::Polygon2d & goal_footprint, double & next_lane_length,
const double search_margin = 2.0);

/**
* @brief return true if (1)the goal is in parking area or (2)the goal is on the lanes and the
* footprint around the goal does not overlap the lanes
*/
bool is_goal_valid(const geometry_msgs::msg::Pose & goal, lanelet::ConstLanelets path_lanelets);

/**
* @brief project the specified goal pose onto the goal lanelet(the last preferred lanelet of
* route_sections) and return the z-aligned goal position
*/
Pose refine_goal_height(const Pose & goal, const RouteSections & route_sections);

void updateRoute(const PlannerPlugin::LaneletRoute & route);
void clearRoute();
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,6 @@
#include <unordered_set>
#include <utility>

bool exists(const std::unordered_set<lanelet::Id> & set, const lanelet::Id & id)
{
return set.find(id) != set.end();
}

tier4_autoware_utils::Polygon2d convert_linear_ring_to_polygon(
tier4_autoware_utils::LinearRing2d footprint)
{
Expand All @@ -40,14 +35,6 @@ tier4_autoware_utils::Polygon2d convert_linear_ring_to_polygon(
return footprint_polygon;
}

void set_color(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, double a)
{
cl->r = r;
cl->g = g;
cl->b = b;
cl->a = a;
}

void insert_marker_array(
visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2)
{
Expand All @@ -64,7 +51,7 @@ lanelet::ConstLanelet combine_lanelets_with_shoulder(
std::vector<uint64_t> right_bound_ids;

for (const auto & llt : lanelets) {
if (llt.id() != 0) {
if (llt.id() != lanelet::InvalId) {
left_bound_ids.push_back(llt.leftBound().id());
right_bound_ids.push_back(llt.rightBound().id());
}
Expand Down Expand Up @@ -96,6 +83,8 @@ lanelet::ConstLanelet combine_lanelets_with_shoulder(
add_bound(left_shared_shoulder_it->leftBound(), lefts);
} else if (
// if not exist, add left bound of lanelet to lefts
// if the **left** of this lanelet does not match any of the **right** bounds of `lanelets`,
// then its left bound constitutes the left boundary of the entire merged lanelet
std::count(right_bound_ids.begin(), right_bound_ids.end(), llt.leftBound().id()) < 1) {
add_bound(llt.leftBound(), lefts);
}
Expand All @@ -108,6 +97,8 @@ lanelet::ConstLanelet combine_lanelets_with_shoulder(
add_bound(right_shared_shoulder_it->rightBound(), rights);
} else if (
// if not exist, add right bound of lanelet to rights
// if the **right** of this lanelet does not match any of the **left** bounds of `lanelets`,
// then its right bound constitutes the right boundary of the entire merged lanelet
std::count(left_bound_ids.begin(), left_bound_ids.end(), llt.rightBound().id()) < 1) {
add_bound(llt.rightBound(), rights);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,6 @@
#include <unordered_set>
#include <vector>

bool exists(const std::unordered_set<lanelet::Id> & set, const lanelet::Id & id);

template <typename T>
bool exists(const std::vector<T> & vectors, const T & item)
{
Expand All @@ -45,12 +43,18 @@ bool exists(const std::vector<T> & vectors, const T & item)

tier4_autoware_utils::Polygon2d convert_linear_ring_to_polygon(
tier4_autoware_utils::LinearRing2d footprint);
void set_color(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, double a);
void insert_marker_array(
visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2);

/**
* @brief create a single merged lanelet whose left/right bounds consist of the leftmost/rightmost
* bound of the original lanelets or the left/right bound of its adjacent road_shoulder respectively
* @param lanelets topologically sorted sequence of lanelets
* @param shoulder_lanelets list of possible road_shoulder lanelets to combine with lanelets
*/
lanelet::ConstLanelet combine_lanelets_with_shoulder(
const lanelet::ConstLanelets & lanelets, const lanelet::ConstLanelets & shoulder_lanelets);

std::vector<geometry_msgs::msg::Point> convertCenterlineToPoints(const lanelet::Lanelet & lanelet);
geometry_msgs::msg::Pose convertBasicPoint3dToPose(
const lanelet::BasicPoint3d & point, const double lane_yaw);
Expand Down

0 comments on commit 81a84ca

Please sign in to comment.