Skip to content

Commit

Permalink
feat(behavior_velocity_detection_area): use base class without RTC
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <[email protected]>
  • Loading branch information
takayuki5168 committed Dec 27, 2024
1 parent a313653 commit 4673814
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 21 deletions.
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,18 +105,12 @@ 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()) {
last_obstacle_found_time_ = {};
if (!planner_param_.suppress_pass_judge_when_stopping || !is_stopped) {
state_ = State::GO;
}
return true;
last_obstacle_found_time_ = {};
if (!planner_param_.suppress_pass_judge_when_stopping || !is_stopped) {
state_ = State::GO;
}
return true;

// Force ignore objects after dead_line
if (planner_param_.use_dead_line) {
Expand All @@ -139,7 +133,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 +145,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 +161,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

0 comments on commit 4673814

Please sign in to comment.