Skip to content

Commit

Permalink
migrate
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin committed Oct 18, 2024
1 parent 91612b3 commit 9cc857a
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 14 deletions.
16 changes: 8 additions & 8 deletions planning/behavior_velocity_intersection_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,11 @@ using tier4_autoware_utils::getOrDeclareParameter;
IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterfaceWithRTC(
node, getModuleName(),
getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc.intersection")),
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc.intersection")),
occlusion_rtc_interface_(
&node, "intersection_occlusion",
getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
getOrDeclareParameter<bool>(
node, std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
{
const std::string ns(getModuleName());
auto & ip = intersection_param_;
Expand Down Expand Up @@ -345,10 +346,10 @@ void IntersectionModuleManager::launchNewModules(
const UUID uuid = getUUID(new_module->getModuleId());
const auto occlusion_uuid = new_module->getOcclusionUUID();
rtc_interface_.updateCooperateStatus(
uuid, true, State::RUNNING, std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::lowest(), clock_->now());
uuid, true, std::numeric_limits<double>::lowest(), std::numeric_limits<double>::lowest(),
clock_->now());
occlusion_rtc_interface_.updateCooperateStatus(
occlusion_uuid, true, State::RUNNING, std::numeric_limits<double>::lowest(),
occlusion_uuid, true, std::numeric_limits<double>::lowest(),
std::numeric_limits<double>::lowest(), clock_->now());
registerModule(std::move(new_module));
}
Expand Down Expand Up @@ -404,13 +405,12 @@ void IntersectionModuleManager::sendRTC(const Time & stamp)
const UUID uuid = getUUID(scene_module->getModuleId());
const bool safety =
scene_module->isSafe() && (!intersection_module->isOcclusionFirstStopRequired());
updateRTCStatus(uuid, safety, State::RUNNING, scene_module->getDistance(), stamp);
updateRTCStatus(uuid, safety, scene_module->getDistance(), stamp);
const auto occlusion_uuid = intersection_module->getOcclusionUUID();
const auto occlusion_distance = intersection_module->getOcclusionDistance();
const auto occlusion_safety = intersection_module->getOcclusionSafety();
occlusion_rtc_interface_.updateCooperateStatus(
occlusion_uuid, occlusion_safety, State::RUNNING, occlusion_distance, occlusion_distance,
stamp);
occlusion_uuid, occlusion_safety, occlusion_distance, occlusion_distance, stamp);

// ==========================================================================================
// module debug data
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include <behavior_velocity_planner_common/utilization/util.hpp>
#include <lanelet2_extension/regulatory_elements/autoware_traffic_light.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <motion_utils/factor/velocity_factor_interface.hpp>
#include <motion_utils/trajectory/trajectory.hpp>
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp> // for toPolygon2d
#include <tier4_autoware_utils/geometry/geometry.hpp>
Expand All @@ -45,7 +44,6 @@ namespace bg = boost::geometry;
using intersection::make_err;
using intersection::make_ok;
using intersection::Result;
using motion_utils::VelocityFactorInterface;

IntersectionModule::IntersectionModule(
const int64_t module_id, const int64_t lane_id,
Expand Down Expand Up @@ -1282,14 +1280,13 @@ void IntersectionModule::updateTrafficSignalObservation()
return;
}
const auto [tl_id, point] = tl_id_and_point_.value();
const auto tl_info_opt =
planner_data_->getTrafficSignal(tl_id, true /* traffic light module keeps last observation*/);
const auto tl_info_opt = planner_data_->getTrafficSignal(tl_id);
if (!tl_info_opt) {
// the info of this traffic light is not available
return;
}
last_tl_valid_observation_ = tl_info_opt.value();
internal_debug_data_.tl_observation = tl_info_opt.value();
last_tl_valid_observation_ = *tl_info_opt;
internal_debug_data_.tl_observation = *tl_info_opt;
}

IntersectionModule::PassJudgeStatus IntersectionModule::isOverPassJudgeLinesStatus(
Expand Down

0 comments on commit 9cc857a

Please sign in to comment.