File tree 3 files changed +15
-6
lines changed
localization/pose_instability_detector
3 files changed +15
-6
lines changed Original file line number Diff line number Diff line change @@ -4,21 +4,26 @@ project(pose_instability_detector)
4
4
find_package (autoware_cmake REQUIRED)
5
5
autoware_package()
6
6
7
- ament_auto_add_executable(pose_instability_detector
8
- src/main.cpp
7
+ ament_auto_add_library(${PROJECT_NAME} SHARED
9
8
src/pose_instability_detector.cpp
10
9
)
11
10
11
+ rclcpp_components_register_node(${PROJECT_NAME}
12
+ PLUGIN "PoseInstabilityDetector"
13
+ EXECUTABLE ${PROJECT_NAME} _node
14
+ EXECUTOR SingleThreadedExecutor
15
+ )
16
+
12
17
if (BUILD_TESTING)
13
18
find_package (ament_cmake_gtest REQUIRED)
14
- ament_auto_add_gtest(test_pose_instability_detector
19
+ ament_auto_add_gtest(test_ ${PROJECT_NAME}
15
20
test /test .cpp
16
21
src/pose_instability_detector.cpp
17
22
)
18
23
endif ()
19
24
20
25
ament_auto_package(
21
26
INSTALL_TO_SHARE
22
- launch
23
- config
27
+ launch
28
+ config
24
29
)
Original file line number Diff line number Diff line change 22
22
<depend >geometry_msgs</depend >
23
23
<depend >nav_msgs</depend >
24
24
<depend >rclcpp</depend >
25
+ <depend >rclcpp_components</depend >
25
26
<depend >tf2</depend >
26
27
<depend >tf2_geometry_msgs</depend >
27
28
<depend >tier4_autoware_utils</depend >
Original file line number Diff line number Diff line change 23
23
#include < string>
24
24
25
25
PoseInstabilityDetector::PoseInstabilityDetector (const rclcpp::NodeOptions & options)
26
- : Node(" pose_instability_detector" , options),
26
+ : rclcpp:: Node(" pose_instability_detector" , options),
27
27
threshold_diff_position_x_(this ->declare_parameter<double >(" threshold_diff_position_x" )),
28
28
threshold_diff_position_y_(this ->declare_parameter<double >(" threshold_diff_position_y" )),
29
29
threshold_diff_position_z_(this ->declare_parameter<double >(" threshold_diff_position_z" )),
@@ -174,3 +174,6 @@ void PoseInstabilityDetector::callback_timer()
174
174
prev_odometry_ = latest_odometry_;
175
175
twist_buffer_.clear ();
176
176
}
177
+
178
+ #include < rclcpp_components/register_node_macro.hpp>
179
+ RCLCPP_COMPONENTS_REGISTER_NODE (PoseInstabilityDetector)
You can’t perform that action at this time.
0 commit comments