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

refactor(motion_utils, obstacle_cruise_planner): add offset to virtual wall utils func #2078

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 @@ -15,23 +15,23 @@
#ifndef MOTION_UTILS__MARKER__MARKER_HELPER_HPP_
#define MOTION_UTILS__MARKER__MARKER_HELPER_HPP_

#include "tier4_autoware_utils/ros/marker_helper.hpp"
#include "tier4_autoware_utils/tier4_autoware_utils.hpp"

#include <string>

namespace motion_utils
{
visualization_msgs::msg::MarkerArray createStopVirtualWallMarker(
const geometry_msgs::msg::Pose & pose, const std::string & module_name, const rclcpp::Time & now,
const int32_t id);
const int32_t id, const double longitudinal_offset = 0.0);

visualization_msgs::msg::MarkerArray createSlowDownVirtualWallMarker(
const geometry_msgs::msg::Pose & pose, const std::string & module_name, const rclcpp::Time & now,
const int32_t id);
const int32_t id, const double longitudinal_offset = 0.0);

visualization_msgs::msg::MarkerArray createDeadLineVirtualWallMarker(
const geometry_msgs::msg::Pose & pose, const std::string & module_name, const rclcpp::Time & now,
const int32_t id);
const int32_t id, const double longitudinal_offset = 0.0);

visualization_msgs::msg::MarkerArray createDeletedStopVirtualWallMarker(
const rclcpp::Time & now, const int32_t id);
Expand Down
18 changes: 12 additions & 6 deletions common/motion_utils/src/marker/marker_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,26 +83,32 @@ namespace motion_utils
{
visualization_msgs::msg::MarkerArray createStopVirtualWallMarker(
const geometry_msgs::msg::Pose & pose, const std::string & module_name, const rclcpp::Time & now,
const int32_t id)
const int32_t id, const double longitudinal_offset)
{
const auto pose_with_offset =
tier4_autoware_utils::calcOffsetPose(pose, longitudinal_offset, 0.0, 0.0);
return createVirtualWallMarkerArray(
pose, module_name, "stop_", now, id, createMarkerColor(1.0, 0.0, 0.0, 0.5));
pose_with_offset, module_name, "stop_", now, id, createMarkerColor(1.0, 0.0, 0.0, 0.5));
}

visualization_msgs::msg::MarkerArray createSlowDownVirtualWallMarker(
const geometry_msgs::msg::Pose & pose, const std::string & module_name, const rclcpp::Time & now,
const int32_t id)
const int32_t id, const double longitudinal_offset)
{
const auto pose_with_offset =
tier4_autoware_utils::calcOffsetPose(pose, longitudinal_offset, 0.0, 0.0);
return createVirtualWallMarkerArray(
pose, module_name, "slow_down_", now, id, createMarkerColor(1.0, 1.0, 0.0, 0.5));
pose_with_offset, module_name, "slow_down_", now, id, createMarkerColor(1.0, 1.0, 0.0, 0.5));
}

visualization_msgs::msg::MarkerArray createDeadLineVirtualWallMarker(
const geometry_msgs::msg::Pose & pose, const std::string & module_name, const rclcpp::Time & now,
const int32_t id)
const int32_t id, const double longitudinal_offset)
{
const auto pose_with_offset =
tier4_autoware_utils::calcOffsetPose(pose, longitudinal_offset, 0.0, 0.0);
return createVirtualWallMarkerArray(
pose, module_name, "dead_line_", now, id, createMarkerColor(0.0, 1.0, 0.0, 0.5));
pose_with_offset, module_name, "dead_line_", now, id, createMarkerColor(0.0, 1.0, 0.0, 0.5));
}

visualization_msgs::msg::MarkerArray createDeletedStopVirtualWallMarker(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -238,11 +238,10 @@ VelocityLimit PIDBasedPlanner::doCruise(
: std::abs(vehicle_info_.min_longitudinal_offset_m);
const double dist_to_rss_wall =
std::min(dist_to_cruise + abs_ego_offset, dist_to_obstacle + abs_ego_offset);
const size_t wall_idx = obstacle_cruise_utils::getIndexWithLongitudinalOffset(
planner_data.traj.points, dist_to_rss_wall, ego_idx);

const auto markers = motion_utils::createSlowDownVirtualWallMarker(
planner_data.traj.points.at(wall_idx).pose, "obstacle cruise", planner_data.current_time, 0);
planner_data.traj.points.at(ego_idx).pose, "obstacle cruise", planner_data.current_time, 0,
dist_to_rss_wall);
tier4_autoware_utils::appendMarkerArray(markers, &debug_wall_marker);

debug_obstacles_to_cruise.push_back(cruise_obstacle_info.obstacle);
Expand Down
7 changes: 2 additions & 5 deletions planning/obstacle_cruise_planner/src/planner_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,13 +195,10 @@ Trajectory PlannerInterface::generateStopTrajectory(
std::max(0.0, closest_obstacle_dist - abs_ego_offset - feasible_margin_from_obstacle);
const auto zero_vel_idx = motion_utils::insertStopPoint(0, zero_vel_dist, output_traj.points);
if (zero_vel_idx) {
const auto wall_idx = obstacle_cruise_utils::getIndexWithLongitudinalOffset(
output_traj.points, abs_ego_offset, *zero_vel_idx);

// virtual wall marker for stop obstacle
const auto marker_pose = output_traj.points.at(wall_idx).pose;
const auto markers = motion_utils::createStopVirtualWallMarker(
marker_pose, "obstacle stop", planner_data.current_time, 0);
output_traj.points.at(*zero_vel_idx).pose, "obstacle stop", planner_data.current_time, 0,
abs_ego_offset);
tier4_autoware_utils::appendMarkerArray(markers, &debug_data.stop_wall_marker);
debug_data.obstacles_to_stop.push_back(*closest_stop_obstacle);

Expand Down