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

refactor(vehicle_velocity_converter)!: prefix package and namespace with autoware #8967

Merged
Show file tree
Hide file tree
Changes from 2 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
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Original file line number Diff line number Diff line change
Expand Up @@ -210,7 +210,7 @@ sensing/autoware_radar_threshold_filter/** [email protected] shunsuke.miur
sensing/autoware_radar_tracks_noise_filter/** [email protected] [email protected] [email protected] [email protected]
sensing/cuda_utils/** [email protected] [email protected]
sensing/livox/autoware_livox_tag_filter/** [email protected] [email protected]
sensing/vehicle_velocity_converter/** [email protected]
sensing/autoware_vehicle_velocity_converter/** [email protected]
simulator/autoware_carla_interface/** [email protected] [email protected]
simulator/dummy_perception_publisher/** [email protected]
simulator/fault_injection/** [email protected]
Expand Down
4 changes: 2 additions & 2 deletions launch/tier4_simulator_launch/launch/simulator.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -187,9 +187,9 @@
<push-ros-namespace namespace="sensing"/>
<arg name="input_vehicle_velocity_topic" default="/vehicle/status/velocity_status"/>
<arg name="output_twist_with_covariance" default="/sensing/vehicle_velocity_converter/twist_with_covariance"/>
<arg name="config_file" default="$(find-pkg-share vehicle_velocity_converter)/config/vehicle_velocity_converter.param.yaml"/>
<arg name="config_file" default="$(find-pkg-share autoware_vehicle_velocity_converter)/config/vehicle_velocity_converter.param.yaml"/>

<node pkg="vehicle_velocity_converter" exec="vehicle_velocity_converter_node" output="both">
<node pkg="autoware_vehicle_velocity_converter" exec="autoware_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
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(vehicle_velocity_converter)
project(autoware_vehicle_velocity_converter)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand All @@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
)

rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "VehicleVelocityConverter"
PLUGIN "autoware::vehicle_velocity_converter::VehicleVelocityConverter"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR SingleThreadedExecutor
)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# vehicle_velocity_converter
# autoware_vehicle_velocity_converter

## Purpose

Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<launch>
<arg name="input_vehicle_velocity_topic" default="velocity_status"/>
<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"/>
<arg name="config_file" default="$(find-pkg-share autoware_vehicle_velocity_converter)/config/vehicle_velocity_converter.param.yaml"/>

<node pkg="vehicle_velocity_converter" exec="vehicle_velocity_converter_node" output="both">
<node pkg="autoware_vehicle_velocity_converter" exec="autoware_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
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>vehicle_velocity_converter</name>
<name>autoware_vehicle_velocity_converter</name>
<version>0.0.0</version>
<description>The vehicle_velocity_converter package</description>
<description>The autoware_vehicle_velocity_converter package</description>
<maintainer email="[email protected]">Ryu Yamamoto</maintainer>
<license>Apache License 2.0</license>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "vehicle_velocity_converter/vehicle_velocity_converter.hpp"
#include "vehicle_velocity_converter.hpp"

namespace autoware::vehicle_velocity_converter
{
VehicleVelocityConverter::VehicleVelocityConverter(const rclcpp::NodeOptions & options)
: rclcpp::Node("vehicle_velocity_converter", options)
{
Expand Down Expand Up @@ -53,6 +55,7 @@

twist_with_covariance_pub_->publish(twist_with_covariance_msg);
}
} // namespace autoware::vehicle_velocity_converter

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

Check warning on line 61 in sensing/autoware_vehicle_velocity_converter/src/vehicle_velocity_converter.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/autoware_vehicle_velocity_converter/src/vehicle_velocity_converter.cpp#L61

Added line #L61 was not covered by tests
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef VEHICLE_VELOCITY_CONVERTER__VEHICLE_VELOCITY_CONVERTER_HPP_
#define VEHICLE_VELOCITY_CONVERTER__VEHICLE_VELOCITY_CONVERTER_HPP_
#ifndef VEHICLE_VELOCITY_CONVERTER_HPP_
#define VEHICLE_VELOCITY_CONVERTER_HPP_

#include <rclcpp/rclcpp.hpp>

Expand All @@ -25,6 +25,8 @@
#include <string>
#include <vector>

namespace autoware::vehicle_velocity_converter
{
class VehicleVelocityConverter : public rclcpp::Node
{
public:
Expand All @@ -43,5 +45,6 @@ class VehicleVelocityConverter : public rclcpp::Node
double stddev_wz_;
double speed_scale_factor_;
};
} // namespace autoware::vehicle_velocity_converter

#endif // VEHICLE_VELOCITY_CONVERTER__VEHICLE_VELOCITY_CONVERTER_HPP_
#endif // VEHICLE_VELOCITY_CONVERTER_HPP_
Loading