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(vehicle_velocity_converter): componentize VehicleVelocityConverter #7116

Merged
Show file tree
Hide file tree
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 sensing/vehicle_velocity_converter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,15 @@ project(vehicle_velocity_converter)
find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_executable(vehicle_velocity_converter
src/vehicle_velocity_converter_node.cpp
ament_auto_add_library(${PROJECT_NAME} SHARED
src/vehicle_velocity_converter.cpp
)
ament_target_dependencies(vehicle_velocity_converter)

rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "VehicleVelocityConverter"
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 @@ -28,7 +28,7 @@
class VehicleVelocityConverter : public rclcpp::Node
{
public:
VehicleVelocityConverter();
explicit VehicleVelocityConverter(const rclcpp::NodeOptions & options);
~VehicleVelocityConverter() = default;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="output_twist_with_covariance" default="twist_with_covariance"/>
<arg name="config_file" default="$(find-pkg-share vehicle_velocity_converter)/config/vehicle_velocity_converter.param.yaml"/>

<node pkg="vehicle_velocity_converter" exec="vehicle_velocity_converter" name="vehicle_velocity_converter_node" output="screen">
<node pkg="vehicle_velocity_converter" exec="vehicle_velocity_converter_node" output="both">
<param from="$(var config_file)"/>
<remap from="velocity_status" to="$(var input_vehicle_velocity_topic)"/>
<remap from="twist_with_covariance" to="$(var output_twist_with_covariance)"/>
Expand Down
1 change: 1 addition & 0 deletions sensing/vehicle_velocity_converter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
<depend>autoware_vehicle_msgs</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,8 @@

#include "vehicle_velocity_converter/vehicle_velocity_converter.hpp"

VehicleVelocityConverter::VehicleVelocityConverter() : Node("vehicle_velocity_converter")
VehicleVelocityConverter::VehicleVelocityConverter(const rclcpp::NodeOptions & options)
: rclcpp::Node("vehicle_velocity_converter", options)
{
// set covariance value for twist with covariance msg
stddev_vx_ = declare_parameter<double>("velocity_stddev_xx");
Expand Down Expand Up @@ -52,3 +53,6 @@ void VehicleVelocityConverter::callbackVelocityReport(

twist_with_covariance_pub_->publish(twist_with_covariance_msg);
}

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(VehicleVelocityConverter)

This file was deleted.

Loading