diff --git a/carma_cooperative_perception/src/multiple_object_tracker_component.cpp b/carma_cooperative_perception/src/multiple_object_tracker_component.cpp index dde1d1500f..46d080ffaf 100644 --- a/carma_cooperative_perception/src/multiple_object_tracker_component.cpp +++ b/carma_cooperative_perception/src/multiple_object_tracker_component.cpp @@ -265,15 +265,6 @@ auto MultipleObjectTrackerNode::handle_on_configure( } }); - declare_parameter( - "execution_frequency_hz", mot::remove_units(units::frequency::hertz_t{1 / execution_period_})); - - declare_parameter( - "track_promotion_threshold", static_cast(track_manager_.get_promotion_threshold().value)); - - declare_parameter( - "track_removal_threshold", static_cast(track_manager_.get_promotion_threshold().value)); - on_set_parameters_callback_ = add_on_set_parameters_callback([this](const std::vector & parameters) { rcl_interfaces::msg::SetParametersResult result; @@ -338,6 +329,15 @@ auto MultipleObjectTrackerNode::handle_on_configure( return result; }); + declare_parameter( + "execution_frequency_hz", mot::remove_units(units::frequency::hertz_t{1 / execution_period_})); + + declare_parameter( + "track_promotion_threshold", static_cast(track_manager_.get_promotion_threshold().value)); + + declare_parameter( + "track_removal_threshold", static_cast(track_manager_.get_promotion_threshold().value)); + RCLCPP_INFO(get_logger(), "Lifecycle transition: successfully configured"); return carma_ros2_utils::CallbackReturn::SUCCESS;