Skip to content

Commit

Permalink
feat(stop_filter): componentize StopFilter (#7099)
Browse files Browse the repository at this point in the history
* remove unused main func file

Signed-off-by: a-maumau <[email protected]>

* add and mod to use glog

Signed-off-by: a-maumau <[email protected]>

* rm dependencies

Signed-off-by: a-maumau <[email protected]>

* change log output from screen to both

Signed-off-by: a-maumau <[email protected]>

---------

Signed-off-by: a-maumau <[email protected]>
  • Loading branch information
a-maumau authored May 24, 2024
1 parent 4ffa82b commit 8281d7f
Show file tree
Hide file tree
Showing 6 changed files with 15 additions and 35 deletions.
10 changes: 7 additions & 3 deletions localization/stop_filter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,15 @@ project(stop_filter)
find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_executable(stop_filter
src/stop_filter_node.cpp
ament_auto_add_library(${PROJECT_NAME} SHARED
src/stop_filter.cpp
)
ament_target_dependencies(stop_filter)

rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "StopFilter"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR SingleThreadedExecutor
)

ament_auto_package(
INSTALL_TO_SHARE
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
class StopFilter : public rclcpp::Node
{
public:
StopFilter(const std::string & node_name, const rclcpp::NodeOptions & options);
explicit StopFilter(const rclcpp::NodeOptions & options);

private:
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr pub_odom_; //!< @brief odom publisher
Expand Down
2 changes: 1 addition & 1 deletion localization/stop_filter/launch/stop_filter.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="input_odom_name" default="ekf_odom"/>
<arg name="output_odom_name" default="stop_filter_odom"/>
<arg name="debug_stop_flag" default="debug/stop_flag"/>
<node pkg="stop_filter" exec="stop_filter" name="stop_filter" output="screen">
<node pkg="stop_filter" exec="stop_filter_node" output="both">
<remap from="input/odom" to="$(var input_odom_name)"/>

<remap from="output/odom" to="$(var output_odom_name)"/>
Expand Down
1 change: 1 addition & 0 deletions localization/stop_filter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<depend>geometry_msgs</depend>
<depend>nav_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tf2</depend>
<depend>tier4_debug_msgs</depend>

Expand Down
7 changes: 5 additions & 2 deletions localization/stop_filter/src/stop_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@

using std::placeholders::_1;

StopFilter::StopFilter(const std::string & node_name, const rclcpp::NodeOptions & node_options)
: rclcpp::Node(node_name, node_options)
StopFilter::StopFilter(const rclcpp::NodeOptions & node_options)
: rclcpp::Node("stop_filter", node_options)
{
vx_threshold_ = declare_parameter<double>("vx_threshold");
wz_threshold_ = declare_parameter<double>("wz_threshold");
Expand Down Expand Up @@ -57,3 +57,6 @@ void StopFilter::callbackOdometry(const nav_msgs::msg::Odometry::SharedPtr msg)
pub_stop_flag_->publish(stop_flag_msg);
pub_odom_->publish(odom_msg);
}

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(StopFilter)
28 changes: 0 additions & 28 deletions localization/stop_filter/src/stop_filter_node.cpp

This file was deleted.

0 comments on commit 8281d7f

Please sign in to comment.