diff --git a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp index 9e284832ec13b..dba00b6f589ee 100644 --- a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp +++ b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp @@ -87,7 +87,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) double publish_rate = declare_parameter("publish_rate"); // [hz] world_frame_id_ = declare_parameter("world_frame_id"); bool enable_delay_compensation{declare_parameter("enable_delay_compensation")}; - consider_odometry_uncertainty_ = declare_parameter("consider_odometry_uncertainty"); + enable_odometry_uncertainty_ = declare_parameter("consider_odometry_uncertainty"); declare_parameter("selected_input_channels", std::vector()); std::vector selected_input_channels = @@ -277,7 +277,7 @@ void MultiObjectTracker::runProcess( // the object uncertainty DetectedObjects input_objects_with_uncertainty = input_objects; - if (consider_odometry_uncertainty_) { + if (enable_odometry_uncertainty_) { // Create a modeled odometry message nav_msgs::msg::Odometry odometry; odometry.header.stamp = measurement_time + rclcpp::Duration::from_seconds(0.001); diff --git a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp index a970e10e1c010..b9886ee3fc847 100644 --- a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp +++ b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp @@ -87,7 +87,7 @@ class MultiObjectTracker : public rclcpp::Node std::string world_frame_id_; // tracking frame std::unique_ptr association_; std::unique_ptr processor_; - bool consider_odometry_uncertainty_; + bool enable_odometry_uncertainty_; // input manager std::unique_ptr input_manager_;