Skip to content

Commit 9cc857a

Browse files
committed
migrate
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 91612b3 commit 9cc857a

File tree

2 files changed

+11
-14
lines changed

2 files changed

+11
-14
lines changed

planning/behavior_velocity_intersection_module/src/manager.cpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -35,10 +35,11 @@ using tier4_autoware_utils::getOrDeclareParameter;
3535
IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
3636
: SceneModuleManagerInterfaceWithRTC(
3737
node, getModuleName(),
38-
getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc.intersection")),
38+
getOrDeclareParameter<bool>(node, std::string(getModuleName()) + ".enable_rtc.intersection")),
3939
occlusion_rtc_interface_(
4040
&node, "intersection_occlusion",
41-
getEnableRTC(node, std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
41+
getOrDeclareParameter<bool>(
42+
node, std::string(getModuleName()) + ".enable_rtc.intersection_to_occlusion"))
4243
{
4344
const std::string ns(getModuleName());
4445
auto & ip = intersection_param_;
@@ -345,10 +346,10 @@ void IntersectionModuleManager::launchNewModules(
345346
const UUID uuid = getUUID(new_module->getModuleId());
346347
const auto occlusion_uuid = new_module->getOcclusionUUID();
347348
rtc_interface_.updateCooperateStatus(
348-
uuid, true, State::RUNNING, std::numeric_limits<double>::lowest(),
349-
std::numeric_limits<double>::lowest(), clock_->now());
349+
uuid, true, std::numeric_limits<double>::lowest(), std::numeric_limits<double>::lowest(),
350+
clock_->now());
350351
occlusion_rtc_interface_.updateCooperateStatus(
351-
occlusion_uuid, true, State::RUNNING, std::numeric_limits<double>::lowest(),
352+
occlusion_uuid, true, std::numeric_limits<double>::lowest(),
352353
std::numeric_limits<double>::lowest(), clock_->now());
353354
registerModule(std::move(new_module));
354355
}
@@ -404,13 +405,12 @@ void IntersectionModuleManager::sendRTC(const Time & stamp)
404405
const UUID uuid = getUUID(scene_module->getModuleId());
405406
const bool safety =
406407
scene_module->isSafe() && (!intersection_module->isOcclusionFirstStopRequired());
407-
updateRTCStatus(uuid, safety, State::RUNNING, scene_module->getDistance(), stamp);
408+
updateRTCStatus(uuid, safety, scene_module->getDistance(), stamp);
408409
const auto occlusion_uuid = intersection_module->getOcclusionUUID();
409410
const auto occlusion_distance = intersection_module->getOcclusionDistance();
410411
const auto occlusion_safety = intersection_module->getOcclusionSafety();
411412
occlusion_rtc_interface_.updateCooperateStatus(
412-
occlusion_uuid, occlusion_safety, State::RUNNING, occlusion_distance, occlusion_distance,
413-
stamp);
413+
occlusion_uuid, occlusion_safety, occlusion_distance, occlusion_distance, stamp);
414414

415415
// ==========================================================================================
416416
// module debug data

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

+3-6
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@
2020
#include <behavior_velocity_planner_common/utilization/util.hpp>
2121
#include <lanelet2_extension/regulatory_elements/autoware_traffic_light.hpp>
2222
#include <lanelet2_extension/utility/utilities.hpp>
23-
#include <motion_utils/factor/velocity_factor_interface.hpp>
2423
#include <motion_utils/trajectory/trajectory.hpp>
2524
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp> // for toPolygon2d
2625
#include <tier4_autoware_utils/geometry/geometry.hpp>
@@ -45,7 +44,6 @@ namespace bg = boost::geometry;
4544
using intersection::make_err;
4645
using intersection::make_ok;
4746
using intersection::Result;
48-
using motion_utils::VelocityFactorInterface;
4947

5048
IntersectionModule::IntersectionModule(
5149
const int64_t module_id, const int64_t lane_id,
@@ -1282,14 +1280,13 @@ void IntersectionModule::updateTrafficSignalObservation()
12821280
return;
12831281
}
12841282
const auto [tl_id, point] = tl_id_and_point_.value();
1285-
const auto tl_info_opt =
1286-
planner_data_->getTrafficSignal(tl_id, true /* traffic light module keeps last observation*/);
1283+
const auto tl_info_opt = planner_data_->getTrafficSignal(tl_id);
12871284
if (!tl_info_opt) {
12881285
// the info of this traffic light is not available
12891286
return;
12901287
}
1291-
last_tl_valid_observation_ = tl_info_opt.value();
1292-
internal_debug_data_.tl_observation = tl_info_opt.value();
1288+
last_tl_valid_observation_ = *tl_info_opt;
1289+
internal_debug_data_.tl_observation = *tl_info_opt;
12931290
}
12941291

12951292
IntersectionModule::PassJudgeStatus IntersectionModule::isOverPassJudgeLinesStatus(

0 commit comments

Comments
 (0)