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

feat(behavior_velocity_detection_area): use base class without RTC #9802

Merged
Merged
Show file tree
Hide file tree
Changes from 2 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 @@ -8,5 +8,4 @@
state_clear_time: 2.0
hold_stop_margin_distance: 0.0
distance_to_judge_over_stop_line: 0.5
enable_rtc: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval
suppress_pass_judge_when_stopping: false
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,7 @@ using autoware::universe_utils::getOrDeclareParameter;
using lanelet::autoware::DetectionArea;

DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(), getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc"))
: SceneModuleManagerInterface(node, getModuleName())
{
const std::string ns(DetectionAreaModuleManager::getModuleName());
planner_param_.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
Expand Down Expand Up @@ -66,10 +65,6 @@ void DetectionAreaModuleManager::launchNewModules(
registerModule(std::make_shared<DetectionAreaModule>(
module_id, lane_id, *detection_area_with_lane_id.first, planner_param_,
logger_.get_child("detection_area_module"), clock_));
generateUUID(module_id);
updateRTCStatus(
getUUID(module_id), true, State::WAITING_FOR_EXECUTION,
std::numeric_limits<double>::lowest(), path.header.stamp);
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@

namespace autoware::behavior_velocity_planner
{
class DetectionAreaModuleManager : public SceneModuleManagerInterfaceWithRTC
class DetectionAreaModuleManager : public SceneModuleManagerInterface<>
{
public:
explicit DetectionAreaModuleManager(rclcpp::Node & node);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,12 +105,10 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
modified_stop_line_seg_idx = current_seg_idx;
}

setDistance(stop_dist);

// Check state
setSafe(detection_area::can_clear_stop_state(
last_obstacle_found_time_, clock_->now(), planner_param_.state_clear_time));
if (isActivated()) {
const bool is_safe = detection_area::can_clear_stop_state(
last_obstacle_found_time_, clock_->now(), planner_param_.state_clear_time);
if (is_safe) {
last_obstacle_found_time_ = {};
if (!planner_param_.suppress_pass_judge_when_stopping || !is_stopped) {
state_ = State::GO;
Expand Down Expand Up @@ -139,7 +137,6 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
dead_line_seg_idx);
if (dist_from_ego_to_dead_line < 0.0) {
RCLCPP_WARN(logger_, "[detection_area] vehicle is over dead line");
setSafe(true);
return true;
}
}
Expand All @@ -152,7 +149,6 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
if (
state_ != State::STOP &&
dist_from_ego_to_stop < -planner_param_.distance_to_judge_over_stop_line) {
setSafe(true);
return true;
}

Expand All @@ -169,7 +165,6 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
RCLCPP_WARN_THROTTLE(
logger_, *clock_, std::chrono::milliseconds(1000).count(),
"[detection_area] vehicle is over stop border");
setSafe(true);
return true;
}
}
Expand Down
Loading