Skip to content

Commit 2ffb7d8

Browse files
committedMay 17, 2024
chore: refactoring
Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 9edd2e0 commit 2ffb7d8

File tree

4 files changed

+32
-26
lines changed

4 files changed

+32
-26
lines changed
 

‎perception/multi_object_tracker/include/multi_object_tracker/debugger/debug_object.hpp

-20
Original file line numberDiff line numberDiff line change
@@ -97,26 +97,6 @@ class TrackerObjectDebugger
9797
visualization_msgs::msg::MarkerArray & marker_array) const;
9898
void process();
9999
void getMessage(visualization_msgs::msg::MarkerArray & marker_array) const;
100-
101-
private:
102-
std::string uuid_to_string(const unique_identifier_msgs::msg::UUID & u) const
103-
{
104-
std::stringstream ss;
105-
for (auto i = 0; i < 16; ++i) {
106-
ss << std::hex << std::setfill('0') << std::setw(2) << +u.uuid[i];
107-
}
108-
return ss.str();
109-
}
110-
111-
boost::uuids::uuid to_boost_uuid(const unique_identifier_msgs::msg::UUID & uuid_msg)
112-
{
113-
const std::string uuid_str = uuid_to_string(uuid_msg);
114-
boost::uuids::string_generator gen;
115-
boost::uuids::uuid uuid = gen(uuid_str);
116-
return uuid;
117-
}
118-
119-
int32_t uuid_to_int(const boost::uuids::uuid & uuid) { return boost::uuids::hash_value(uuid); }
120100
};
121101

122102
#endif // MULTI_OBJECT_TRACKER__DEBUGGER__DEBUG_OBJECT_HPP_

‎perception/multi_object_tracker/src/debugger/debug_object.cpp

+28-3
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,31 @@
2323
#include <sstream>
2424
#include <string>
2525

26+
namespace
27+
{
28+
std::string uuidToString(const unique_identifier_msgs::msg::UUID & uuid_msg)
29+
{
30+
std::stringstream ss;
31+
for (auto i = 0; i < 16; ++i) {
32+
ss << std::hex << std::setfill('0') << std::setw(2) << +uuid_msg.uuid[i];
33+
}
34+
return ss.str();
35+
}
36+
37+
boost::uuids::uuid uuidToBoostUuid(const unique_identifier_msgs::msg::UUID & uuid_msg)
38+
{
39+
const std::string uuid_str = uuidToString(uuid_msg);
40+
boost::uuids::string_generator gen;
41+
boost::uuids::uuid uuid = gen(uuid_str);
42+
return uuid;
43+
}
44+
45+
int32_t uuidToInt(const boost::uuids::uuid & uuid)
46+
{
47+
return boost::uuids::hash_value(uuid);
48+
}
49+
} // namespace
50+
2651
TrackerObjectDebugger::TrackerObjectDebugger(std::string frame_id)
2752
{
2853
// set frame id
@@ -67,9 +92,9 @@ void TrackerObjectDebugger::collect(
6792

6893
autoware_auto_perception_msgs::msg::TrackedObject tracked_object;
6994
(*(tracker_itr))->getTrackedObject(message_time, tracked_object);
70-
object_data.uuid = to_boost_uuid(tracked_object.object_id);
71-
object_data.uuid_int = uuid_to_int(object_data.uuid);
72-
object_data.uuid_str = uuid_to_string(tracked_object.object_id);
95+
object_data.uuid = uuidToBoostUuid(tracked_object.object_id);
96+
object_data.uuid_int = uuidToInt(object_data.uuid);
97+
object_data.uuid_str = uuidToString(tracked_object.object_id);
7398

7499
// tracker
75100
bool is_associated = false;

‎perception/multi_object_tracker/src/debugger/debugger.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -30,12 +30,12 @@ TrackerDebugger::TrackerDebugger(rclcpp::Node & node, const std::string & frame_
3030
if (debug_settings_.publish_tentative_objects) {
3131
debug_tentative_objects_pub_ =
3232
node_.create_publisher<autoware_auto_perception_msgs::msg::TrackedObjects>(
33-
"multi_object_tracker/debug/tentative_objects", rclcpp::QoS{1});
33+
"~/debug/tentative_objects", rclcpp::QoS{1});
3434
}
3535

3636
if (debug_settings_.publish_debug_markers) {
3737
debug_objects_markers_pub_ = node_.create_publisher<visualization_msgs::msg::MarkerArray>(
38-
"multi_object_tracker/debug/objects_markers", rclcpp::QoS{1});
38+
"~/debug/objects_markers", rclcpp::QoS{1});
3939
}
4040

4141
// initialize timestamps

‎perception/multi_object_tracker/src/processor/input_manager.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,8 @@ void InputStream::updateTimingStatus(const rclcpp::Time & now, const rclcpp::Tim
122122

123123
// Update time
124124
latest_message_time_ = now;
125-
if (std::abs((latest_measurement_time_ - objects_time).seconds()) > 3.0) {
125+
constexpr double delay_threshold = 3.0; // [s]
126+
if (std::abs((latest_measurement_time_ - objects_time).seconds()) > delay_threshold) {
126127
// Reset the latest measurement time if the time difference is too large
127128
latest_measurement_time_ = objects_time;
128129
RCLCPP_WARN(

0 commit comments

Comments
 (0)