Skip to content

Commit 1047f94

Browse files
committed
fix again
1 parent 7c07161 commit 1047f94

File tree

2 files changed

+14
-12
lines changed

2 files changed

+14
-12
lines changed

perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@
3535
#include <Eigen/Core>
3636
#include <Eigen/Geometry>
3737
#include <rclcpp_components/register_node_macro.hpp>
38+
#include <rclcpp/rclcpp.hpp>
3839

3940
namespace
4041
{
@@ -257,7 +258,7 @@ void MultiObjectTracker::runProcess(
257258
rclcpp::Time(input_objects_msg.header.stamp, this->now().get_clock_type());
258259

259260
const auto & list_tracker = processor_->getListTracker();
260-
const auto & detected_objects;
261+
autoware_perception_msgs::msg::DetectedObjects detected_objects;
261262

262263
// Get the transform of the self frame
263264
const auto self_transform =
@@ -323,7 +324,7 @@ void MultiObjectTracker::runProcess(
323324
/* tracker pruning */
324325
processor_->prune(measurement_time);
325326

326-
RCLCPP_INFO(get_logger(), "\nobject links:\n%s", debug_message.c_str());
327+
RCLCPP_INFO(this->get_logger(), "\nobject links:\n%s", debug_message.c_str());
327328

328329
/* spawn new tracker */
329330
if (input_manager_->isChannelSpawnEnabled(channel_index)) {

perception/multi_object_tracker/src/processor/processor.cpp

+11-10
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,9 @@
2121

2222
#include <iterator>
2323

24+
#include <rclcpp/logging.hpp>
25+
26+
2427
using Label = autoware_perception_msgs::msg::ObjectClassification;
2528

2629
TrackerProcessor::TrackerProcessor(
@@ -47,13 +50,13 @@ void TrackerProcessor::predict(const rclcpp::Time & time)
4750
}
4851

4952
void TrackerProcessor::update(
50-
// Add at the beginning of the function
51-
std::string debug_message = "";
52-
5353
const autoware_perception_msgs::msg::DetectedObjects & detected_objects,
5454
const geometry_msgs::msg::Transform & self_transform,
5555
const std::unordered_map<int, int> & direct_assignment, const uint & channel_index)
5656
{
57+
// Add at the beginning of the function
58+
std::string debug_message = "";
59+
5760
int tracker_idx = 0;
5861
const auto & time = detected_objects.header.stamp;
5962
for (auto tracker_itr = list_tracker_.begin(); tracker_itr != list_tracker_.end();
@@ -65,11 +68,10 @@ void TrackerProcessor::update(
6568
->updateWithMeasurement(associated_object, time, self_transform, channel_index);
6669

6770
char buf[120];
68-
snprintf(buf, sizeof(buf), "track meas update idx[%d], x[%.3f], y[%.3f], t[%.3f], cls[%d]\n",
71+
snprintf(buf, sizeof(buf), "track meas update idx[%d], x[%.3f], y[%.3f], cls[%d]\n",
6972
tracker_idx,
7073
associated_object.kinematics.pose_with_covariance.pose.position.x,
7174
associated_object.kinematics.pose_with_covariance.pose.position.y,
72-
measurement_time.seconds(),
7375
associated_object.classification.at(0).label);
7476
debug_message += buf;
7577

@@ -78,19 +80,18 @@ void TrackerProcessor::update(
7880
(*(tracker_itr))->updateWithoutMeasurement(time);
7981

8082
char buf[120];
81-
snprintf(buf, sizeof(buf), "track no meas update idx[%d], x[%.3f], y[%.3f], t[%.3f], cls[%d]\n",
83+
snprintf(buf, sizeof(buf), "track no meas update idx[%d], x[%.3f], y[%.3f], cls[%d]\n",
8284
tracker_idx,
8385
associated_object.kinematics.pose_with_covariance.pose.position.x,
8486
associated_object.kinematics.pose_with_covariance.pose.position.y,
85-
measurement_time.seconds(),
8687
associated_object.classification.at(0).label);
8788
debug_message += buf;
8889

8990
}
9091
}
9192
// Add at the end of the function, before return
9293
if (!debug_message.empty()) {
93-
RCLCPP_INFO(get_logger(), "\nobject updates:\n%s", debug_message.c_str());
94+
RCLCPP_INFO(rclcpp::get_logger("multi_object_tracker"), "\nobject updates:\n%s", debug_message.c_str());
9495
}
9596
}
9697

@@ -109,7 +110,7 @@ void TrackerProcessor::spawn(
109110
createNewTracker(new_object, time, self_transform, channel_index);
110111
if (tracker) {
111112
list_tracker_.push_back(tracker);
112-
RCLCPP_INFO(get_logger(), "New tracker");
113+
RCLCPP_INFO(rclcpp::get_logger("multi_object_tracker"), "New tracker [%ld]", i);
113114
}
114115
}
115116
}
@@ -240,7 +241,7 @@ void TrackerProcessor::removeOverlappedTracker(const rclcpp::Time & time)
240241
sorted_list_tracker.erase(sorted_list_tracker.begin() + j);
241242
--j;
242243

243-
RCLCPP_INFO(get_logger(), "Erase tracker [%d] -> [%d] ", i, j);
244+
RCLCPP_INFO(rclcpp::get_logger("multi_object_tracker"), "Erase tracker [%ld] -> [%ld] ", i, j);
244245
}
245246
}
246247
}

0 commit comments

Comments
 (0)