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 7, 2024
1 parent e752cad commit 190c5a1
Show file tree
Hide file tree
Showing 33 changed files with 98 additions and 76 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@
/>
<let
name="behavior_velocity_planner_launch_modules"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'behavior_velocity_planner::OcclusionSpotModulePlugin, '&quot;)"
value="$(eval &quot;'$(var behavior_velocity_planner_launch_modules)' + 'autoware::behavior_velocity_planner::OcclusionSpotModulePlugin, '&quot;)"
if="$(var launch_occlusion_spot_module)"
/>
<let
Expand Down
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="behavior_velocity_planner::PluginInterface"/>
</library>
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include <string>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
namespace
{
Expand Down Expand Up @@ -137,7 +137,7 @@ MarkerArray makePolygonMarker(
Marker debug_marker;
debug_marker.header.frame_id = "map";
debug_marker.header.stamp = rclcpp::Time(0);
debug_marker.id = planning_utils::bitShift(id);
debug_marker.id = ::behavior_velocity_planner::planning_utils::bitShift(id);
debug_marker.type = Marker::LINE_STRIP;
debug_marker.action = Marker::ADD;
debug_marker.pose.position = createMarkerPosition(0.0, 0.0, 0);
Expand Down Expand Up @@ -165,7 +165,7 @@ MarkerArray makeSlicePolygonMarker(
Marker debug_marker;
debug_marker.header.frame_id = "map";
debug_marker.header.stamp = rclcpp::Time(0);
debug_marker.id = planning_utils::bitShift(id);
debug_marker.id = ::behavior_velocity_planner::planning_utils::bitShift(id);
debug_marker.type = Marker::LINE_STRIP;
debug_marker.action = Marker::ADD;
debug_marker.pose.position = createMarkerPosition(0.0, 0.0, 0);
Expand Down Expand Up @@ -207,7 +207,7 @@ MarkerArray OcclusionSpotModule::createDebugMarkerArray()
}
if (!debug_data_.occlusion_points.empty()) {
appendMarkerArray(
debug::createPointsMarkerArray(
::behavior_velocity_planner::debug::createPointsMarkerArray(
debug_data_.occlusion_points, "occlusion", module_id_, now, 0.5, 0.5, 0.5, 1.0, 0.0, 0.0),
&debug_marker_array, now);
}
Expand All @@ -227,4 +227,4 @@ motion_utils::VirtualWalls OcclusionSpotModule::createVirtualWalls()
}
return virtual_walls;
}
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <utility>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
namespace grid_utils
{
Expand All @@ -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 @@ -134,6 +134,7 @@ std::optional<Polygon2d> generateOcclusionPolygon(

Polygon2d generateOccupancyPolygon(const nav_msgs::msg::MapMetaData & info, const double r = 100)
{
using ::behavior_velocity_planner::to_bg2d;
using tier4_autoware_utils::calcOffsetPose;
// generate occupancy polygon from grid origin
Polygon2d poly; // create counter clockwise poly
Expand All @@ -142,7 +143,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 Expand Up @@ -381,4 +382,4 @@ void denoiseOccupancyGridCV(
grid_map::GridMapRosConverter::fromOccupancyGrid(occupancy_grid, "layer", grid_map);
}
} // namespace grid_utils
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change
Expand Up @@ -49,18 +49,23 @@

#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::PoseStamped;
namespace grid_utils
{
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using ::behavior_velocity_planner::Polygons2d;
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 Expand Up @@ -118,6 +123,6 @@ void denoiseOccupancyGridCV(
grid_map::GridMap & grid_map, const GridParam & param, const bool is_show_debug_window,
const int num_iter, const bool use_object_footprints, const bool use_object_ray_casts);
} // namespace grid_utils
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // GRID_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,14 @@
#include <string>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
using occlusion_spot_utils::DETECTION_METHOD;
using occlusion_spot_utils::PASS_JUDGE;
using tier4_autoware_utils::getOrDeclareParameter;

OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
: ::behavior_velocity_planner::SceneModuleManagerInterface(node, getModuleName())
{
const std::string ns(getModuleName());
auto & pp = planner_param_;
Expand Down Expand Up @@ -128,16 +128,18 @@ void OcclusionSpotModuleManager::launchNewModules(
}
}

std::function<bool(const std::shared_ptr<SceneModuleInterface> &)>
std::function<bool(const std::shared_ptr<::behavior_velocity_planner::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<::behavior_velocity_planner::SceneModuleInterface> &
scene_module) { return false; };
}
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(
behavior_velocity_planner::OcclusionSpotModulePlugin, behavior_velocity_planner::PluginInterface)
autoware::behavior_velocity_planner::OcclusionSpotModulePlugin,
behavior_velocity_planner::PluginInterface)
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,9 @@
#include <string>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
class OcclusionSpotModuleManager : public SceneModuleManagerInterface
class OcclusionSpotModuleManager : public ::behavior_velocity_planner::SceneModuleManagerInterface
{
public:
explicit OcclusionSpotModuleManager(rclcpp::Node & node);
Expand All @@ -55,14 +55,15 @@ 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<::behavior_velocity_planner::SceneModuleInterface> &)>
getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) override;
};

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

} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // MANAGER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,10 @@
#include <utility>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
using ::behavior_velocity_planner::LineString2d;
using ::behavior_velocity_planner::Polygon2d;
namespace bg = boost::geometry;
namespace occlusion_spot_utils
{
Expand All @@ -43,7 +45,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 =
::behavior_velocity_planner::upScalePolygon(obj_pose.position, obj_footprint, scale);
return obj_footprint;
}

Expand Down Expand Up @@ -77,7 +80,7 @@ bool buildDetectionAreaPolygon(
const size_t target_seg_idx, const PlannerParam & param)
{
const auto & p = param;
DetectionRange da_range;
::behavior_velocity_planner::DetectionRange da_range;
da_range.interval = p.detection_area.slice_length;
da_range.min_longitudinal_distance =
std::max(0.0, p.baselink_to_front - p.detection_area.min_longitudinal_offset);
Expand All @@ -89,7 +92,7 @@ bool buildDetectionAreaPolygon(
da_range.right_overhang = p.right_overhang;
da_range.left_overhang = p.left_overhang;
slices.clear();
return planning_utils::createDetectionAreaPolygons(
return ::behavior_velocity_planner::planning_utils::createDetectionAreaPolygons(
slices, path, target_pose, target_seg_idx, da_range, p.pedestrian_vel);
}

Expand Down Expand Up @@ -485,4 +488,4 @@ std::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionSpo
}

} // namespace occlusion_spot_utils
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
#include <utility>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::PredictedObject;
Expand All @@ -63,6 +63,9 @@ using tier4_planning_msgs::msg::PathPointWithLaneId;
using tier4_planning_msgs::msg::PathWithLaneId;
using DetectionAreaIdx = std::optional<std::pair<double, double>>;
using BasicPolygons2d = std::vector<lanelet::BasicPolygon2d>;
// TODO(Maxime): remove once behavior_velocity_planner is moved to the autoware namespace
using ::behavior_velocity_planner::Point2d;
using ::behavior_velocity_planner::Polygons2d;

namespace occlusion_spot_utils
{
Expand Down Expand Up @@ -246,6 +249,6 @@ bool generatePossibleCollisionsFromGridMap(
DebugData & debug_data);

} // namespace occlusion_spot_utils
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // OCCLUSION_SPOT_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include <algorithm>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
namespace occlusion_spot_utils
{
Expand All @@ -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);
::behavior_velocity_planner::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 = ::behavior_velocity_planner::planning_utils::insertDecelPoint(
pose.position, *inout_path, safe_velocity);
if (decel_pose) debug_poses.push_back(decel_pose.value());
}
}
Expand Down Expand Up @@ -98,4 +99,4 @@ SafeMotion calculateSafeMotion(const Velocity & v, const double ttv)
return sm;
}
} // namespace occlusion_spot_utils
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include <algorithm>
#include <vector>

namespace behavior_velocity_planner
namespace autoware::behavior_velocity_planner
{
namespace occlusion_spot_utils
{
Expand All @@ -38,6 +38,6 @@ void applySafeVelocityConsideringPossibleCollision(
SafeMotion calculateSafeMotion(const Velocity & v, const double ttv);

} // namespace occlusion_spot_utils
} // namespace behavior_velocity_planner
} // namespace autoware::behavior_velocity_planner

#endif // RISK_PREDICTIVE_BRAKING_HPP_
Loading

0 comments on commit 190c5a1

Please sign in to comment.