Skip to content

Commit

Permalink
fix(intersection): fix bugs (#6050)
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin authored Jan 11, 2024
1 parent 5a0e141 commit 73c9e17
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@
enable: false
creep_velocity: 0.8333
peeking_offset: -0.5
occlusion_required_clearance_distance: 55
occlusion_required_clearance_distance: 55.0
possible_object_bbox: [1.5, 2.5]
ignore_parked_vehicle_speed_threshold: 0.8333
occlusion_detection_hold_time: 1.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
getOrDeclareParameter<double>(node, ns + ".occlusion.creep_during_peeking.creep_velocity");
ip.occlusion.peeking_offset =
getOrDeclareParameter<double>(node, ns + ".occlusion.peeking_offset");
ip.occlusion.occlusion_required_clearance_distance =
getOrDeclareParameter<double>(node, ns + ".occlusion.occlusion_required_clearance_distance");
ip.occlusion.possible_object_bbox =
getOrDeclareParameter<std::vector<double>>(node, ns + ".occlusion.possible_object_bbox");
ip.occlusion.ignore_parked_vehicle_speed_threshold =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1195,7 +1195,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
}
}

const double is_amber_or_red =
const bool is_amber_or_red =
(traffic_prioritized_level == TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) ||
(traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED);
auto occlusion_status =
Expand Down

0 comments on commit 73c9e17

Please sign in to comment.