@@ -35,10 +35,11 @@ using tier4_autoware_utils::getOrDeclareParameter;
35
35
IntersectionModuleManager::IntersectionModuleManager (rclcpp::Node & node)
36
36
: SceneModuleManagerInterfaceWithRTC(
37
37
node, getModuleName(),
38
- getEnableRTC (node, std::string(getModuleName()) + ".enable_rtc.intersection")),
38
+ getOrDeclareParameter< bool > (node, std::string(getModuleName()) + " .enable_rtc.intersection" )),
39
39
occlusion_rtc_interface_ (
40
40
&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"))
42
43
{
43
44
const std::string ns (getModuleName ());
44
45
auto & ip = intersection_param_;
@@ -345,10 +346,10 @@ void IntersectionModuleManager::launchNewModules(
345
346
const UUID uuid = getUUID (new_module->getModuleId ());
346
347
const auto occlusion_uuid = new_module->getOcclusionUUID ();
347
348
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 ());
350
351
occlusion_rtc_interface_.updateCooperateStatus (
351
- occlusion_uuid, true , State::RUNNING, std::numeric_limits<double >::lowest (),
352
+ occlusion_uuid, true , std::numeric_limits<double >::lowest (),
352
353
std::numeric_limits<double >::lowest (), clock_->now ());
353
354
registerModule (std::move (new_module));
354
355
}
@@ -404,13 +405,12 @@ void IntersectionModuleManager::sendRTC(const Time & stamp)
404
405
const UUID uuid = getUUID (scene_module->getModuleId ());
405
406
const bool safety =
406
407
scene_module->isSafe () && (!intersection_module->isOcclusionFirstStopRequired ());
407
- updateRTCStatus (uuid, safety, State::RUNNING, scene_module->getDistance (), stamp);
408
+ updateRTCStatus (uuid, safety, scene_module->getDistance (), stamp);
408
409
const auto occlusion_uuid = intersection_module->getOcclusionUUID ();
409
410
const auto occlusion_distance = intersection_module->getOcclusionDistance ();
410
411
const auto occlusion_safety = intersection_module->getOcclusionSafety ();
411
412
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);
414
414
415
415
// ==========================================================================================
416
416
// module debug data
0 commit comments