Skip to content

Commit 161027f

Browse files
committed
feat(twist2accel): componentize Twist2Accel (autowarefoundation#7101)
* remove unusing main func file Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com> * add and mod to use glog Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com> * rm dependencies Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com> * change log output from screen to both Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com> --------- Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com>
1 parent 916e33e commit 161027f

File tree

6 files changed

+15
-35
lines changed

6 files changed

+15
-35
lines changed

localization/twist2accel/CMakeLists.txt

+7-3
Original file line numberDiff line numberDiff line change
@@ -4,11 +4,15 @@ project(twist2accel)
44
find_package(autoware_cmake REQUIRED)
55
autoware_package()
66

7-
ament_auto_add_executable(twist2accel
8-
src/twist2accel_node.cpp
7+
ament_auto_add_library(${PROJECT_NAME} SHARED
98
src/twist2accel.cpp
109
)
11-
ament_target_dependencies(twist2accel)
10+
11+
rclcpp_components_register_node(${PROJECT_NAME}
12+
PLUGIN "Twist2Accel"
13+
EXECUTABLE ${PROJECT_NAME}_node
14+
EXECUTOR SingleThreadedExecutor
15+
)
1216

1317
ament_auto_package(
1418
INSTALL_TO_SHARE

localization/twist2accel/include/twist2accel/twist2accel.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@
4040
class Twist2Accel : public rclcpp::Node
4141
{
4242
public:
43-
Twist2Accel(const std::string & node_name, const rclcpp::NodeOptions & options);
43+
explicit Twist2Accel(const rclcpp::NodeOptions & options);
4444

4545
private:
4646
rclcpp::Publisher<geometry_msgs::msg::AccelWithCovarianceStamped>::SharedPtr

localization/twist2accel/launch/twist2accel.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
<arg name="in_odom" default="in_odom"/>
55
<arg name="in_twist" default="in_twist"/>
66
<arg name="out_accel" default="out_accel"/>
7-
<node pkg="twist2accel" exec="twist2accel" name="twist2accel" output="screen">
7+
<node pkg="twist2accel" exec="twist2accel_node" output="both">
88
<remap from="input/odom" to="$(var in_odom)"/>
99
<remap from="input/twist" to="$(var in_twist)"/>
1010
<remap from="output/accel" to="$(var out_accel)"/>

localization/twist2accel/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
<depend>geometry_msgs</depend>
2222
<depend>nav_msgs</depend>
2323
<depend>rclcpp</depend>
24+
<depend>rclcpp_components</depend>
2425
<depend>signal_processing</depend>
2526
<depend>tf2</depend>
2627
<depend>tier4_debug_msgs</depend>

localization/twist2accel/src/twist2accel.cpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,8 @@
2424

2525
using std::placeholders::_1;
2626

27-
Twist2Accel::Twist2Accel(const std::string & node_name, const rclcpp::NodeOptions & node_options)
28-
: rclcpp::Node(node_name, node_options)
27+
Twist2Accel::Twist2Accel(const rclcpp::NodeOptions & node_options)
28+
: rclcpp::Node("twist2accel", node_options)
2929
{
3030
sub_odom_ = create_subscription<nav_msgs::msg::Odometry>(
3131
"input/odom", 1, std::bind(&Twist2Accel::callbackOdometry, this, _1));
@@ -103,3 +103,6 @@ void Twist2Accel::estimateAccel(const geometry_msgs::msg::TwistStamped::SharedPt
103103
pub_accel_->publish(accel_msg);
104104
prev_twist_ptr_ = msg;
105105
}
106+
107+
#include <rclcpp_components/register_node_macro.hpp>
108+
RCLCPP_COMPONENTS_REGISTER_NODE(Twist2Accel)

localization/twist2accel/src/twist2accel_node.cpp

-28
This file was deleted.

0 commit comments

Comments
 (0)