Skip to content

Commit

Permalink
refactor: rename consider_odometry_uncertainty to enable_odometry_unc…
Browse files Browse the repository at this point in the history
…ertainty
  • Loading branch information
technolojin committed Oct 23, 2024
1 parent fa45c87 commit 6abfbea
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
double publish_rate = declare_parameter<double>("publish_rate"); // [hz]
world_frame_id_ = declare_parameter<std::string>("world_frame_id");
bool enable_delay_compensation{declare_parameter<bool>("enable_delay_compensation")};
consider_odometry_uncertainty_ = declare_parameter<bool>("consider_odometry_uncertainty");
enable_odometry_uncertainty_ = declare_parameter<bool>("consider_odometry_uncertainty");

Check warning on line 90 in perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

MultiObjectTracker::MultiObjectTracker increases from 99 to 100 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

declare_parameter("selected_input_channels", std::vector<std::string>());
std::vector<std::string> selected_input_channels =
Expand Down Expand Up @@ -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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class MultiObjectTracker : public rclcpp::Node
std::string world_frame_id_; // tracking frame
std::unique_ptr<DataAssociation> association_;
std::unique_ptr<TrackerProcessor> processor_;
bool consider_odometry_uncertainty_;
bool enable_odometry_uncertainty_;

// input manager
std::unique_ptr<InputManager> input_manager_;
Expand Down

0 comments on commit 6abfbea

Please sign in to comment.