Skip to content

Commit

Permalink
refactor(occlusion_spot): add autoware prefix
Browse files Browse the repository at this point in the history
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
  • Loading branch information
maxime-clem committed Jun 10, 2024
1 parent ac483b9 commit 54cf638
Show file tree
Hide file tree
Showing 30 changed files with 32 additions and 18 deletions.
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(behavior_velocity_occlusion_spot_module)
project(autoware_behavior_velocity_occlusion_spot_module)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>behavior_velocity_occlusion_spot_module</name>
<name>autoware_behavior_velocity_occlusion_spot_module</name>
<version>0.1.0</version>
<description>The behavior_velocity_occlusion_spot_module package</description>
<description>The autoware_behavior_velocity_occlusion_spot_module package</description>

<maintainer email="taiki.tanaka@tier4.jp">Taiki Tanaka</maintainer>
<maintainer email="tomoya.kimura@tier4.jp">Tomoya Kimura</maintainer>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
<library path="autoware_behavior_velocity_occlusion_spot_module">
<class type="autoware::behavior_velocity_planner::OcclusionSpotModulePlugin" base_class_type="autoware::behavior_velocity_planner::PluginInterface"/>
</library>
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ Polygon2d pointsToPoly(const Point2d p0, const Point2d p1, const double radius)
// std::cout << boost::geometry::wkt(line_poly) << std::endl;
// std::cout << boost::geometry::wkt(line) << std::endl;

bg::correct(line_poly);
boost::geometry::correct(line_poly);
return line_poly;
}

Expand Down Expand Up @@ -142,7 +142,7 @@ Polygon2d generateOccupancyPolygon(const nav_msgs::msg::MapMetaData & info, cons
poly.outer().emplace_back(to_bg2d(calcOffsetPose(info.origin, r, r, 0).position));
poly.outer().emplace_back(to_bg2d(calcOffsetPose(info.origin, 0, r, 0).position));

bg::correct(poly);
boost::geometry::correct(poly);
return poly;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,10 @@ using geometry_msgs::msg::Point;
using geometry_msgs::msg::TransformStamped;
using nav_msgs::msg::MapMetaData;
using nav_msgs::msg::OccupancyGrid;
using tier4_autoware_utils::LineString2d;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;

namespace occlusion_cost_value
{
static constexpr unsigned char FREE_SPACE = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,9 +132,10 @@ std::function<bool(const std::shared_ptr<SceneModuleInterface> &)>
OcclusionSpotModuleManager::getModuleExpiredFunction(
const tier4_planning_msgs::msg::PathWithLaneId & path)
{
return [path]([[maybe_unused]] const std::shared_ptr<SceneModuleInterface> & scene_module) {
return false;
};
return
[path](
[[maybe_unused]] const std::shared_ptr<SceneModuleInterface> &
scene_module) { return false; };
}
} // namespace autoware::behavior_velocity_planner

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,11 +55,12 @@ class OcclusionSpotModuleManager : public SceneModuleManagerInterface

void launchNewModules(const tier4_planning_msgs::msg::PathWithLaneId & path) override;

std::function<bool(const std::shared_ptr<SceneModuleInterface> &)> getModuleExpiredFunction(
const tier4_planning_msgs::msg::PathWithLaneId & path) override;
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)>
getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override;
};

class OcclusionSpotModulePlugin : public PluginWrapper<OcclusionSpotModuleManager>
class OcclusionSpotModulePlugin
: public PluginWrapper<OcclusionSpotModuleManager>
{
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,8 @@ Polygon2d toFootprintPolygon(const PredictedObject & object, const double scale
const Pose & obj_pose = object.kinematics.initial_pose_with_covariance.pose;
Polygon2d obj_footprint = tier4_autoware_utils::toPolygon2d(object);
// upscale foot print for noise
obj_footprint = upScalePolygon(obj_pose.position, obj_footprint, scale);
obj_footprint =
upScalePolygon(obj_pose.position, obj_footprint, scale);
return obj_footprint;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,8 @@ void applySafeVelocityConsideringPossibleCollision(

// safe slow down: consider ego smooth brake
const double v_safe_slow_down =
planning_utils::calcDecelerationVelocityFromDistanceToTarget(j_min, a_min, a0, v0, l_obs);
planning_utils::calcDecelerationVelocityFromDistanceToTarget(
j_min, a_min, a0, v0, l_obs);

// TODO(tanaka): consider edge case if ego passed safe margin
const double v_slow_down = (l_obs < 0 && v0 <= v_safe) ? v_safe : v_safe_slow_down;
Expand All @@ -62,8 +63,8 @@ void applySafeVelocityConsideringPossibleCollision(
safe_velocity = std::max(safe_velocity, v_min);
possible_collision.obstacle_info.safe_motion.safe_velocity = safe_velocity;
const auto & pose = possible_collision.collision_with_margin.pose;
const auto & decel_pose =
planning_utils::insertDecelPoint(pose.position, *inout_path, safe_velocity);
const auto & decel_pose = planning_utils::insertDecelPoint(
pose.position, *inout_path, safe_velocity);
if (decel_pose) debug_poses.push_back(decel_pose.value());
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,8 @@ namespace autoware::behavior_velocity_planner
namespace utils = occlusion_spot_utils;

OcclusionSpotModule::OcclusionSpotModule(
const int64_t module_id, const std::shared_ptr<const PlannerData> & planner_data,
const int64_t module_id,
const std::shared_ptr<const PlannerData> & planner_data,
const PlannerParam & planner_param, const rclcpp::Logger & logger,
const rclcpp::Clock::SharedPtr clock)
: SceneModuleInterface(module_id, logger, clock), param_(planner_param)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,14 +46,16 @@ class OcclusionSpotModule : public SceneModuleInterface

public:
OcclusionSpotModule(
const int64_t module_id, const std::shared_ptr<const PlannerData> & planner_data,
const int64_t module_id,
const std::shared_ptr<const PlannerData> & planner_data,
const PlannerParam & planner_param, const rclcpp::Logger & logger,
const rclcpp::Clock::SharedPtr clock);

/**
* @brief plan occlusion spot velocity at unknown area in occupancy grid
*/
bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override;
bool modifyPathVelocity(
PathWithLaneId * path, StopReason * stop_reason) override;

visualization_msgs::msg::MarkerArray createDebugMarkerArray() override;
motion_utils::VirtualWalls createVirtualWalls() override;
Expand Down

0 comments on commit 54cf638

Please sign in to comment.