Skip to content

Commit 05e9c89

Browse files
authoredNov 30, 2023
feat(map_based_prediction): use glog (#5721)
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 3ac90b0 commit 05e9c89

File tree

3 files changed

+9
-0
lines changed

3 files changed

+9
-0
lines changed
 

‎perception/map_based_prediction/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,8 @@ autoware_package()
66

77
find_package(Eigen3 REQUIRED)
88

9+
find_package(glog REQUIRED)
10+
911
include_directories(
1012
SYSTEM
1113
${EIGEN3_INCLUDE_DIR}
@@ -17,6 +19,8 @@ ament_auto_add_library(map_based_prediction_node SHARED
1719
src/debug.cpp
1820
)
1921

22+
target_link_libraries(map_based_prediction_node glog::glog)
23+
2024
rclcpp_components_register_node(map_based_prediction_node
2125
PLUGIN "map_based_prediction::MapBasedPredictionNode"
2226
EXECUTABLE map_based_prediction

‎perception/map_based_prediction/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
<depend>autoware_auto_perception_msgs</depend>
1919
<depend>interpolation</depend>
2020
<depend>lanelet2_extension</depend>
21+
<depend>libgoogle-glog-dev</depend>
2122
<depend>motion_utils</depend>
2223
<depend>rclcpp</depend>
2324
<depend>rclcpp_components</depend>

‎perception/map_based_prediction/src/map_based_prediction_node.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,8 @@
4343
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
4444
#endif
4545

46+
#include <glog/logging.h>
47+
4648
#include <algorithm>
4749
#include <chrono>
4850
#include <cmath>
@@ -718,6 +720,8 @@ void replaceObjectYawWithLaneletsYaw(
718720
MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options)
719721
: Node("map_based_prediction", node_options), debug_accumulated_time_(0.0)
720722
{
723+
google::InitGoogleLogging("map_based_prediction_node");
724+
google::InstallFailureSignalHandler();
721725
enable_delay_compensation_ = declare_parameter<bool>("enable_delay_compensation");
722726
prediction_time_horizon_ = declare_parameter<double>("prediction_time_horizon");
723727
lateral_control_time_horizon_ =

0 commit comments

Comments
 (0)