Skip to content

Commit ed60229

Browse files
authored
refactor(vehicle_info_utils)!: prefix package and namespace with autoware (autowarefoundation#7353)
* chore(autoware_vehicle_info_utils): rename header Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(bpp-common): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(path_optimizer): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(velocity_smoother): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(bvp-common): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(static_centerline_generator): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(obstacle_cruise_planner): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(obstacle_velocity_limiter): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(mission_planner): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(obstacle_stop_planner): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(planning_validator): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(surround_obstacle_checker): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(goal_planner): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(start_planner): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(control_performance_analysis): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(lane_departure_checker): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(predicted_path_checker): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(vehicle_cmd_gate): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(obstacle_collision_checker): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(operation_mode_transition_manager): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(mpc): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(control): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(common): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(perception): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(evaluator): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(freespace): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(planning): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(vehicle): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(simulator): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(launch): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(system): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * chore(sensing): vehicle info Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(autoware_joy_controller): remove unused deps Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent badc3e7 commit ed60229

File tree

194 files changed

+350
-338
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

194 files changed

+350
-338
lines changed

.github/CODEOWNERS

+2-1
Original file line numberDiff line numberDiff line change
@@ -248,6 +248,7 @@ vehicle/accel_brake_map_calibrator/** taiki.tanaka@tier4.jp takeshi.miura@tier4.
248248
vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp
249249
vehicle/external_cmd_converter/** takamasa.horibe@tier4.jp
250250
vehicle/raw_vehicle_cmd_converter/** makoto.kurihara@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp
251-
vehicle/vehicle_info_util/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
251+
vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp
252+
vehicle/autoware_vehicle_info_utils/** shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
252253

253254
### Copied from .github/CODEOWNERS-manual ###

common/global_parameter_loader/launch/global_params.launch.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ def launch_setup(context, *args, **kwargs):
3333

3434
load_vehicle_info = IncludeLaunchDescription(
3535
PythonLaunchDescriptionSource(
36-
[FindPackageShare("vehicle_info_util"), "/launch/vehicle_info.launch.py"]
36+
[FindPackageShare("autoware_vehicle_info_utils"), "/launch/vehicle_info.launch.py"]
3737
),
3838
launch_arguments={
3939
"vehicle_info_param_file": [vehicle_description_pkg, "/config/vehicle_info.param.yaml"]

common/global_parameter_loader/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@
1010
<buildtool_depend>ament_cmake_auto</buildtool_depend>
1111
<buildtool_depend>autoware_cmake</buildtool_depend>
1212

13-
<exec_depend>vehicle_info_util</exec_depend>
13+
<exec_depend>autoware_vehicle_info_utils</exec_depend>
1414

1515
<test_depend>ament_lint_auto</test_depend>
1616
<test_depend>autoware_lint_common</test_depend>

common/tier4_localization_rviz_plugin/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111
<buildtool_depend>ament_cmake_auto</buildtool_depend>
1212
<buildtool_depend>autoware_cmake</buildtool_depend>
1313

14+
<depend>autoware_vehicle_info_utils</depend>
1415
<depend>geometry_msgs</depend>
1516
<depend>libqt5-core</depend>
1617
<depend>libqt5-gui</depend>
@@ -20,7 +21,6 @@
2021
<depend>rviz_common</depend>
2122
<depend>rviz_default_plugins</depend>
2223
<depend>tf2_ros</depend>
23-
<depend>vehicle_info_util</depend>
2424

2525
<test_depend>ament_lint_auto</test_depend>
2626
<test_depend>autoware_lint_common</test_depend>

common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -172,7 +172,7 @@ void PoseHistoryFootprint::updateFootprint()
172172
if (!vehicle_info_) {
173173
try {
174174
vehicle_info_ = std::make_shared<VehicleInfo>(
175-
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
175+
VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
176176
updateVehicleInfo();
177177
} catch (const std::exception & e) {
178178
RCLCPP_WARN_THROTTLE(

common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,8 @@
1515
#ifndef POSE_HISTORY_FOOTPRINT__DISPLAY_HPP_
1616
#define POSE_HISTORY_FOOTPRINT__DISPLAY_HPP_
1717

18+
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
1819
#include <rviz_common/message_filter_display.hpp>
19-
#include <vehicle_info_util/vehicle_info_util.hpp>
2020

2121
#include <geometry_msgs/msg/pose_stamped.hpp>
2222

@@ -39,8 +39,8 @@ class BoolProperty;
3939
namespace rviz_plugins
4040
{
4141

42-
using vehicle_info_util::VehicleInfo;
43-
using vehicle_info_util::VehicleInfoUtil;
42+
using autoware::vehicle_info_utils::VehicleInfo;
43+
using autoware::vehicle_info_utils::VehicleInfoUtils;
4444

4545
class PoseHistoryFootprint
4646
: public rviz_common::MessageFilterDisplay<geometry_msgs::msg::PoseStamped>

common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_
1616
#define TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_
1717

18+
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
1819
#include <rclcpp/rclcpp.hpp>
1920
#include <rviz_common/display_context.hpp>
2021
#include <rviz_common/frame_manager_iface.hpp>
@@ -25,7 +26,6 @@
2526
#include <rviz_common/properties/parse_color.hpp>
2627
#include <rviz_common/validate_floats.hpp>
2728
#include <rviz_rendering/objects/movable_text.hpp>
28-
#include <vehicle_info_util/vehicle_info_util.hpp>
2929

3030
#include <autoware_planning_msgs/msg/path.hpp>
3131

@@ -97,8 +97,8 @@ bool validateFloats(const typename T::ConstSharedPtr & msg_ptr)
9797

9898
namespace rviz_plugins
9999
{
100-
using vehicle_info_util::VehicleInfo;
101-
using vehicle_info_util::VehicleInfoUtil;
100+
using autoware::vehicle_info_utils::VehicleInfo;
101+
using autoware::vehicle_info_utils::VehicleInfoUtils;
102102
template <typename T>
103103
class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay<T>
104104
{

common/tier4_planning_rviz_plugin/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
<buildtool_depend>autoware_cmake</buildtool_depend>
1313

1414
<depend>autoware_planning_msgs</depend>
15+
<depend>autoware_vehicle_info_utils</depend>
1516
<depend>libqt5-core</depend>
1617
<depend>libqt5-gui</depend>
1718
<depend>libqt5-widgets</depend>
@@ -25,7 +26,6 @@
2526
<depend>tf2_ros</depend>
2627
<depend>tier4_autoware_utils</depend>
2728
<depend>tier4_planning_msgs</depend>
28-
<depend>vehicle_info_util</depend>
2929

3030
<test_depend>ament_lint_auto</test_depend>
3131
<test_depend>autoware_lint_common</test_depend>

common/tier4_planning_rviz_plugin/src/path/display.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ void AutowarePathWithLaneIdDisplay::preProcessMessageDetail()
3131
if (!vehicle_info_) {
3232
try {
3333
vehicle_info_ = std::make_shared<VehicleInfo>(
34-
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
34+
VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
3535
updateVehicleInfo();
3636
} catch (const std::exception & e) {
3737
RCLCPP_WARN_ONCE(
@@ -107,7 +107,7 @@ void AutowarePathDisplay::preProcessMessageDetail()
107107
if (!vehicle_info_) {
108108
try {
109109
vehicle_info_ = std::make_shared<VehicleInfo>(
110-
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
110+
VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
111111
updateVehicleInfo();
112112
} catch (const std::exception & e) {
113113
RCLCPP_WARN_ONCE(
@@ -124,7 +124,7 @@ void AutowareTrajectoryDisplay::preProcessMessageDetail()
124124
if (!vehicle_info_) {
125125
try {
126126
vehicle_info_ = std::make_shared<VehicleInfo>(
127-
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
127+
VehicleInfoUtils(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
128128
updateVehicleInfo();
129129
} catch (const std::exception & e) {
130130
RCLCPP_WARN_ONCE(

control/autoware_autonomous_emergency_braking/include/autoware_autonomous_emergency_braking/node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,13 @@
1515
#ifndef AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_
1616
#define AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_
1717

18+
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
1819
#include <diagnostic_updater/diagnostic_updater.hpp>
1920
#include <motion_utils/trajectory/trajectory.hpp>
2021
#include <pcl_ros/transforms.hpp>
2122
#include <rclcpp/rclcpp.hpp>
2223
#include <tier4_autoware_utils/geometry/geometry.hpp>
2324
#include <tier4_autoware_utils/ros/polling_subscriber.hpp>
24-
#include <vehicle_info_util/vehicle_info_util.hpp>
2525

2626
#include <autoware_planning_msgs/msg/trajectory.hpp>
2727
#include <autoware_system_msgs/msg/autoware_state.hpp>
@@ -59,11 +59,11 @@ using nav_msgs::msg::Odometry;
5959
using sensor_msgs::msg::Imu;
6060
using sensor_msgs::msg::PointCloud2;
6161
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
62+
using autoware::vehicle_info_utils::VehicleInfo;
6263
using diagnostic_updater::DiagnosticStatusWrapper;
6364
using diagnostic_updater::Updater;
6465
using tier4_autoware_utils::Point2d;
6566
using tier4_autoware_utils::Polygon2d;
66-
using vehicle_info_util::VehicleInfo;
6767
using visualization_msgs::msg::Marker;
6868
using visualization_msgs::msg::MarkerArray;
6969
using Path = std::vector<geometry_msgs::msg::Pose>;

control/autoware_autonomous_emergency_braking/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
<depend>autoware_control_msgs</depend>
1818
<depend>autoware_planning_msgs</depend>
1919
<depend>autoware_system_msgs</depend>
20+
<depend>autoware_vehicle_info_utils</depend>
2021
<depend>autoware_vehicle_msgs</depend>
2122
<depend>diagnostic_updater</depend>
2223
<depend>geometry_msgs</depend>
@@ -34,7 +35,6 @@
3435
<depend>tf2_geometry_msgs</depend>
3536
<depend>tf2_ros</depend>
3637
<depend>tier4_autoware_utils</depend>
37-
<depend>vehicle_info_util</depend>
3838
<depend>visualization_msgs</depend>
3939

4040
<test_depend>ament_lint_auto</test_depend>

control/autoware_autonomous_emergency_braking/src/node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point &
6060

6161
Polygon2d createPolygon(
6262
const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & next_pose,
63-
const vehicle_info_util::VehicleInfo & vehicle_info, const double expand_width)
63+
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double expand_width)
6464
{
6565
Polygon2d polygon;
6666

@@ -102,7 +102,7 @@ Polygon2d createPolygon(
102102

103103
AEB::AEB(const rclcpp::NodeOptions & node_options)
104104
: Node("AEB", node_options),
105-
vehicle_info_(vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo()),
105+
vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo()),
106106
collision_data_keeper_(this->get_clock())
107107
{
108108
// Publisher

control/autoware_mpc_lateral_controller/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
<depend>autoware_control_msgs</depend>
2121
<depend>autoware_planning_msgs</depend>
22+
<depend>autoware_vehicle_info_utils</depend>
2223
<depend>autoware_vehicle_msgs</depend>
2324
<depend>diagnostic_msgs</depend>
2425
<depend>diagnostic_updater</depend>
@@ -35,7 +36,6 @@
3536
<depend>tier4_autoware_utils</depend>
3637
<depend>tier4_debug_msgs</depend>
3738
<depend>trajectory_follower_base</depend>
38-
<depend>vehicle_info_util</depend>
3939

4040
<test_depend>ament_cmake_ros</test_depend>
4141
<test_depend>ament_lint_auto</test_depend>

control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -19,10 +19,10 @@
1919
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_dynamics.hpp"
2020
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics.hpp"
2121
#include "autoware_mpc_lateral_controller/vehicle_model/vehicle_model_bicycle_kinematics_no_delay.hpp"
22+
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
2223
#include "motion_utils/trajectory/trajectory.hpp"
2324
#include "tf2/utils.h"
2425
#include "tf2_ros/create_timer_ros.h"
25-
#include "vehicle_info_util/vehicle_info_util.hpp"
2626

2727
#include <algorithm>
2828
#include <deque>
@@ -69,7 +69,7 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node)
6969
m_mpc_converged_threshold_rps = dp_double("mpc_converged_threshold_rps"); // [rad/s]
7070

7171
/* mpc parameters */
72-
const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
72+
const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();
7373
const double wheelbase = vehicle_info.wheel_base_m;
7474
constexpr double deg2rad = static_cast<double>(M_PI) / 180.0;
7575
m_mpc->m_steer_lim = vehicle_info.max_steer_angle_rad;

control/autoware_pid_longitudinal_controller/include/autoware_pid_longitudinal_controller/pid_longitudinal_controller.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -20,14 +20,14 @@
2020
#include "autoware_pid_longitudinal_controller/lowpass_filter.hpp"
2121
#include "autoware_pid_longitudinal_controller/pid.hpp"
2222
#include "autoware_pid_longitudinal_controller/smooth_stop.hpp"
23+
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
2324
#include "diagnostic_updater/diagnostic_updater.hpp"
2425
#include "rclcpp/rclcpp.hpp"
2526
#include "tf2/utils.h"
2627
#include "tf2_ros/buffer.h"
2728
#include "tf2_ros/transform_listener.h"
2829
#include "tier4_autoware_utils/ros/marker_helper.hpp"
2930
#include "trajectory_follower_base/longitudinal_controller_base.hpp"
30-
#include "vehicle_info_util/vehicle_info_util.hpp"
3131

3232
#include <Eigen/Core>
3333
#include <Eigen/Geometry>

control/autoware_pid_longitudinal_controller/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
<depend>autoware_adapi_v1_msgs</depend>
2222
<depend>autoware_control_msgs</depend>
2323
<depend>autoware_planning_msgs</depend>
24+
<depend>autoware_vehicle_info_utils</depend>
2425
<depend>autoware_vehicle_msgs</depend>
2526
<depend>diagnostic_msgs</depend>
2627
<depend>diagnostic_updater</depend>
@@ -36,7 +37,6 @@
3637
<depend>tier4_autoware_utils</depend>
3738
<depend>tier4_debug_msgs</depend>
3839
<depend>trajectory_follower_base</depend>
39-
<depend>vehicle_info_util</depend>
4040

4141
<test_depend>ament_cmake_ros</test_depend>
4242
<test_depend>ament_lint_auto</test_depend>

control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+5-3
Original file line numberDiff line numberDiff line change
@@ -38,9 +38,11 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node)
3838
// parameters timer
3939
m_longitudinal_ctrl_period = node.get_parameter("ctrl_period").as_double();
4040

41-
m_wheel_base = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo().wheel_base_m;
42-
m_vehicle_width = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo().vehicle_width_m;
43-
m_front_overhang = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo().front_overhang_m;
41+
m_wheel_base = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo().wheel_base_m;
42+
m_vehicle_width =
43+
autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo().vehicle_width_m;
44+
m_front_overhang =
45+
autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo().front_overhang_m;
4446

4547
// parameters for delay compensation
4648
m_delay_compensation_time = node.declare_parameter<double>("delay_compensation_time"); // [s]

control/autoware_vehicle_cmd_gate/launch/vehicle_cmd_gate.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
<arg name="check_external_emergency_heartbeat" default="true"/>
44

55
<!-- vehicle info -->
6-
<arg name="vehicle_info_param_file" default="$(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml"/>
6+
<arg name="vehicle_info_param_file" default="$(find-pkg-share autoware_vehicle_info_utils)/config/vehicle_info.param.yaml"/>
77

88
<node pkg="autoware_vehicle_cmd_gate" exec="vehicle_cmd_gate_exe" name="vehicle_cmd_gate" output="screen">
99
<remap from="input/steering" to="/vehicle/status/steering_status"/>

control/autoware_vehicle_cmd_gate/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
<depend>autoware_adapi_v1_msgs</depend>
1919
<depend>autoware_control_msgs</depend>
20+
<depend>autoware_vehicle_info_utils</depend>
2021
<depend>autoware_vehicle_msgs</depend>
2122
<depend>component_interface_specs</depend>
2223
<depend>component_interface_utils</depend>
@@ -33,7 +34,6 @@
3334
<depend>tier4_external_api_msgs</depend>
3435
<depend>tier4_system_msgs</depend>
3536
<depend>tier4_vehicle_msgs</depend>
36-
<depend>vehicle_info_util</depend>
3737
<depend>visualization_msgs</depend>
3838

3939
<exec_depend>rosidl_default_runtime</exec_depend>

control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -170,7 +170,7 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
170170
declare_parameter<double>("filter_activated_velocity_threshold");
171171

172172
// Vehicle Parameter
173-
const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
173+
const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo();
174174
{
175175
VehicleCmdFilterParam p;
176176
p.wheel_base = vehicle_info.wheel_base_m;
@@ -276,7 +276,7 @@ rcl_interfaces::msg::SetParametersResult VehicleCmdGate::onParameter(
276276
parameters, "filter_activated_velocity_threshold", filter_activated_velocity_threshold_);
277277

278278
// Vehicle Parameter
279-
const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo();
279+
const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo();
280280
{
281281
VehicleCmdFilterParam p = filter_.getParam();
282282
p.wheel_base = vehicle_info.wheel_base_m;

control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -21,11 +21,11 @@
2121
#include "vehicle_cmd_filter.hpp"
2222

2323
#include <autoware_vehicle_cmd_gate/msg/is_filter_activated.hpp>
24+
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
2425
#include <diagnostic_updater/diagnostic_updater.hpp>
2526
#include <motion_utils/vehicle/vehicle_state_checker.hpp>
2627
#include <rclcpp/rclcpp.hpp>
2728
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
28-
#include <vehicle_info_util/vehicle_info_util.hpp>
2929

3030
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
3131
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>

control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -371,7 +371,7 @@ std::shared_ptr<VehicleCmdGate> generateNode()
371371
const auto vehicle_cmd_gate_dir =
372372
ament_index_cpp::get_package_share_directory("autoware_vehicle_cmd_gate");
373373
const auto vehicle_info_util_dir =
374-
ament_index_cpp::get_package_share_directory("vehicle_info_util");
374+
ament_index_cpp::get_package_share_directory("autoware_vehicle_info_utils");
375375

376376
node_options.arguments(
377377
{"--ros-args", "--params-file", vehicle_cmd_gate_dir + "/config/vehicle_cmd_gate.param.yaml",

control/control_performance_analysis/launch/control_performance_analysis.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
<arg name="output/driving_status_stamped" default="/control_performance/driving_status"/>
99

1010
<!-- vehicle info -->
11-
<arg name="vehicle_info_param_file" default="$(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml"/>
11+
<arg name="vehicle_info_param_file" default="$(find-pkg-share autoware_vehicle_info_utils)/config/vehicle_info.param.yaml"/>
1212

1313
<node pkg="control_performance_analysis" exec="control_performance_analysis_exe" name="control_performance_analysis_exe" output="screen">
1414
<param from="$(var control_performance_analysis_param_path)"/>

control/control_performance_analysis/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626

2727
<depend>autoware_control_msgs</depend>
2828
<depend>autoware_planning_msgs</depend>
29+
<depend>autoware_vehicle_info_utils</depend>
2930
<depend>autoware_vehicle_msgs</depend>
3031
<depend>geometry_msgs</depend>
3132
<depend>libboost-dev</depend>
@@ -41,7 +42,6 @@
4142
<depend>tf2_ros</depend>
4243
<depend>tier4_autoware_utils</depend>
4344
<depend>tier4_debug_msgs</depend>
44-
<depend>vehicle_info_util</depend>
4545
<exec_depend>builtin_interfaces</exec_depend>
4646
<exec_depend>global_parameter_loader</exec_depend>
4747
<exec_depend>rosidl_default_runtime</exec_depend>

0 commit comments

Comments
 (0)