Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(twist2accel): componentize Twist2Accel #7101

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 7 additions & 3 deletions localization/twist2accel/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -4,11 +4,15 @@ project(twist2accel)
find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_executable(twist2accel
src/twist2accel_node.cpp
ament_auto_add_library(${PROJECT_NAME} SHARED
src/twist2accel.cpp
)
ament_target_dependencies(twist2accel)

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

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

private:
rclcpp::Publisher<geometry_msgs::msg::AccelWithCovarianceStamped>::SharedPtr
2 changes: 1 addition & 1 deletion localization/twist2accel/launch/twist2accel.launch.xml
Original file line number Diff line number Diff line change
@@ -4,7 +4,7 @@
<arg name="in_odom" default="in_odom"/>
<arg name="in_twist" default="in_twist"/>
<arg name="out_accel" default="out_accel"/>
<node pkg="twist2accel" exec="twist2accel" name="twist2accel" output="screen">
<node pkg="twist2accel" exec="twist2accel_node" output="both">
<remap from="input/odom" to="$(var in_odom)"/>
<remap from="input/twist" to="$(var in_twist)"/>
<remap from="output/accel" to="$(var out_accel)"/>
1 change: 1 addition & 0 deletions localization/twist2accel/package.xml
Original file line number Diff line number Diff line change
@@ -21,6 +21,7 @@
<depend>geometry_msgs</depend>
<depend>nav_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>signal_processing</depend>
<depend>tf2</depend>
<depend>tier4_debug_msgs</depend>
7 changes: 5 additions & 2 deletions localization/twist2accel/src/twist2accel.cpp
Original file line number Diff line number Diff line change
@@ -24,8 +24,8 @@

using std::placeholders::_1;

Twist2Accel::Twist2Accel(const std::string & node_name, const rclcpp::NodeOptions & node_options)
: rclcpp::Node(node_name, node_options)
Twist2Accel::Twist2Accel(const rclcpp::NodeOptions & node_options)
: rclcpp::Node("twist2accel", node_options)
{
sub_odom_ = create_subscription<nav_msgs::msg::Odometry>(
"input/odom", 1, std::bind(&Twist2Accel::callbackOdometry, this, _1));
@@ -103,3 +103,6 @@ void Twist2Accel::estimateAccel(const geometry_msgs::msg::TwistStamped::SharedPt
pub_accel_->publish(accel_msg);
prev_twist_ptr_ = msg;
}

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(Twist2Accel)
28 changes: 0 additions & 28 deletions localization/twist2accel/src/twist2accel_node.cpp

This file was deleted.

Loading