Skip to content

Commit b8dc9b9

Browse files
style(pre-commit): autofix
1 parent 4a6804f commit b8dc9b9

File tree

3 files changed

+13
-20
lines changed

3 files changed

+13
-20
lines changed

perception/autoware_multi_object_tracker/config/multi_object_tracker_node.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -37,4 +37,4 @@
3737
diagnostics_warn_delay: 0.5 # [sec]
3838
diagnostics_error_delay: 1.0 # [sec]
3939
diagnostics_warn_extrapolation_: 0.5 # [sec]
40-
diagnostics_error_extrapolation_: 1.0 # [sec]
40+
diagnostics_error_extrapolation_: 1.0 # [sec]

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp

+11-16
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,6 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
6464
diagnostics_warn_extrapolation_ = declare_parameter<double>("diagnostics_warn_extrapolation_");
6565
diagnostics_error_extrapolation_ = declare_parameter<double>("diagnostics_error_extrapolation_");
6666

67-
6867
declare_parameter("selected_input_channels", std::vector<std::string>());
6968
std::vector<std::string> selected_input_channels =
7069
get_parameter("selected_input_channels").as_string_array();
@@ -194,13 +193,12 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
194193
}
195194

196195
// Debugger
197-
debugger_ = std::make_unique<TrackerDebugger>(*this, world_frame_id_,input_channels_config_);
196+
debugger_ = std::make_unique<TrackerDebugger>(*this, world_frame_id_, input_channels_config_);
198197

199198
published_time_publisher_ = std::make_unique<autoware_utils::PublishedTimePublisher>(this);
200199
// Diagnostics
201-
diagnostics_interface_ptr_ =
202-
std::make_unique<autoware_utils::DiagnosticsInterface>(this, "multi_object_tracker_delay_compensation");
203-
200+
diagnostics_interface_ptr_ = std::make_unique<autoware_utils::DiagnosticsInterface>(
201+
this, "multi_object_tracker_delay_compensation");
204202
}
205203

206204
void MultiObjectTracker::onTrigger()
@@ -235,8 +233,8 @@ void MultiObjectTracker::onTimer()
235233
// Get minimum prediction time delta from all trackers
236234
const double min_extrapolation_time = (current_time - last_updated_time_).seconds();
237235

238-
239-
std::cout<<"MultiObjectTracker::onTimer: min_prediction_delta: "<<min_extrapolation_time<<std::endl;
236+
std::cout << "MultiObjectTracker::onTimer: min_prediction_delta: " << min_extrapolation_time
237+
<< std::endl;
240238

241239
// ensure minimum interval: room for the next process(prediction)
242240
const double minimum_publish_interval = publisher_period_ * minimum_publish_interval_ratio;
@@ -258,22 +256,19 @@ void MultiObjectTracker::onTimer()
258256

259257
if (min_extrapolation_time > diagnostics_error_extrapolation_) {
260258
std::stringstream message;
261-
message << "min_extrapolation_time exceeds error threshold ("
259+
message << "min_extrapolation_time exceeds error threshold ("
262260
<< diagnostics_error_extrapolation_ << "), current value: " << min_extrapolation_time;
263261
diagnostics_interface_ptr_->update_level_and_message(
264262
diagnostic_msgs::msg::DiagnosticStatus::ERROR, message.str());
265-
}
266-
else if (min_extrapolation_time > diagnostics_warn_extrapolation_) {
263+
} else if (min_extrapolation_time > diagnostics_warn_extrapolation_) {
267264
std::stringstream message;
268-
message << "min_extrapolation_time exceeds warning threshold ("
265+
message << "min_extrapolation_time exceeds warning threshold ("
269266
<< diagnostics_warn_extrapolation_ << "), current value: " << min_extrapolation_time;
270267
diagnostics_interface_ptr_->update_level_and_message(
271268
diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str());
272-
}
273-
else {
274-
diagnostics_interface_ptr_->update_level_and_message(
275-
diagnostic_msgs::msg::DiagnosticStatus::OK, "OK");
276-
269+
} else {
270+
diagnostics_interface_ptr_->update_level_and_message(
271+
diagnostic_msgs::msg::DiagnosticStatus::OK, "OK");
277272
}
278273
diagnostics_interface_ptr_->publish(current_time);
279274

perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -22,16 +22,15 @@
2222
#include "autoware/multi_object_tracker/object_model/types.hpp"
2323
#include "autoware/multi_object_tracker/odometry.hpp"
2424
#include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp"
25-
2625
#include "debugger/debugger.hpp"
2726
#include "processor/input_manager.hpp"
2827
#include "processor/processor.hpp"
2928

29+
#include <autoware_utils/ros/diagnostics_interface.hpp>
3030
#include <rclcpp/rclcpp.hpp>
3131

3232
#include "autoware_perception_msgs/msg/detected_objects.hpp"
3333
#include "autoware_perception_msgs/msg/tracked_objects.hpp"
34-
#include <autoware_utils/ros/diagnostics_interface.hpp>
3534
#include <geometry_msgs/msg/pose_stamped.hpp>
3635

3736
#include <tf2/LinearMath/Transform.h>
@@ -82,7 +81,6 @@ class MultiObjectTracker : public rclcpp::Node
8281
static constexpr double maximum_publish_interval_ratio = 1.05;
8382
double diagnostics_warn_extrapolation_;
8483
double diagnostics_error_extrapolation_;
85-
8684

8785
// internal states
8886
std::string world_frame_id_; // tracking frame

0 commit comments

Comments
 (0)