Skip to content

Commit

Permalink
Revert "feat(map_based_prediction): use glog (autowarefoundation#5721)"
Browse files Browse the repository at this point in the history
This reverts commit 05e9c89.
  • Loading branch information
zymouse authored and h-ohta committed Jan 5, 2024
1 parent 51cdd5a commit f2137d4
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 9 deletions.
4 changes: 0 additions & 4 deletions perception/map_based_prediction/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,6 @@ autoware_package()

find_package(Eigen3 REQUIRED)

find_package(glog REQUIRED)

include_directories(
SYSTEM
${EIGEN3_INCLUDE_DIR}
Expand All @@ -19,8 +17,6 @@ ament_auto_add_library(map_based_prediction_node SHARED
src/debug.cpp
)

target_link_libraries(map_based_prediction_node glog::glog)

rclcpp_components_register_node(map_based_prediction_node
PLUGIN "map_based_prediction::MapBasedPredictionNode"
EXECUTABLE map_based_prediction
Expand Down
1 change: 0 additions & 1 deletion perception/map_based_prediction/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
<depend>autoware_auto_perception_msgs</depend>
<depend>interpolation</depend>
<depend>lanelet2_extension</depend>
<depend>libgoogle-glog-dev</depend>
<depend>motion_utils</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,6 @@
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

#include <glog/logging.h>

#include <algorithm>
#include <chrono>
#include <cmath>
Expand Down Expand Up @@ -720,8 +718,6 @@ void replaceObjectYawWithLaneletsYaw(
MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options)
: Node("map_based_prediction", node_options), debug_accumulated_time_(0.0)
{
google::InitGoogleLogging("map_based_prediction_node");
google::InstallFailureSignalHandler();
enable_delay_compensation_ = declare_parameter<bool>("enable_delay_compensation");
prediction_time_horizon_ = declare_parameter<double>("prediction_time_horizon");
lateral_control_time_horizon_ =
Expand Down

0 comments on commit f2137d4

Please sign in to comment.