File tree 5 files changed +16
-6
lines changed
5 files changed +16
-6
lines changed Original file line number Diff line number Diff line change @@ -4,10 +4,16 @@ project(stop_filter)
4
4
find_package (autoware_cmake REQUIRED)
5
5
autoware_package()
6
6
7
- ament_auto_add_executable(stop_filter
8
- src/stop_filter_node.cpp
7
+ ament_auto_add_library(${PROJECT_NAME} SHARED
9
8
src/stop_filter.cpp
10
9
)
10
+
11
+ rclcpp_components_register_node(${PROJECT_NAME}
12
+ PLUGIN "StopFilter"
13
+ EXECUTABLE ${PROJECT_NAME} _node
14
+ EXECUTOR SingleThreadedExecutor
15
+ )
16
+
11
17
ament_target_dependencies(stop_filter)
12
18
13
19
ament_auto_package(
Original file line number Diff line number Diff line change 37
37
class StopFilter : public rclcpp ::Node
38
38
{
39
39
public:
40
- StopFilter (const std::string & node_name, const rclcpp::NodeOptions & options);
40
+ explicit StopFilter (const rclcpp::NodeOptions & options);
41
41
42
42
private:
43
43
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr pub_odom_; // !< @brief odom publisher
Original file line number Diff line number Diff line change 3
3
<arg name =" input_odom_name" default =" ekf_odom" />
4
4
<arg name =" output_odom_name" default =" stop_filter_odom" />
5
5
<arg name =" debug_stop_flag" default =" debug/stop_flag" />
6
- <node pkg =" stop_filter" exec =" stop_filter " name = " stop_filter " output =" screen" >
6
+ <node pkg =" stop_filter" exec =" stop_filter_node " output =" screen" >
7
7
<remap from =" input/odom" to =" $(var input_odom_name)" />
8
8
9
9
<remap from =" output/odom" to =" $(var output_odom_name)" />
Original file line number Diff line number Diff line change 21
21
<depend >geometry_msgs</depend >
22
22
<depend >nav_msgs</depend >
23
23
<depend >rclcpp</depend >
24
+ <depend >rclcpp_components</depend >
24
25
<depend >tf2</depend >
25
26
<depend >tier4_debug_msgs</depend >
26
27
Original file line number Diff line number Diff line change 24
24
25
25
using std::placeholders::_1;
26
26
27
- StopFilter::StopFilter (const std::string & node_name, const rclcpp::NodeOptions & node_options)
28
- : rclcpp::Node(node_name , node_options)
27
+ StopFilter::StopFilter (const rclcpp::NodeOptions & node_options)
28
+ : rclcpp::Node(" stop_filter " , node_options)
29
29
{
30
30
vx_threshold_ = declare_parameter<double >(" vx_threshold" );
31
31
wz_threshold_ = declare_parameter<double >(" wz_threshold" );
@@ -57,3 +57,6 @@ void StopFilter::callbackOdometry(const nav_msgs::msg::Odometry::SharedPtr msg)
57
57
pub_stop_flag_->publish (stop_flag_msg);
58
58
pub_odom_->publish (odom_msg);
59
59
}
60
+
61
+ #include < rclcpp_components/register_node_macro.hpp>
62
+ RCLCPP_COMPONENTS_REGISTER_NODE (StopFilter)
You can’t perform that action at this time.
0 commit comments