diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS
index 9c64b64645c6f..b241c8c45bb3e 100644
--- a/.github/CODEOWNERS
+++ b/.github/CODEOWNERS
@@ -248,6 +248,7 @@ vehicle/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.
vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp
vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp
vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp
-vehicle/vehicle_info_util/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
+vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp
+vehicle/autoware_vehicle_info_utils/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
### Copied from .github/CODEOWNERS-manual ###
diff --git a/common/global_parameter_loader/launch/global_params.launch.py b/common/global_parameter_loader/launch/global_params.launch.py
index 06f807aaa4609..8f9092b10fa37 100644
--- a/common/global_parameter_loader/launch/global_params.launch.py
+++ b/common/global_parameter_loader/launch/global_params.launch.py
@@ -33,7 +33,7 @@ def launch_setup(context, *args, **kwargs):
load_vehicle_info = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
- [FindPackageShare("vehicle_info_util"), "/launch/vehicle_info.launch.py"]
+ [FindPackageShare("autoware_vehicle_info_utils"), "/launch/vehicle_info.launch.py"]
),
launch_arguments={
"vehicle_info_param_file": [vehicle_description_pkg, "/config/vehicle_info.param.yaml"]
diff --git a/common/global_parameter_loader/package.xml b/common/global_parameter_loader/package.xml
index 4c2568b9aec98..472ef0c063430 100644
--- a/common/global_parameter_loader/package.xml
+++ b/common/global_parameter_loader/package.xml
@@ -10,7 +10,7 @@
ament_cmake_auto
autoware_cmake
- vehicle_info_util
+ autoware_vehicle_info_utils
ament_lint_auto
autoware_lint_common
diff --git a/common/tier4_localization_rviz_plugin/package.xml b/common/tier4_localization_rviz_plugin/package.xml
index f2482b2d45a3b..1c1c4ad6d8ba1 100644
--- a/common/tier4_localization_rviz_plugin/package.xml
+++ b/common/tier4_localization_rviz_plugin/package.xml
@@ -11,6 +11,7 @@
ament_cmake_auto
autoware_cmake
+ autoware_vehicle_info_utils
geometry_msgs
libqt5-core
libqt5-gui
@@ -20,7 +21,6 @@
rviz_common
rviz_default_plugins
tf2_ros
- vehicle_info_util
ament_lint_auto
autoware_lint_common
diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp
index c4233bd6305e3..cd32df498bfd4 100644
--- a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp
+++ b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp
@@ -172,7 +172,7 @@ void PoseHistoryFootprint::updateFootprint()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared(
- VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
+ VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_THROTTLE(
diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp
index d957054bd479e..44625ad7deb41 100644
--- a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp
+++ b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp
@@ -15,8 +15,8 @@
#ifndef POSE_HISTORY_FOOTPRINT__DISPLAY_HPP_
#define POSE_HISTORY_FOOTPRINT__DISPLAY_HPP_
+#include
#include
-#include
#include
@@ -39,8 +39,8 @@ class BoolProperty;
namespace rviz_plugins
{
-using vehicle_info_util::VehicleInfo;
-using vehicle_info_util::VehicleInfoUtil;
+using autoware::vehicle_info_utils::VehicleInfo;
+using autoware::vehicle_info_utils::VehicleInfoUtils;
class PoseHistoryFootprint
: public rviz_common::MessageFilterDisplay
diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp
index ed79e122c0a01..9cb710c239029 100644
--- a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp
+++ b/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp
@@ -15,6 +15,7 @@
#ifndef TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_
#define TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_
+#include
#include
#include
#include
@@ -25,7 +26,6 @@
#include
#include
#include
-#include
#include
@@ -97,8 +97,8 @@ bool validateFloats(const typename T::ConstSharedPtr & msg_ptr)
namespace rviz_plugins
{
-using vehicle_info_util::VehicleInfo;
-using vehicle_info_util::VehicleInfoUtil;
+using autoware::vehicle_info_utils::VehicleInfo;
+using autoware::vehicle_info_utils::VehicleInfoUtils;
template
class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay
{
diff --git a/common/tier4_planning_rviz_plugin/package.xml b/common/tier4_planning_rviz_plugin/package.xml
index 5d755d212c859..95edcb7a96c56 100644
--- a/common/tier4_planning_rviz_plugin/package.xml
+++ b/common/tier4_planning_rviz_plugin/package.xml
@@ -12,6 +12,7 @@
autoware_cmake
autoware_planning_msgs
+ autoware_vehicle_info_utils
libqt5-core
libqt5-gui
libqt5-widgets
@@ -25,7 +26,6 @@
tf2_ros
tier4_autoware_utils
tier4_planning_msgs
- vehicle_info_util
ament_lint_auto
autoware_lint_common
diff --git a/common/tier4_planning_rviz_plugin/src/path/display.cpp b/common/tier4_planning_rviz_plugin/src/path/display.cpp
index 4a297b47bcfcc..342e72d66c5f9 100644
--- a/common/tier4_planning_rviz_plugin/src/path/display.cpp
+++ b/common/tier4_planning_rviz_plugin/src/path/display.cpp
@@ -31,7 +31,7 @@ void AutowarePathWithLaneIdDisplay::preProcessMessageDetail()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared(
- VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
+ VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_ONCE(
@@ -107,7 +107,7 @@ void AutowarePathDisplay::preProcessMessageDetail()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared(
- VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
+ VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_ONCE(
@@ -124,7 +124,7 @@ void AutowareTrajectoryDisplay::preProcessMessageDetail()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared(
- VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
+ VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_ONCE(
diff --git a/control/autoware_autonomous_emergency_braking/include/autoware_autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware_autonomous_emergency_braking/node.hpp
index b87f421de7c8c..3e72d72cb9946 100644
--- a/control/autoware_autonomous_emergency_braking/include/autoware_autonomous_emergency_braking/node.hpp
+++ b/control/autoware_autonomous_emergency_braking/include/autoware_autonomous_emergency_braking/node.hpp
@@ -15,13 +15,13 @@
#ifndef AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_
#define AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_
+#include
#include
#include
#include
#include
#include
#include
-#include
#include
#include
@@ -59,11 +59,11 @@ using nav_msgs::msg::Odometry;
using sensor_msgs::msg::Imu;
using sensor_msgs::msg::PointCloud2;
using PointCloud = pcl::PointCloud;
+using autoware::vehicle_info_utils::VehicleInfo;
using diagnostic_updater::DiagnosticStatusWrapper;
using diagnostic_updater::Updater;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;
-using vehicle_info_util::VehicleInfo;
using visualization_msgs::msg::Marker;
using visualization_msgs::msg::MarkerArray;
using Path = std::vector;
diff --git a/control/autoware_autonomous_emergency_braking/package.xml b/control/autoware_autonomous_emergency_braking/package.xml
index 221fc2c000826..0404eec7ca308 100644
--- a/control/autoware_autonomous_emergency_braking/package.xml
+++ b/control/autoware_autonomous_emergency_braking/package.xml
@@ -17,6 +17,7 @@
autoware_control_msgs
autoware_planning_msgs
autoware_system_msgs
+ autoware_vehicle_info_utils
autoware_vehicle_msgs
diagnostic_updater
geometry_msgs
@@ -34,7 +35,6 @@
tf2_geometry_msgs
tf2_ros
tier4_autoware_utils
- vehicle_info_util
visualization_msgs
ament_lint_auto
diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp
index 3ec8cc68df9b1..d01855bc8ab5d 100644
--- a/control/autoware_autonomous_emergency_braking/src/node.cpp
+++ b/control/autoware_autonomous_emergency_braking/src/node.cpp
@@ -60,7 +60,7 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point &
Polygon2d createPolygon(
const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & next_pose,
- const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double expand_width)
{
Polygon2d polygon;
@@ -102,7 +102,7 @@ Polygon2d createPolygon(
AEB::AEB(const rclcpp::NodeOptions & node_options)
: Node("AEB", node_options),
- vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()),
+ vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo()),
collision_data_keeper_(this->get_clock())
{
// Publisher
diff --git a/control/autoware_mpc_lateral_controller/package.xml b/control/autoware_mpc_lateral_controller/package.xml
index 3e62d69f6ebb6..673d9d7896745 100644
--- a/control/autoware_mpc_lateral_controller/package.xml
+++ b/control/autoware_mpc_lateral_controller/package.xml
@@ -19,6 +19,7 @@
autoware_control_msgs
autoware_planning_msgs
+ autoware_vehicle_info_utils
autoware_vehicle_msgs
diagnostic_msgs
diagnostic_updater
@@ -35,7 +36,6 @@
tier4_autoware_utils
tier4_debug_msgs
trajectory_follower_base
- vehicle_info_util
ament_cmake_ros
ament_lint_auto
diff --git a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp
index 3d66078eed1f2..cf8a4ed5a251b 100644
--- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp
+++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp
@@ -19,10 +19,10 @@
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp"
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp"
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp"
+#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "tf2/utils.h"
#include "tf2_ros/create_timer_ros.h"
-#include "vehicle_info_util/vehicle_info_util.hpp"
#include
#include
@@ -69,7 +69,7 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node)
m_mpc_converged_threshold_rps = dp_double("mpc_converged_threshold_rps"); // [rad/s]
/* mpc parameters */
- const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
+ const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();
const double wheelbase = vehicle_info.wheel_base_m;
constexpr double deg2rad = static_cast(M_PI) / 180.0;
m_mpc->m_steer_lim = vehicle_info.max_steer_angle_rad;
diff --git a/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid_longitudinal_controller.hpp
index 7b9d999a3decb..08a6a51d3098b 100644
--- a/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid_longitudinal_controller.hpp
+++ b/control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid_longitudinal_controller.hpp
@@ -20,6 +20,7 @@
#include "autoware_pid_longitudinal_controller/lowpass_filter.hpp"
#include "autoware_pid_longitudinal_controller/pid.hpp"
#include "autoware_pid_longitudinal_controller/smooth_stop.hpp"
+#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "diagnostic_updater/diagnostic_updater.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"
@@ -27,7 +28,6 @@
#include "tf2_ros/transform_listener.h"
#include "tier4_autoware_utils/ros/marker_helper.hpp"
#include "trajectory_follower_base/longitudinal_controller_base.hpp"
-#include "vehicle_info_util/vehicle_info_util.hpp"
#include
#include
diff --git a/control/autoware_pid_longitudinal_controller/package.xml b/control/autoware_pid_longitudinal_controller/package.xml
index 50ae7ccaf2e55..66f6a6dfcda8b 100644
--- a/control/autoware_pid_longitudinal_controller/package.xml
+++ b/control/autoware_pid_longitudinal_controller/package.xml
@@ -21,6 +21,7 @@
autoware_adapi_v1_msgs
autoware_control_msgs
autoware_planning_msgs
+ autoware_vehicle_info_utils
autoware_vehicle_msgs
diagnostic_msgs
diagnostic_updater
@@ -36,7 +37,6 @@
tier4_autoware_utils
tier4_debug_msgs
trajectory_follower_base
- vehicle_info_util
ament_cmake_ros
ament_lint_auto
diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp
index e1dd414b2446d..4cca525f6ebf3 100644
--- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp
+++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp
@@ -38,9 +38,11 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node)
// parameters timer
m_longitudinal_ctrl_period = node.get_parameter("ctrl_period").as_double();
- m_wheel_base = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo().wheel_base_m;
- m_vehicle_width = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo().vehicle_width_m;
- m_front_overhang = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo().front_overhang_m;
+ m_wheel_base = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo().wheel_base_m;
+ m_vehicle_width =
+ autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo().vehicle_width_m;
+ m_front_overhang =
+ autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo().front_overhang_m;
// parameters for delay compensation
m_delay_compensation_time = node.declare_parameter("delay_compensation_time"); // [s]
diff --git a/control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml b/control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml
index c9e83bf9878b8..c9df4e67c2647 100644
--- a/control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml
+++ b/control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml
@@ -3,7 +3,7 @@
-
+
diff --git a/control/autoware_vehicle_cmd_gate/package.xml b/control/autoware_vehicle_cmd_gate/package.xml
index da0e885cc564a..f67d01a5593ae 100644
--- a/control/autoware_vehicle_cmd_gate/package.xml
+++ b/control/autoware_vehicle_cmd_gate/package.xml
@@ -17,6 +17,7 @@
autoware_adapi_v1_msgs
autoware_control_msgs
+ autoware_vehicle_info_utils
autoware_vehicle_msgs
component_interface_specs
component_interface_utils
@@ -33,7 +34,6 @@
tier4_external_api_msgs
tier4_system_msgs
tier4_vehicle_msgs
- vehicle_info_util
visualization_msgs
rosidl_default_runtime
diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp
index e8d35beb94b1f..bb50dcb586e83 100644
--- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp
+++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp
@@ -170,7 +170,7 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
declare_parameter("filter_activated_velocity_threshold");
// Vehicle Parameter
- const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
+ const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo();
{
VehicleCmdFilterParam p;
p.wheel_base = vehicle_info.wheel_base_m;
@@ -276,7 +276,7 @@ rcl_interfaces::msg::SetParametersResult VehicleCmdGate::onParameter(
parameters, "filter_activated_velocity_threshold", filter_activated_velocity_threshold_);
// Vehicle Parameter
- const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
+ const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo();
{
VehicleCmdFilterParam p = filter_.getParam();
p.wheel_base = vehicle_info.wheel_base_m;
diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp
index 22613de5d1f07..06dad536d842d 100644
--- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp
+++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp
@@ -21,11 +21,11 @@
#include "vehicle_cmd_filter.hpp"
#include
+#include
#include
#include
#include
#include
-#include
#include
#include
diff --git a/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp b/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp
index 6f148fe6c8140..46130fc8f9941 100644
--- a/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp
+++ b/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp
@@ -371,7 +371,7 @@ std::shared_ptr generateNode()
const auto vehicle_cmd_gate_dir =
ament_index_cpp::get_package_share_directory("autoware_vehicle_cmd_gate");
const auto vehicle_info_util_dir =
- ament_index_cpp::get_package_share_directory("vehicle_info_util");
+ ament_index_cpp::get_package_share_directory("autoware_vehicle_info_utils");
node_options.arguments(
{"--ros-args", "--params-file", vehicle_cmd_gate_dir + "/config/vehicle_cmd_gate.param.yaml",
diff --git a/control/control_performance_analysis/launch/control_performance_analysis.launch.xml b/control/control_performance_analysis/launch/control_performance_analysis.launch.xml
index be2b30bdf1bf9..f2997f0e10b83 100644
--- a/control/control_performance_analysis/launch/control_performance_analysis.launch.xml
+++ b/control/control_performance_analysis/launch/control_performance_analysis.launch.xml
@@ -8,7 +8,7 @@
-
+
diff --git a/control/control_performance_analysis/package.xml b/control/control_performance_analysis/package.xml
index a26f4164a177b..b18fb8c98ccdc 100644
--- a/control/control_performance_analysis/package.xml
+++ b/control/control_performance_analysis/package.xml
@@ -26,6 +26,7 @@
autoware_control_msgs
autoware_planning_msgs
+ autoware_vehicle_info_utils
autoware_vehicle_msgs
geometry_msgs
libboost-dev
@@ -41,7 +42,6 @@
tf2_ros
tier4_autoware_utils
tier4_debug_msgs
- vehicle_info_util
builtin_interfaces
global_parameter_loader
rosidl_default_runtime
diff --git a/control/control_performance_analysis/src/control_performance_analysis_node.cpp b/control/control_performance_analysis/src/control_performance_analysis_node.cpp
index 693194e8b70a6..47ce3ce07e83c 100644
--- a/control/control_performance_analysis/src/control_performance_analysis_node.cpp
+++ b/control/control_performance_analysis/src/control_performance_analysis_node.cpp
@@ -17,7 +17,7 @@
#include "control_performance_analysis/msg/driving_monitor_stamped.hpp"
#include "control_performance_analysis/msg/error_stamped.hpp"
-#include
+#include
#include
#include
@@ -32,7 +32,7 @@ using control_performance_analysis::msg::ErrorStamped;
namespace control_performance_analysis
{
-using vehicle_info_util::VehicleInfoUtil;
+using autoware::vehicle_info_utils::VehicleInfoUtils;
ControlPerformanceAnalysisNode::ControlPerformanceAnalysisNode(
const rclcpp::NodeOptions & node_options)
@@ -41,7 +41,7 @@ ControlPerformanceAnalysisNode::ControlPerformanceAnalysisNode(
using std::placeholders::_1;
// Implement Reading Global and Local Variables.
- const auto & vehicle_info = VehicleInfoUtil(*this).getVehicleInfo();
+ const auto & vehicle_info = VehicleInfoUtils(*this).getVehicleInfo();
param_.wheelbase_ = vehicle_info.wheel_base_m;
// Node Parameters.
diff --git a/control/control_validator/include/control_validator/control_validator.hpp b/control/control_validator/include/control_validator/control_validator.hpp
index e048ef03bf11a..56125cc40b74e 100644
--- a/control/control_validator/include/control_validator/control_validator.hpp
+++ b/control/control_validator/include/control_validator/control_validator.hpp
@@ -15,9 +15,9 @@
#ifndef CONTROL_VALIDATOR__CONTROL_VALIDATOR_HPP_
#define CONTROL_VALIDATOR__CONTROL_VALIDATOR_HPP_
+#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "control_validator/debug_marker.hpp"
#include "control_validator/msg/control_validator_status.hpp"
-#include "vehicle_info_util/vehicle_info_util.hpp"
#include
#include
@@ -83,7 +83,7 @@ class ControlValidator : public rclcpp::Node
ControlValidatorStatus validation_status_;
ValidationParams validation_params_; // for thresholds
- vehicle_info_util::VehicleInfo vehicle_info_;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
bool isAllValid(const ControlValidatorStatus & status);
diff --git a/control/control_validator/package.xml b/control/control_validator/package.xml
index 2f4400d6ebc57..93779d28d6218 100644
--- a/control/control_validator/package.xml
+++ b/control/control_validator/package.xml
@@ -21,6 +21,7 @@
rosidl_default_generators
autoware_planning_msgs
+ autoware_vehicle_info_utils
diagnostic_updater
geometry_msgs
motion_utils
@@ -28,7 +29,6 @@
rclcpp
rclcpp_components
tier4_autoware_utils
- vehicle_info_util
visualization_msgs
ament_cmake_ros
diff --git a/control/control_validator/src/control_validator.cpp b/control/control_validator/src/control_validator.cpp
index 5282e31fef898..be103647f1b36 100644
--- a/control/control_validator/src/control_validator.cpp
+++ b/control/control_validator/src/control_validator.cpp
@@ -61,7 +61,7 @@ void ControlValidator::setupParameters()
}
try {
- vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
+ vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo();
} catch (...) {
RCLCPP_ERROR(get_logger(), "failed to get vehicle info. use default value.");
vehicle_info_.front_overhang_m = 0.5;
diff --git a/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp
index d90dbc9474fd8..e29623bf69891 100644
--- a/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp
+++ b/control/lane_departure_checker/include/autoware_lane_departure_checker/lane_departure_checker.hpp
@@ -15,10 +15,10 @@
#ifndef AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_
#define AUTOWARE_LANE_DEPARTURE_CHECKER__LANE_DEPARTURE_CHECKER_HPP_
+#include
#include
#include
#include
-#include
#include
#include
@@ -103,17 +103,17 @@ class LaneDepartureChecker
public:
Output update(const Input & input);
- void setParam(const Param & param, const vehicle_info_util::VehicleInfo vehicle_info)
+ void setParam(const Param & param, const autoware::vehicle_info_utils::VehicleInfo vehicle_info)
{
param_ = param;
- vehicle_info_ptr_ = std::make_shared(vehicle_info);
+ vehicle_info_ptr_ = std::make_shared(vehicle_info);
}
void setParam(const Param & param) { param_ = param; }
- void setVehicleInfo(const vehicle_info_util::VehicleInfo vehicle_info)
+ void setVehicleInfo(const autoware::vehicle_info_utils::VehicleInfo vehicle_info)
{
- vehicle_info_ptr_ = std::make_shared(vehicle_info);
+ vehicle_info_ptr_ = std::make_shared(vehicle_info);
}
bool checkPathWillLeaveLane(
@@ -137,7 +137,7 @@ class LaneDepartureChecker
private:
Param param_;
- std::shared_ptr vehicle_info_ptr_;
+ std::shared_ptr vehicle_info_ptr_;
static PoseDeviation calcTrajectoryDeviation(
const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose,
diff --git a/control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp b/control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp
index 917317361d702..c85e37212b16f 100644
--- a/control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp
+++ b/control/lane_departure_checker/include/autoware_lane_departure_checker/util/create_vehicle_footprint.hpp
@@ -29,8 +29,8 @@
#define AUTOWARE_LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_
#include
+#include
#include
-#include
#include
diff --git a/control/lane_departure_checker/launch/lane_departure_checker.launch.xml b/control/lane_departure_checker/launch/lane_departure_checker.launch.xml
index 7ea2e8b2de60a..b9f820f66690b 100644
--- a/control/lane_departure_checker/launch/lane_departure_checker.launch.xml
+++ b/control/lane_departure_checker/launch/lane_departure_checker.launch.xml
@@ -7,7 +7,7 @@
-
+
diff --git a/control/lane_departure_checker/package.xml b/control/lane_departure_checker/package.xml
index 466dc7351cd9e..7a08cd2907120 100644
--- a/control/lane_departure_checker/package.xml
+++ b/control/lane_departure_checker/package.xml
@@ -15,6 +15,7 @@
autoware_map_msgs
autoware_planning_msgs
+ autoware_vehicle_info_utils
boost
diagnostic_updater
eigen
@@ -30,7 +31,6 @@
tf2_ros
tier4_autoware_utils
tier4_debug_msgs
- vehicle_info_util
ament_lint_auto
autoware_lint_common
diff --git a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp
index 7956410fdf898..b25b3fd843f4b 100644
--- a/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp
+++ b/control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp
@@ -145,7 +145,7 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o
declare_parameter>("boundary_types_to_detect");
// Vehicle Info
- const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
+ const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo();
vehicle_length_m_ = vehicle_info.vehicle_length_m;
// Core Parameter
diff --git a/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker.hpp b/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker.hpp
index a65d818056bd7..efaefd765e793 100644
--- a/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker.hpp
+++ b/control/obstacle_collision_checker/include/obstacle_collision_checker/obstacle_collision_checker.hpp
@@ -15,8 +15,8 @@
#ifndef OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_
#define OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_
+#include
#include
-#include
#include
#include
@@ -75,7 +75,7 @@ class ObstacleCollisionChecker
private:
Param param_;
- vehicle_info_util::VehicleInfo vehicle_info_;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
//! This function assumes the input trajectory is sampled dense enough
static autoware_planning_msgs::msg::Trajectory resampleTrajectory(
@@ -86,7 +86,7 @@ class ObstacleCollisionChecker
static std::vector createVehicleFootprints(
const autoware_planning_msgs::msg::Trajectory & trajectory, const Param & param,
- const vehicle_info_util::VehicleInfo & vehicle_info);
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info);
static std::vector createVehiclePassingAreas(
const std::vector & vehicle_footprints);
diff --git a/control/obstacle_collision_checker/launch/obstacle_collision_checker.launch.xml b/control/obstacle_collision_checker/launch/obstacle_collision_checker.launch.xml
index 078993d064064..f82384534e040 100755
--- a/control/obstacle_collision_checker/launch/obstacle_collision_checker.launch.xml
+++ b/control/obstacle_collision_checker/launch/obstacle_collision_checker.launch.xml
@@ -6,7 +6,7 @@
-
+
diff --git a/control/obstacle_collision_checker/package.xml b/control/obstacle_collision_checker/package.xml
index ef7560755a122..795302abe75f4 100644
--- a/control/obstacle_collision_checker/package.xml
+++ b/control/obstacle_collision_checker/package.xml
@@ -19,6 +19,7 @@
autoware_cmake
autoware_planning_msgs
+ autoware_vehicle_info_utils
boost
diagnostic_updater
eigen
@@ -33,7 +34,6 @@
tf2_geometry_msgs
tf2_ros
tier4_autoware_utils
- vehicle_info_util
ament_cmake_ros
ament_lint_auto
diff --git a/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker.cpp b/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker.cpp
index 6887be4cedd77..a844fe6a50cbf 100644
--- a/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker.cpp
+++ b/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker.cpp
@@ -83,7 +83,7 @@ double calcBrakingDistance(
namespace obstacle_collision_checker
{
ObstacleCollisionChecker::ObstacleCollisionChecker(rclcpp::Node & node)
-: vehicle_info_(vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo())
+: vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo())
{
}
@@ -188,7 +188,7 @@ autoware_planning_msgs::msg::Trajectory ObstacleCollisionChecker::cutTrajectory(
std::vector ObstacleCollisionChecker::createVehicleFootprints(
const autoware_planning_msgs::msg::Trajectory & trajectory, const Param & param,
- const vehicle_info_util::VehicleInfo & vehicle_info)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info)
{
// Create vehicle footprint in base_link coordinate
const auto local_vehicle_footprint = vehicle_info.createFootprint(param.footprint_margin);
diff --git a/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker_node.cpp b/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker_node.cpp
index cfde4ee849728..402123c81d361 100644
--- a/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker_node.cpp
+++ b/control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker_node.cpp
@@ -14,10 +14,10 @@
#include "obstacle_collision_checker/obstacle_collision_checker_node.hpp"
+#include
#include
#include
#include
-#include
#include
#include
diff --git a/control/operation_mode_transition_manager/launch/operation_mode_transition_manager.launch.xml b/control/operation_mode_transition_manager/launch/operation_mode_transition_manager.launch.xml
index 569d743ba2c4f..c6f03db0fcacc 100644
--- a/control/operation_mode_transition_manager/launch/operation_mode_transition_manager.launch.xml
+++ b/control/operation_mode_transition_manager/launch/operation_mode_transition_manager.launch.xml
@@ -1,6 +1,6 @@
-
+
diff --git a/control/operation_mode_transition_manager/package.xml b/control/operation_mode_transition_manager/package.xml
index 81517675281c3..40232469fdb6a 100644
--- a/control/operation_mode_transition_manager/package.xml
+++ b/control/operation_mode_transition_manager/package.xml
@@ -13,6 +13,7 @@
rosidl_default_generators
autoware_control_msgs
+ autoware_vehicle_info_utils
autoware_vehicle_msgs
component_interface_specs
component_interface_utils
@@ -25,7 +26,6 @@
tier4_control_msgs
tier4_system_msgs
tier4_vehicle_msgs
- vehicle_info_util
ament_cmake_gtest
ament_lint_auto
diff --git a/control/operation_mode_transition_manager/src/state.cpp b/control/operation_mode_transition_manager/src/state.cpp
index 635ead2430677..82270875b2e17 100644
--- a/control/operation_mode_transition_manager/src/state.cpp
+++ b/control/operation_mode_transition_manager/src/state.cpp
@@ -33,7 +33,7 @@ using tier4_autoware_utils::calcYawDeviation;
AutonomousMode::AutonomousMode(rclcpp::Node * node)
: logger_(node->get_logger()), clock_(node->get_clock())
{
- vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*node).getVehicleInfo();
+ vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo();
sub_control_cmd_ = node->create_subscription(
"control_cmd", 1, [this](const Control::SharedPtr msg) { control_cmd_ = *msg; });
diff --git a/control/operation_mode_transition_manager/src/state.hpp b/control/operation_mode_transition_manager/src/state.hpp
index e5abd4285ad5f..54434690f2147 100644
--- a/control/operation_mode_transition_manager/src/state.hpp
+++ b/control/operation_mode_transition_manager/src/state.hpp
@@ -18,8 +18,8 @@
#include "data.hpp"
#include "operation_mode_transition_manager/msg/operation_mode_transition_manager_debug.hpp"
+#include
#include
-#include
#include
#include
@@ -83,7 +83,7 @@ class AutonomousMode : public ModeChangeBase
Control trajectory_follower_control_cmd_;
Odometry kinematics_;
Trajectory trajectory_;
- vehicle_info_util::VehicleInfo vehicle_info_;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
DebugInfo debug_info_;
std::shared_ptr stable_start_time_; // Reset every transition start.
diff --git a/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp b/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp
index 8410e7c78f723..2a7a552c1973d 100644
--- a/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp
+++ b/control/predicted_path_checker/include/predicted_path_checker/collision_checker.hpp
@@ -15,6 +15,7 @@
#ifndef PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_
#define PREDICTED_PATH_CHECKER__COLLISION_CHECKER_HPP_
+#include
#include
#include
#include
@@ -23,7 +24,6 @@
#include
#include
#include
-#include
#include
#include
@@ -120,7 +120,7 @@ class CollisionChecker
// Variables
std::shared_ptr debug_ptr_;
rclcpp::Node * node_;
- vehicle_info_util::VehicleInfo vehicle_info_;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
std::vector predicted_object_history_{};
};
} // namespace autoware::motion::control::predicted_path_checker
diff --git a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp
index 23696887c7051..6c4832a0dac3e 100644
--- a/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp
+++ b/control/predicted_path_checker/include/predicted_path_checker/predicted_path_checker_node.hpp
@@ -15,6 +15,8 @@
#ifndef PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_
#define PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_
+#include
+#include
#include
#include
#include
@@ -24,8 +26,6 @@
#include
#include
#include
-#include
-#include
#include
#include
@@ -116,7 +116,7 @@ class PredictedPathCheckerNode : public rclcpp::Node
// Variables
State current_state_{State::DRIVE};
- vehicle_info_util::VehicleInfo vehicle_info_;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
bool is_calling_set_stop_{false};
bool is_stopped_by_node_{false};
diff --git a/control/predicted_path_checker/include/predicted_path_checker/utils.hpp b/control/predicted_path_checker/include/predicted_path_checker/utils.hpp
index 957800ad04305..d9299f09dfb6b 100644
--- a/control/predicted_path_checker/include/predicted_path_checker/utils.hpp
+++ b/control/predicted_path_checker/include/predicted_path_checker/utils.hpp
@@ -15,10 +15,10 @@
#ifndef PREDICTED_PATH_CHECKER__UTILS_HPP_
#define PREDICTED_PATH_CHECKER__UTILS_HPP_
+#include
#include
#include
#include
-#include
#include
#include
@@ -39,6 +39,7 @@
namespace utils
{
+using autoware::vehicle_info_utils::VehicleInfo;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_planning_msgs::msg::TrajectoryPoint;
@@ -48,7 +49,6 @@ using geometry_msgs::msg::TransformStamped;
using std_msgs::msg::Header;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;
-using vehicle_info_util::VehicleInfo;
using PointArray = std::vector;
using TrajectoryPoints = std::vector;
@@ -57,7 +57,7 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point &
Polygon2d createOneStepPolygon(
const geometry_msgs::msg::Pose & base_step_pose, const geometry_msgs::msg::Pose & next_step_pose,
- const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width);
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double expand_width);
TrajectoryPoint calcInterpolatedPoint(
const TrajectoryPoints & trajectory, const geometry_msgs::msg::Point & target_point,
@@ -65,7 +65,7 @@ TrajectoryPoint calcInterpolatedPoint(
std::pair findStopPoint(
TrajectoryPoints & predicted_trajectory_array, const size_t collision_idx,
- const double stop_margin, vehicle_info_util::VehicleInfo & vehicle_info);
+ const double stop_margin, autoware::vehicle_info_utils::VehicleInfo & vehicle_info);
bool isInBrakeDistance(
const TrajectoryPoints & trajectory, const size_t stop_idx, const double relative_velocity,
diff --git a/control/predicted_path_checker/launch/predicted_path_checker.launch.xml b/control/predicted_path_checker/launch/predicted_path_checker.launch.xml
index a35c11b80c1f7..6af1372a5bb4a 100755
--- a/control/predicted_path_checker/launch/predicted_path_checker.launch.xml
+++ b/control/predicted_path_checker/launch/predicted_path_checker.launch.xml
@@ -7,7 +7,7 @@
-
+
diff --git a/control/predicted_path_checker/package.xml b/control/predicted_path_checker/package.xml
index bca65302dba55..911344c578414 100644
--- a/control/predicted_path_checker/package.xml
+++ b/control/predicted_path_checker/package.xml
@@ -14,6 +14,7 @@
autoware_perception_msgs
autoware_planning_msgs
+ autoware_vehicle_info_utils
boost
component_interface_specs
component_interface_utils
@@ -34,7 +35,6 @@
tier4_control_msgs
tier4_external_api_msgs
tier4_planning_msgs
- vehicle_info_util
ament_cmake_ros
ament_lint_auto
diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp
index 5e8d96805b832..7d392571546b4 100644
--- a/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp
+++ b/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp
@@ -27,7 +27,7 @@ CollisionChecker::CollisionChecker(
rclcpp::Node * node, std::shared_ptr debug_ptr)
: debug_ptr_(std::move(debug_ptr)),
node_(node),
- vehicle_info_(vehicle_info_util::VehicleInfoUtil(*node).getVehicleInfo())
+ vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*node).getVehicleInfo())
{
}
diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp
index 28ea21f639a0e..38717a1849ad9 100644
--- a/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp
+++ b/control/predicted_path_checker/src/predicted_path_checker_node/predicted_path_checker_node.cpp
@@ -38,7 +38,7 @@ PredictedPathCheckerNode::PredictedPathCheckerNode(const rclcpp::NodeOptions & n
group_cli_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
adaptor.init_cli(cli_set_stop_, group_cli_);
adaptor.init_sub(sub_stop_state_, this, &PredictedPathCheckerNode::onIsStopped);
- vehicle_info_ = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
+ vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo();
// Node Parameter
node_param_.update_rate = declare_parameter("update_rate", 10.0);
diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp
index f1c76ce6eef8f..a9c3e2b24f9a5 100644
--- a/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp
+++ b/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp
@@ -29,7 +29,7 @@ using tier4_autoware_utils::getRPY;
// Utils Functions
Polygon2d createOneStepPolygon(
const geometry_msgs::msg::Pose & base_step_pose, const geometry_msgs::msg::Pose & next_step_pose,
- const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double expand_width)
{
Polygon2d polygon;
@@ -146,7 +146,7 @@ TrajectoryPoint calcInterpolatedPoint(
std::pair findStopPoint(
TrajectoryPoints & trajectory_array, const size_t collision_idx, const double stop_margin,
- vehicle_info_util::VehicleInfo & vehicle_info)
+ autoware::vehicle_info_utils::VehicleInfo & vehicle_info)
{
// It returns the stop point and segment of the point on trajectory.
diff --git a/control/pure_pursuit/package.xml b/control/pure_pursuit/package.xml
index 0747766af54c8..32744d744f95f 100644
--- a/control/pure_pursuit/package.xml
+++ b/control/pure_pursuit/package.xml
@@ -16,6 +16,7 @@
autoware_control_msgs
autoware_planning_msgs
+ autoware_vehicle_info_utils
boost
geometry_msgs
libboost-dev
@@ -32,7 +33,6 @@
tier4_autoware_utils
tier4_debug_msgs
trajectory_follower_base
- vehicle_info_util
visualization_msgs
ament_lint_auto
diff --git a/control/pure_pursuit/src/pure_pursuit/pure_pursuit_lateral_controller.cpp b/control/pure_pursuit/src/pure_pursuit/pure_pursuit_lateral_controller.cpp
index a8232cce5d08d..eddcdb5e362df 100644
--- a/control/pure_pursuit/src/pure_pursuit/pure_pursuit_lateral_controller.cpp
+++ b/control/pure_pursuit/src/pure_pursuit/pure_pursuit_lateral_controller.cpp
@@ -34,7 +34,7 @@
#include "pure_pursuit/util/planning_utils.hpp"
#include "pure_pursuit/util/tf_utils.hpp"
-#include
+#include
#include
#include
@@ -65,7 +65,7 @@ PurePursuitLateralController::PurePursuitLateralController(rclcpp::Node & node)
pure_pursuit_ = std::make_unique();
// Vehicle Parameters
- const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
+ const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();
param_.wheel_base = vehicle_info.wheel_base_m;
param_.max_steering_angle = vehicle_info.max_steer_angle_rad;
diff --git a/control/pure_pursuit/src/pure_pursuit/pure_pursuit_node.cpp b/control/pure_pursuit/src/pure_pursuit/pure_pursuit_node.cpp
index a4b491930df1e..d629c8f549f52 100644
--- a/control/pure_pursuit/src/pure_pursuit/pure_pursuit_node.cpp
+++ b/control/pure_pursuit/src/pure_pursuit/pure_pursuit_node.cpp
@@ -34,7 +34,7 @@
#include "pure_pursuit/util/planning_utils.hpp"
#include "pure_pursuit/util/tf_utils.hpp"
-#include
+#include
#include
#include
@@ -59,7 +59,7 @@ PurePursuitNode::PurePursuitNode(const rclcpp::NodeOptions & node_options)
pure_pursuit_ = std::make_unique();
// Vehicle Parameters
- const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
+ const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo();
param_.wheel_base = vehicle_info.wheel_base_m;
// Node Parameters
diff --git a/control/trajectory_follower_base/package.xml b/control/trajectory_follower_base/package.xml
index 6f2e9c3e8ebc2..b36b4669be04e 100644
--- a/control/trajectory_follower_base/package.xml
+++ b/control/trajectory_follower_base/package.xml
@@ -22,6 +22,7 @@
autoware_adapi_v1_msgs
autoware_control_msgs
autoware_planning_msgs
+ autoware_vehicle_info_utils
autoware_vehicle_msgs
diagnostic_msgs
diagnostic_updater
@@ -37,7 +38,6 @@
tf2_ros
tier4_autoware_utils
tier4_debug_msgs
- vehicle_info_util
ament_cmake_ros
ament_lint_auto
diff --git a/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp b/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp
index 8e9752ba19f66..b342aace69bde 100644
--- a/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp
+++ b/control/trajectory_follower_node/include/trajectory_follower_node/controller_node.hpp
@@ -15,6 +15,7 @@
#ifndef TRAJECTORY_FOLLOWER_NODE__CONTROLLER_NODE_HPP_
#define TRAJECTORY_FOLLOWER_NODE__CONTROLLER_NODE_HPP_
+#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"
#include "tf2_ros/buffer.h"
@@ -24,7 +25,6 @@
#include "trajectory_follower_base/lateral_controller_base.hpp"
#include "trajectory_follower_base/longitudinal_controller_base.hpp"
#include "trajectory_follower_node/visibility_control.hpp"
-#include "vehicle_info_util/vehicle_info_util.hpp"
#include
#include
diff --git a/control/trajectory_follower_node/package.xml b/control/trajectory_follower_node/package.xml
index 92b99e690931f..c57a07155128a 100644
--- a/control/trajectory_follower_node/package.xml
+++ b/control/trajectory_follower_node/package.xml
@@ -24,6 +24,7 @@
autoware_mpc_lateral_controller
autoware_pid_longitudinal_controller
autoware_planning_msgs
+ autoware_vehicle_info_utils
autoware_vehicle_msgs
motion_utils
pure_pursuit
@@ -31,7 +32,6 @@
rclcpp_components
tier4_autoware_utils
trajectory_follower_base
- vehicle_info_util
visualization_msgs
ros2launch
diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp
index be335a2d78fa3..b05bb5e1d8ad3 100644
--- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp
+++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/utils/marker_utils.hpp
@@ -15,7 +15,7 @@
#ifndef PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_
#define PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_
-#include
+#include
#include "autoware_perception_msgs/msg/predicted_objects.hpp"
#include
@@ -45,10 +45,10 @@ inline int64_t bitShift(int64_t original_id)
void addFootprintMarker(
visualization_msgs::msg::Marker & marker, const geometry_msgs::msg::Pose & pose,
- const vehicle_info_util::VehicleInfo & vehicle_info);
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info);
MarkerArray createFootprintMarkerArray(
- const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info,
+ const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo vehicle_info,
const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b);
MarkerArray createPointsMarkerArray(
diff --git a/evaluator/perception_online_evaluator/package.xml b/evaluator/perception_online_evaluator/package.xml
index 3f855e2f1f887..d64d3a5ec4957 100644
--- a/evaluator/perception_online_evaluator/package.xml
+++ b/evaluator/perception_online_evaluator/package.xml
@@ -18,6 +18,7 @@
autoware_cmake
autoware_perception_msgs
+ autoware_vehicle_info_utils
diagnostic_msgs
eigen
geometry_msgs
@@ -32,7 +33,6 @@
tf2
tf2_ros
tier4_autoware_utils
- vehicle_info_util
ament_cmake_ros
ament_lint_auto
diff --git a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp
index 523e11883e755..eddeadc331101 100644
--- a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp
+++ b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp
@@ -39,7 +39,7 @@ using visualization_msgs::msg::Marker;
void addFootprintMarker(
visualization_msgs::msg::Marker & marker, const geometry_msgs::msg::Pose & pose,
- const vehicle_info_util::VehicleInfo & vehicle_info)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info)
{
const double half_width = vehicle_info.vehicle_width_m / 2.0;
const double base_to_front = vehicle_info.vehicle_length_m - vehicle_info.rear_overhang_m;
@@ -57,7 +57,7 @@ void addFootprintMarker(
}
MarkerArray createFootprintMarkerArray(
- const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info,
+ const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo vehicle_info,
const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b)
{
const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now();
diff --git a/launch/tier4_sensing_launch/launch/sensing.launch.xml b/launch/tier4_sensing_launch/launch/sensing.launch.xml
index 391a1f8bad641..9981c99a8f3fc 100644
--- a/launch/tier4_sensing_launch/launch/sensing.launch.xml
+++ b/launch/tier4_sensing_launch/launch/sensing.launch.xml
@@ -1,7 +1,7 @@
-
+
diff --git a/launch/tier4_sensing_launch/package.xml b/launch/tier4_sensing_launch/package.xml
index a1f10ee743db5..410f685285b7d 100644
--- a/launch/tier4_sensing_launch/package.xml
+++ b/launch/tier4_sensing_launch/package.xml
@@ -10,7 +10,7 @@
ament_cmake_auto
autoware_cmake
- vehicle_info_util
+ autoware_vehicle_info_utils
ament_lint_auto
autoware_lint_common
diff --git a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp
index d97bbaa2118e5..314c9cfb97a75 100644
--- a/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp
+++ b/perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp
@@ -18,7 +18,7 @@
#include "pointcloud_preprocessor/filter.hpp"
#include "pointcloud_preprocessor/transform_info.hpp"
-#include
+#include
#include
@@ -43,7 +43,7 @@ class ScanGroundFilterTest;
namespace ground_segmentation
{
-using vehicle_info_util::VehicleInfo;
+using autoware::vehicle_info_utils::VehicleInfo;
class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter
{
diff --git a/perception/ground_segmentation/launch/scan_ground_filter.launch.py b/perception/ground_segmentation/launch/scan_ground_filter.launch.py
index d3d856925b9db..df8290997315e 100644
--- a/perception/ground_segmentation/launch/scan_ground_filter.launch.py
+++ b/perception/ground_segmentation/launch/scan_ground_filter.launch.py
@@ -85,7 +85,7 @@ def add_launch_arg(name: str, default_value=None):
return DeclareLaunchArgument(name, default_value=default_value)
default_vehicle_info_param = os.path.join(
- get_package_share_directory("vehicle_info_util"), "config/vehicle_info.param.yaml"
+ get_package_share_directory("autoware_vehicle_info_utils"), "config/vehicle_info.param.yaml"
)
vehicle_info_param = DeclareLaunchArgument(
diff --git a/perception/ground_segmentation/launch/scan_ground_filter.launch.xml b/perception/ground_segmentation/launch/scan_ground_filter.launch.xml
index 2a9e4983ecb56..1146138211211 100644
--- a/perception/ground_segmentation/launch/scan_ground_filter.launch.xml
+++ b/perception/ground_segmentation/launch/scan_ground_filter.launch.xml
@@ -3,7 +3,7 @@
-
+
diff --git a/perception/ground_segmentation/package.xml b/perception/ground_segmentation/package.xml
index 05d5d18baf29e..1b807b393b739 100644
--- a/perception/ground_segmentation/package.xml
+++ b/perception/ground_segmentation/package.xml
@@ -19,6 +19,7 @@
ament_cmake_auto
autoware_cmake
+ autoware_vehicle_info_utils
libopencv-dev
pcl_conversions
pcl_ros
@@ -31,7 +32,6 @@
tf2_eigen
tf2_ros
tf2_sensor_msgs
- vehicle_info_util
yaml-cpp
ament_lint_auto
diff --git a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp
index a63d218df62de..e638baba12521 100644
--- a/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp
+++ b/perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp
@@ -14,10 +14,10 @@
#include "ground_segmentation/scan_ground_filter_nodelet.hpp"
+#include
#include
#include
#include
-#include
#include
#include
@@ -25,12 +25,12 @@
namespace ground_segmentation
{
+using autoware::vehicle_info_utils::VehicleInfoUtils;
using pointcloud_preprocessor::get_param;
using tier4_autoware_utils::calcDistance3d;
using tier4_autoware_utils::deg2rad;
using tier4_autoware_utils::normalizeDegree;
using tier4_autoware_utils::normalizeRadian;
-using vehicle_info_util::VehicleInfoUtil;
ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & options)
: Filter("ScanGroundFilter", options)
@@ -59,7 +59,7 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
use_recheck_ground_cluster_ = declare_parameter("use_recheck_ground_cluster");
use_lowest_point_ = declare_parameter("use_lowest_point");
radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_);
- vehicle_info_ = VehicleInfoUtil(*this).getVehicleInfo();
+ vehicle_info_ = VehicleInfoUtils(*this).getVehicleInfo();
grid_mode_switch_grid_id_ =
grid_mode_switch_radius_ / grid_size_m_; // changing the mode of grid division
diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/marker_utils/utils.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/marker_utils/utils.hpp
index 4abbfd419c43b..04873d9ebcfab 100644
--- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/marker_utils/utils.hpp
+++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/marker_utils/utils.hpp
@@ -18,7 +18,7 @@
#include "autoware_behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp"
#include "autoware_behavior_path_planner_common/utils/path_shifter/path_shifter.hpp"
-#include
+#include
#include
#include
@@ -60,10 +60,10 @@ inline int64_t bitShift(int64_t original_id)
void addFootprintMarker(
visualization_msgs::msg::Marker & marker, const geometry_msgs::msg::Pose & pose,
- const vehicle_info_util::VehicleInfo & vehicle_info);
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info);
MarkerArray createFootprintMarkerArray(
- const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info,
+ const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo vehicle_info,
const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b);
MarkerArray createPointsMarkerArray(
@@ -107,8 +107,9 @@ MarkerArray createDrivableLanesMarkerArray(
const std::vector & drivable_lanes, std::string && ns);
MarkerArray createPredictedPathMarkerArray(
- const PredictedPath & ego_predicted_path, const vehicle_info_util::VehicleInfo & vehicle_info,
- std::string && ns, const int32_t & id, const float & r, const float & g, const float & b);
+ const PredictedPath & ego_predicted_path,
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, std::string && ns,
+ const int32_t & id, const float & r, const float & g, const float & b);
MarkerArray showPolygon(const CollisionCheckDebugMap & obj_debug_vec, std::string && ns);
diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/parameters.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/parameters.hpp
index 21d4906380b59..2f14e227d05ef 100644
--- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/parameters.hpp
+++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/parameters.hpp
@@ -15,7 +15,7 @@
#ifndef AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__PARAMETERS_HPP_
#define AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__PARAMETERS_HPP_
-#include
+#include
struct ModuleConfigParameters
{
@@ -66,7 +66,7 @@ struct BehaviorPathPlannerParameters
double ego_nearest_yaw_threshold;
// vehicle info
- vehicle_info_util::VehicleInfo vehicle_info;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info;
double wheel_base;
double front_overhang;
double rear_overhang;
diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp
index 4dda036fecdb7..d658d29710704 100644
--- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp
+++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp
@@ -237,7 +237,7 @@ class TurnSignalDecider
inline bool straddleRoadBound(
const ShiftedPath & path, const ShiftLine & shift_line, const lanelet::ConstLanelets & lanes,
- const vehicle_info_util::VehicleInfo & vehicle_info) const
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) const
{
using boost::geometry::intersects;
using tier4_autoware_utils::pose2transform;
diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp
index 32613948814ae..35da7e4e24382 100644
--- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp
+++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp
@@ -15,8 +15,8 @@
#ifndef AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__PARAMETERS_HPP_
#define AUTOWARE_BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__PARAMETERS_HPP_
+#include
#include
-#include
#include
#include
@@ -83,7 +83,7 @@ struct DrivableAreaExpansionParameters
bool avoid_dynamic_objects{};
bool print_runtime{};
std::vector avoid_linestring_types{};
- vehicle_info_util::VehicleInfo vehicle_info;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info;
DrivableAreaExpansionParameters() = default;
explicit DrivableAreaExpansionParameters(rclcpp::Node & node) { init(node); }
@@ -121,7 +121,7 @@ struct DrivableAreaExpansionParameters
avoid_linestring_dist = node.declare_parameter(AVOID_LINESTRING_DIST_PARAM);
print_runtime = node.declare_parameter(PRINT_RUNTIME_PARAM);
- vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
+ vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();
}
};
diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp
index d0693a271379e..018e1c87e2302 100644
--- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp
+++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp
@@ -31,6 +31,7 @@
namespace behavior_path_planner::utils::path_safety_checker
{
+using autoware::vehicle_info_utils::VehicleInfo;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedPath;
using autoware_perception_msgs::msg::Shape;
@@ -40,7 +41,6 @@ using geometry_msgs::msg::Twist;
using tier4_autoware_utils::calcYawDeviation;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;
-using vehicle_info_util::VehicleInfo;
bool isTargetObjectOncoming(
const geometry_msgs::msg::Pose & vehicle_pose, const geometry_msgs::msg::Pose & object_pose,
@@ -48,13 +48,13 @@ bool isTargetObjectOncoming(
bool isTargetObjectFront(
const geometry_msgs::msg::Pose & ego_pose, const Polygon2d & obj_polygon,
- const vehicle_info_util::VehicleInfo & vehicle_info);
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info);
bool isTargetObjectFront(
const PathWithLaneId & path, const geometry_msgs::msg::Pose & ego_pose,
- const vehicle_info_util::VehicleInfo & vehicle_info, const Polygon2d & obj_polygon);
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const Polygon2d & obj_polygon);
Polygon2d createExtendedPolygon(
- const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info,
+ const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info,
const double lon_length, const double lat_margin, const bool is_stopped_obj,
CollisionCheckDebug & debug);
Polygon2d createExtendedPolygon(
diff --git a/planning/autoware_behavior_path_planner_common/package.xml b/planning/autoware_behavior_path_planner_common/package.xml
index 03391063b14fc..e9b33f3e71d6f 100644
--- a/planning/autoware_behavior_path_planner_common/package.xml
+++ b/planning/autoware_behavior_path_planner_common/package.xml
@@ -48,6 +48,7 @@
autoware_perception_msgs
autoware_planning_msgs
autoware_rtc_interface
+ autoware_vehicle_info_utils
geometry_msgs
interpolation
lanelet2_extension
@@ -61,7 +62,6 @@
tier4_autoware_utils
tier4_planning_msgs
traffic_light_utils
- vehicle_info_util
visualization_msgs
ament_cmake_ros
ament_lint_auto
diff --git a/planning/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp
index 2b150b807c6ce..a22a63ba0fe6d 100644
--- a/planning/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp
+++ b/planning/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp
@@ -42,7 +42,7 @@ using visualization_msgs::msg::Marker;
void addFootprintMarker(
visualization_msgs::msg::Marker & marker, const geometry_msgs::msg::Pose & pose,
- const vehicle_info_util::VehicleInfo & vehicle_info)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info)
{
const double half_width = vehicle_info.vehicle_width_m / 2.0;
const double base_to_front = vehicle_info.vehicle_length_m - vehicle_info.rear_overhang_m;
@@ -60,7 +60,7 @@ void addFootprintMarker(
}
MarkerArray createFootprintMarkerArray(
- const Pose & base_link_pose, const vehicle_info_util::VehicleInfo vehicle_info,
+ const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo vehicle_info,
const std::string && ns, const int32_t & id, const float & r, const float & g, const float & b)
{
const auto current_time = rclcpp::Clock{RCL_ROS_TIME}.now();
@@ -388,8 +388,9 @@ MarkerArray createDrivableLanesMarkerArray(
return msg;
}
MarkerArray createPredictedPathMarkerArray(
- const PredictedPath & predicted_path, const vehicle_info_util::VehicleInfo & vehicle_info,
- std::string && ns, const int32_t & id, const float & r, const float & g, const float & b)
+ const PredictedPath & predicted_path,
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, std::string && ns,
+ const int32_t & id, const float & r, const float & g, const float & b)
{
if (predicted_path.path.empty()) {
return MarkerArray{};
diff --git a/planning/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
index 233e6f47b92cc..7951be43aa799 100644
--- a/planning/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
+++ b/planning/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp
@@ -51,7 +51,7 @@ bool isTargetObjectOncoming(
bool isTargetObjectFront(
const geometry_msgs::msg::Pose & ego_pose, const Polygon2d & obj_polygon,
- const vehicle_info_util::VehicleInfo & vehicle_info)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info)
{
const double base_to_front = vehicle_info.max_longitudinal_offset_m;
const auto ego_offset_pose =
@@ -71,7 +71,7 @@ bool isTargetObjectFront(
bool isTargetObjectFront(
const PathWithLaneId & path, const geometry_msgs::msg::Pose & ego_pose,
- const vehicle_info_util::VehicleInfo & vehicle_info, const Polygon2d & obj_polygon)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const Polygon2d & obj_polygon)
{
const double base_to_front = vehicle_info.max_longitudinal_offset_m;
const auto ego_point =
@@ -90,7 +90,7 @@ bool isTargetObjectFront(
}
Polygon2d createExtendedPolygon(
- const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info,
+ const Pose & base_link_pose, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info,
const double lon_length, const double lat_margin, const bool is_stopped_obj,
CollisionCheckDebug & debug)
{
@@ -189,7 +189,7 @@ Polygon2d createExtendedPolygon(
Polygon2d createExtendedPolygonAlongPath(
const PathWithLaneId & planned_path, const Pose & base_link_pose,
- const vehicle_info_util::VehicleInfo & vehicle_info, const double lon_length,
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double lon_length,
const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug)
{
const double & base_to_front = vehicle_info.max_longitudinal_offset_m;
diff --git a/planning/autoware_behavior_path_planner_common/test/test_safety_check.cpp b/planning/autoware_behavior_path_planner_common/test/test_safety_check.cpp
index 3cb71b1f9c4e2..4f23c9f6c07c0 100644
--- a/planning/autoware_behavior_path_planner_common/test/test_safety_check.cpp
+++ b/planning/autoware_behavior_path_planner_common/test/test_safety_check.cpp
@@ -39,7 +39,7 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon)
{
using behavior_path_planner::utils::path_safety_checker::createExtendedPolygon;
- vehicle_info_util::VehicleInfo vehicle_info;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info;
vehicle_info.max_longitudinal_offset_m = 4.0;
vehicle_info.vehicle_width_m = 2.0;
vehicle_info.rear_overhang_m = 1.0;
diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp
index 613911ba33460..0c8eb1850b9d5 100644
--- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp
+++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/freespace_pull_out.hpp
@@ -36,7 +36,7 @@ class FreespacePullOut : public PullOutPlannerBase
public:
FreespacePullOut(
rclcpp::Node & node, const StartPlannerParameters & parameters,
- const vehicle_info_util::VehicleInfo & vehicle_info);
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info);
PlannerType getPlannerType() const override { return PlannerType::FREESPACE; }
diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp
index 8cbe3569d13fe..38eeb558e85eb 100644
--- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp
+++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/pull_out_planner_base.hpp
@@ -45,7 +45,7 @@ class PullOutPlannerBase
public:
explicit PullOutPlannerBase(rclcpp::Node & node, const StartPlannerParameters & parameters)
{
- vehicle_info_ = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
+ vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();
vehicle_footprint_ = vehicle_info_.createFootprint();
parameters_ = parameters;
}
@@ -95,7 +95,7 @@ class PullOutPlannerBase
collision_check_margin_);
};
std::shared_ptr planner_data_;
- vehicle_info_util::VehicleInfo vehicle_info_;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
LinearRing2d vehicle_footprint_;
StartPlannerParameters parameters_;
double collision_check_margin_;
diff --git a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp
index 7a98a43efec5b..ccbf1eada7378 100644
--- a/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp
+++ b/planning/autoware_behavior_path_start_planner_module/include/autoware_behavior_path_start_planner_module/start_planner_module.hpp
@@ -28,8 +28,8 @@
#include "autoware_behavior_path_start_planner_module/shift_pull_out.hpp"
#include
-#include
-#include
+#include
+#include
#include
@@ -255,7 +255,7 @@ class StartPlannerModule : public SceneModuleInterface
mutable std::shared_ptr ego_predicted_path_params_;
mutable std::shared_ptr objects_filtering_params_;
mutable std::shared_ptr safety_check_params_;
- vehicle_info_util::VehicleInfo vehicle_info_;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
std::vector> start_planners_;
PullOutStatus status_;
diff --git a/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp b/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp
index f0a83741212b8..1b154138d427e 100644
--- a/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp
+++ b/planning/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp
@@ -28,7 +28,7 @@ namespace behavior_path_planner
{
FreespacePullOut::FreespacePullOut(
rclcpp::Node & node, const StartPlannerParameters & parameters,
- const vehicle_info_util::VehicleInfo & vehicle_info)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info)
: PullOutPlannerBase{node, parameters}, velocity_{parameters.freespace_planner_velocity}
{
autoware::freespace_planning_algorithms::VehicleShape vehicle_shape(
diff --git a/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp
index b30af17eaa898..2efd2bc17e6ab 100644
--- a/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp
+++ b/planning/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp
@@ -60,7 +60,7 @@ StartPlannerModule::StartPlannerModule(
objects_of_interest_marker_interface_ptr_map)
: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT
parameters_{parameters},
- vehicle_info_{vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo()},
+ vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()},
is_freespace_planner_cb_running_{false}
{
lane_departure_checker_ = std::make_shared();
diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml b/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml
index e3699306df1f3..5a47bed4c712a 100644
--- a/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml
+++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/package.xml
@@ -24,6 +24,7 @@
autoware_behavior_path_planner_common
autoware_perception_msgs
autoware_rtc_interface
+ autoware_vehicle_info_utils
behavior_path_planner
geometry_msgs
lanelet2_extension
@@ -41,7 +42,6 @@
tf2_ros
tier4_autoware_utils
tier4_planning_msgs
- vehicle_info_util
visualization_msgs
ament_cmake_ros
diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp
index 8671c71430b3d..1408c096c7e4e 100644
--- a/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp
+++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp
@@ -138,7 +138,7 @@ double calcSignedArcLengthToFirstNearestPoint(
}
geometry_msgs::msg::Polygon createVehiclePolygon(
- const vehicle_info_util::VehicleInfo & vehicle_info, const double offset)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double offset)
{
const auto & i = vehicle_info;
const auto & front_m = i.max_longitudinal_offset_m;
diff --git a/planning/autoware_behavior_velocity_intersection_module/package.xml b/planning/autoware_behavior_velocity_intersection_module/package.xml
index 0655867951ed8..5ce1ff206a1a9 100644
--- a/planning/autoware_behavior_velocity_intersection_module/package.xml
+++ b/planning/autoware_behavior_velocity_intersection_module/package.xml
@@ -22,6 +22,7 @@
autoware_perception_msgs
autoware_planning_msgs
autoware_rtc_interface
+ autoware_vehicle_info_utils
fmt
geometry_msgs
interpolation
@@ -36,7 +37,6 @@
tf2_geometry_msgs
tier4_autoware_utils
tier4_planning_msgs
- vehicle_info_util
visualization_msgs
ament_lint_auto
diff --git a/planning/autoware_behavior_velocity_occlusion_spot_module/package.xml b/planning/autoware_behavior_velocity_occlusion_spot_module/package.xml
index 2f56bce7155b5..d8177ddc908f3 100644
--- a/planning/autoware_behavior_velocity_occlusion_spot_module/package.xml
+++ b/planning/autoware_behavior_velocity_occlusion_spot_module/package.xml
@@ -19,6 +19,7 @@
autoware_behavior_velocity_planner_common
autoware_perception_msgs
autoware_planning_msgs
+ autoware_vehicle_info_utils
geometry_msgs
grid_map_ros
grid_map_utils
@@ -34,7 +35,6 @@
tf2
tf2_geometry_msgs
tier4_autoware_utils
- vehicle_info_util
visualization_msgs
ament_cmake_ros
diff --git a/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp b/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp
index b1757c4142212..c1d345cbc9aac 100644
--- a/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp
+++ b/planning/autoware_behavior_velocity_occlusion_spot_module/src/manager.cpp
@@ -109,7 +109,7 @@ OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node)
pp.grid.free_space_max = getOrDeclareParameter(node, ns + ".grid.free_space_max");
pp.grid.occupied_min = getOrDeclareParameter(node, ns + ".grid.occupied_min");
- const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
+ const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();
pp.baselink_to_front = vehicle_info.max_longitudinal_offset_m;
pp.wheel_tread = vehicle_info.wheel_tread_m;
pp.right_overhang = vehicle_info.right_overhang_m;
diff --git a/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp
index c69f23215a369..df5d083f5dcb1 100644
--- a/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp
+++ b/planning/autoware_behavior_velocity_planner_common/include/autoware_behavior_velocity_planner_common/planner_data.hpp
@@ -18,8 +18,8 @@
#include "route_handler/route_handler.hpp"
#include
+#include
#include
-#include
#include
#include
@@ -51,7 +51,7 @@ class BehaviorVelocityPlannerNode;
struct PlannerData
{
explicit PlannerData(rclcpp::Node & node)
- : vehicle_info_(vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo())
+ : vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo())
{
max_stop_acceleration_threshold = node.declare_parameter(
"max_accel"); // TODO(someone): read min_acc in velocity_controller.param.yaml?
@@ -92,7 +92,7 @@ struct PlannerData
// route handler
std::shared_ptr route_handler_;
// parameters
- vehicle_info_util::VehicleInfo vehicle_info_;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
// additional parameters
double max_stop_acceleration_threshold;
diff --git a/planning/autoware_behavior_velocity_planner_common/package.xml b/planning/autoware_behavior_velocity_planner_common/package.xml
index 7ab991a247a63..0e317ceb5db66 100644
--- a/planning/autoware_behavior_velocity_planner_common/package.xml
+++ b/planning/autoware_behavior_velocity_planner_common/package.xml
@@ -24,6 +24,7 @@
autoware_perception_msgs
autoware_planning_msgs
autoware_rtc_interface
+ autoware_vehicle_info_utils
autoware_velocity_smoother
diagnostic_msgs
eigen
@@ -46,7 +47,6 @@
tier4_autoware_utils
tier4_planning_msgs
tier4_v2x_msgs
- vehicle_info_util
visualization_msgs
ament_cmake_ros
diff --git a/planning/autoware_behavior_velocity_run_out_module/package.xml b/planning/autoware_behavior_velocity_run_out_module/package.xml
index 330880b77d3da..284797cbed0a8 100644
--- a/planning/autoware_behavior_velocity_run_out_module/package.xml
+++ b/planning/autoware_behavior_velocity_run_out_module/package.xml
@@ -22,6 +22,7 @@
autoware_behavior_velocity_planner_common
autoware_perception_msgs
autoware_planning_msgs
+ autoware_vehicle_info_utils
behavior_velocity_crosswalk_module
eigen
geometry_msgs
@@ -38,7 +39,6 @@
tf2_eigen
tf2_ros
tier4_autoware_utils
- vehicle_info_util
visualization_msgs
ament_lint_auto
diff --git a/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp b/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp
index 002a49abae611..4da58522165d6 100644
--- a/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp
+++ b/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp
@@ -28,7 +28,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node)
{
// Vehicle Parameters
{
- const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
+ const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();
auto & p = planner_param_.vehicle_param;
p.base_to_front = vehicle_info.wheel_base_m + vehicle_info.front_overhang_m;
p.base_to_rear = vehicle_info.rear_overhang_m;
diff --git a/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp b/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp
index 28bfa9569c66d..90f8238d0d543 100644
--- a/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp
+++ b/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp
@@ -19,7 +19,7 @@
#include
#include
-#include
+#include
#include
#include
@@ -34,6 +34,7 @@ namespace autoware::behavior_velocity_planner
namespace run_out_utils
{
namespace bg = boost::geometry;
+using autoware::vehicle_info_utils::VehicleInfo;
using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::Shape;
@@ -44,7 +45,6 @@ using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;
using tier4_debug_msgs::msg::Float32Stamped;
using tier4_planning_msgs::msg::PathWithLaneId;
-using vehicle_info_util::VehicleInfo;
using PathPointsWithLaneId = std::vector;
struct CommonParam
{
diff --git a/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml b/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml
index cda3abbd0eee9..415dcd983a8df 100644
--- a/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml
+++ b/planning/autoware_behavior_velocity_virtual_traffic_light_module/package.xml
@@ -19,6 +19,7 @@
autoware_adapi_v1_msgs
autoware_behavior_velocity_planner_common
autoware_planning_msgs
+ autoware_vehicle_info_utils
geometry_msgs
lanelet2_extension
motion_utils
@@ -29,7 +30,6 @@
tier4_autoware_utils
tier4_planning_msgs
tier4_v2x_msgs
- vehicle_info_util
visualization_msgs
ament_lint_auto
diff --git a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp
index 9775e64145529..d413a8721c09e 100644
--- a/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp
+++ b/planning/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp
@@ -16,13 +16,13 @@
#define SCENE_HPP_
#include
+#include
#include
#include
#include
#include
#include
#include
-#include
#include
#include
diff --git a/planning/autoware_behavior_velocity_walkway_module/package.xml b/planning/autoware_behavior_velocity_walkway_module/package.xml
index bbe87ffb8b2cd..60ef7593ab8ff 100644
--- a/planning/autoware_behavior_velocity_walkway_module/package.xml
+++ b/planning/autoware_behavior_velocity_walkway_module/package.xml
@@ -19,6 +19,7 @@
autoware_behavior_velocity_planner_common
autoware_planning_msgs
+ autoware_vehicle_info_utils
behavior_velocity_crosswalk_module
geometry_msgs
lanelet2_extension
@@ -28,7 +29,6 @@
rclcpp
route_handler
tier4_autoware_utils
- vehicle_info_util
visualization_msgs
ament_lint_auto
diff --git a/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp
index 27a563f4ec1af..394900c9a704c 100644
--- a/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp
+++ b/planning/autoware_freespace_planning_algorithms/include/autoware_freespace_planning_algorithms/abstract_algorithm.hpp
@@ -15,8 +15,8 @@
#ifndef AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_
#define AUTOWARE_FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_
+#include
#include
-#include
#include
#include
@@ -69,7 +69,7 @@ struct VehicleShape
}
explicit VehicleShape(
- const vehicle_info_util::VehicleInfo & vehicle_info, const double margin = 0.0)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double margin = 0.0)
: length(vehicle_info.vehicle_length_m + margin),
width(vehicle_info.vehicle_width_m + margin),
base2back(vehicle_info.rear_overhang_m + margin / 2.0)
@@ -125,7 +125,7 @@ class AbstractPlanningAlgorithm
AbstractPlanningAlgorithm(
const PlannerCommonParam & planner_common_param,
- const vehicle_info_util::VehicleInfo & vehicle_info, const double margin = 0.0)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double margin = 0.0)
: planner_common_param_(planner_common_param), collision_vehicle_shape_(vehicle_info, margin)
{
}
diff --git a/planning/autoware_freespace_planning_algorithms/package.xml b/planning/autoware_freespace_planning_algorithms/package.xml
index d2b7ddc7c620a..61173f0a877e4 100644
--- a/planning/autoware_freespace_planning_algorithms/package.xml
+++ b/planning/autoware_freespace_planning_algorithms/package.xml
@@ -16,6 +16,7 @@
autoware_cmake
python_cmake_module
+ autoware_vehicle_info_utils
geometry_msgs
nav_msgs
nlohmann-json-dev
@@ -25,7 +26,6 @@
tf2
tf2_geometry_msgs
tier4_autoware_utils
- vehicle_info_util
ament_cmake_ros
ament_lint_auto
diff --git a/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp b/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp
index edca8d706047b..cea58a11a530a 100644
--- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp
+++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/debug_marker.hpp
@@ -16,10 +16,10 @@
#include "autoware_path_optimizer/common_structs.hpp"
#include "autoware_path_optimizer/type_alias.hpp"
+#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "rclcpp/clock.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"
-#include "vehicle_info_util/vehicle_info_util.hpp"
#include
#include
@@ -30,6 +30,6 @@ namespace autoware::path_optimizer
MarkerArray getDebugMarker(
const DebugData & debug_data,
const std::vector & optimized_points,
- const vehicle_info_util::VehicleInfo & vehicle_info, const bool publish_extra_marker);
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const bool publish_extra_marker);
} // namespace autoware::path_optimizer
#endif // AUTOWARE_PATH_OPTIMIZER__DEBUG_MARKER_HPP_
diff --git a/planning/autoware_path_optimizer/include/autoware_path_optimizer/mpt_optimizer.hpp b/planning/autoware_path_optimizer/include/autoware_path_optimizer/mpt_optimizer.hpp
index 8c207a9a3830f..98d7e131f4bdc 100644
--- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/mpt_optimizer.hpp
+++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/mpt_optimizer.hpp
@@ -18,12 +18,12 @@
#include "autoware_path_optimizer/common_structs.hpp"
#include "autoware_path_optimizer/state_equation_generator.hpp"
#include "autoware_path_optimizer/type_alias.hpp"
+#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "gtest/gtest.h"
#include "interpolation/linear_interpolation.hpp"
#include "interpolation/spline_interpolation_points_2d.hpp"
#include "osqp_interface/osqp_interface.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"
-#include "vehicle_info_util/vehicle_info_util.hpp"
#include
#include
@@ -105,8 +105,8 @@ class MPTOptimizer
public:
MPTOptimizer(
rclcpp::Node * node, const bool enable_debug_info, const EgoNearestParam ego_nearest_param,
- const vehicle_info_util::VehicleInfo & vehicle_info, const TrajectoryParam & traj_param,
- const std::shared_ptr debug_data_ptr,
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info,
+ const TrajectoryParam & traj_param, const std::shared_ptr debug_data_ptr,
const std::shared_ptr time_keeper_ptr);
std::vector optimizeTrajectory(const PlannerData & planner_data);
@@ -142,7 +142,8 @@ class MPTOptimizer
struct MPTParam
{
- explicit MPTParam(rclcpp::Node * node, const vehicle_info_util::VehicleInfo & vehicle_info);
+ explicit MPTParam(
+ rclcpp::Node * node, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info);
MPTParam() = default;
void onParam(const std::vector & parameters);
@@ -218,7 +219,7 @@ class MPTOptimizer
// argument
bool enable_debug_info_;
EgoNearestParam ego_nearest_param_;
- vehicle_info_util::VehicleInfo vehicle_info_;
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
TrajectoryParam traj_param_;
mutable std::shared_ptr debug_data_ptr_;
mutable std::shared_ptr time_keeper_ptr_;
diff --git a/planning/autoware_path_optimizer/include/autoware_path_optimizer/node.hpp b/planning/autoware_path_optimizer/include/autoware_path_optimizer/node.hpp
index 30c95debe11cb..c1f644d31aa9a 100644
--- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/node.hpp
+++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/node.hpp
@@ -19,11 +19,11 @@
#include "autoware_path_optimizer/mpt_optimizer.hpp"
#include "autoware_path_optimizer/replan_checker.hpp"
#include "autoware_path_optimizer/type_alias.hpp"
+#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
-#include "vehicle_info_util/vehicle_info_util.hpp"
#include
@@ -63,7 +63,7 @@ class PathOptimizer : public rclcpp::Node
DrivingDirectionChecker driving_direction_checker_{};
// argument variables
- vehicle_info_util::VehicleInfo vehicle_info_{};
+ autoware::vehicle_info_utils::VehicleInfo vehicle_info_{};
mutable std::shared_ptr debug_data_ptr_{nullptr};
mutable std::shared_ptr time_keeper_ptr_{nullptr};
diff --git a/planning/autoware_path_optimizer/include/autoware_path_optimizer/utils/geometry_utils.hpp b/planning/autoware_path_optimizer/include/autoware_path_optimizer/utils/geometry_utils.hpp
index 588b68f52a094..aa44a515a08ec 100644
--- a/planning/autoware_path_optimizer/include/autoware_path_optimizer/utils/geometry_utils.hpp
+++ b/planning/autoware_path_optimizer/include/autoware_path_optimizer/utils/geometry_utils.hpp
@@ -17,11 +17,11 @@
#include "autoware_path_optimizer/common_structs.hpp"
#include "autoware_path_optimizer/type_alias.hpp"
+#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "interpolation/linear_interpolation.hpp"
#include "interpolation/spline_interpolation.hpp"
#include "interpolation/spline_interpolation_points_2d.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
-#include "vehicle_info_util/vehicle_info_util.hpp"
#include
@@ -65,7 +65,7 @@ bool isSamePoint(const T1 & t1, const T2 & t2)
bool isOutsideDrivableAreaFromRectangleFootprint(
const geometry_msgs::msg::Pose & pose, const std::vector & left_bound,
const std::vector & right_bound,
- const vehicle_info_util::VehicleInfo & vehicle_info,
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info,
const bool use_footprint_polygon_for_outside_drivable_area_check);
} // namespace geometry_utils
} // namespace autoware::path_optimizer
diff --git a/planning/autoware_path_optimizer/package.xml b/planning/autoware_path_optimizer/package.xml
index f02473ebd015e..c158815999398 100644
--- a/planning/autoware_path_optimizer/package.xml
+++ b/planning/autoware_path_optimizer/package.xml
@@ -16,6 +16,7 @@
autoware_planning_msgs
autoware_planning_test_manager
+ autoware_vehicle_info_utils
geometry_msgs
interpolation
motion_utils
@@ -28,7 +29,6 @@
tier4_autoware_utils
tier4_debug_msgs
tier4_planning_msgs
- vehicle_info_util
visualization_msgs
ament_cmake_ros
diff --git a/planning/autoware_path_optimizer/src/debug_marker.cpp b/planning/autoware_path_optimizer/src/debug_marker.cpp
index 7c644f4448a0c..c97d5c5adec46 100644
--- a/planning/autoware_path_optimizer/src/debug_marker.cpp
+++ b/planning/autoware_path_optimizer/src/debug_marker.cpp
@@ -29,7 +29,7 @@ namespace
{
MarkerArray getFootprintsMarkerArray(
const std::vector & mpt_traj,
- const vehicle_info_util::VehicleInfo & vehicle_info, const size_t sampling_num)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const size_t sampling_num)
{
auto marker = createDefaultMarker(
"map", rclcpp::Clock().now(), "mpt_footprints", 0, Marker::LINE_STRIP,
@@ -73,7 +73,7 @@ MarkerArray getFootprintsMarkerArray(
MarkerArray getBoundsWidthMarkerArray(
const std::vector & ref_points,
- const vehicle_info_util::VehicleInfo & vehicle_info, const size_t sampling_num)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const size_t sampling_num)
{
const auto current_time = rclcpp::Clock().now();
MarkerArray marker_array;
@@ -146,7 +146,7 @@ MarkerArray getBoundsWidthMarkerArray(
MarkerArray getBoundsLineMarkerArray(
const std::vector & ref_points,
- const vehicle_info_util::VehicleInfo & vehicle_info)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info)
{
MarkerArray marker_array;
@@ -183,7 +183,7 @@ MarkerArray getBoundsLineMarkerArray(
MarkerArray getVehicleCircleLinesMarkerArray(
const std::vector & ref_points,
const std::vector & vehicle_circle_longitudinal_offsets,
- const vehicle_info_util::VehicleInfo & vehicle_info, const size_t sampling_num,
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const size_t sampling_num,
const std::string & ns)
{
const auto current_time = rclcpp::Clock().now();
@@ -339,8 +339,9 @@ visualization_msgs::msg::MarkerArray getPointsTextMarkerArray(
}
visualization_msgs::msg::MarkerArray getFootprintByDrivableAreaMarkerArray(
- const geometry_msgs::msg::Pose & stop_pose, const vehicle_info_util::VehicleInfo & vehicle_info,
- const std::string & ns, const double r, const double g, const double b)
+ const geometry_msgs::msg::Pose & stop_pose,
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const std::string & ns,
+ const double r, const double g, const double b)
{
visualization_msgs::msg::MarkerArray msg;
@@ -373,7 +374,7 @@ visualization_msgs::msg::MarkerArray getFootprintByDrivableAreaMarkerArray(
MarkerArray getDebugMarker(
const DebugData & debug_data, const std::vector & optimized_points,
- const vehicle_info_util::VehicleInfo & vehicle_info, const bool publish_extra_marker)
+ const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const bool publish_extra_marker)
{
MarkerArray marker_array;
diff --git a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp
index 2ab622c6b4b58..0652085d85c48 100644
--- a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp
+++ b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp
@@ -34,7 +34,7 @@ namespace autoware::path_optimizer
namespace
{
std::tuple, std::vector