Skip to content

Commit

Permalink
refactor(vehicle_info_utils)!: prefix package and namespace with auto…
Browse files Browse the repository at this point in the history
…ware (#7353)

* chore(autoware_vehicle_info_utils): rename header

Signed-off-by: satoshi-ota <[email protected]>

* chore(bpp-common): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(path_optimizer): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(velocity_smoother): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(bvp-common): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(static_centerline_generator): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(obstacle_cruise_planner): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(obstacle_velocity_limiter): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(mission_planner): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(obstacle_stop_planner): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(planning_validator): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(surround_obstacle_checker): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(goal_planner): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(start_planner): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(control_performance_analysis): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(lane_departure_checker): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(predicted_path_checker): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(vehicle_cmd_gate): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(obstacle_collision_checker): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(operation_mode_transition_manager): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(mpc): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(control): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(common): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(perception): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(evaluator): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(freespace): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(planning): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(vehicle): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(simulator): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(launch): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(system): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* chore(sensing): vehicle info

Signed-off-by: satoshi-ota <[email protected]>

* fix(autoware_joy_controller): remove unused deps

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota authored Jun 10, 2024
1 parent badc3e7 commit ed60229
Show file tree
Hide file tree
Showing 194 changed files with 350 additions and 338 deletions.
3 changes: 2 additions & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -248,6 +248,7 @@ vehicle/accel_brake_map_calibrator/** [email protected] takeshi.miura@tier4.
vehicle/autoware_steer_offset_estimator/** [email protected]
vehicle/external_cmd_converter/** [email protected]
vehicle/raw_vehicle_cmd_converter/** [email protected] [email protected] [email protected]
vehicle/vehicle_info_util/** [email protected] [email protected] [email protected]
vehicle/autoware_steer_offset_estimator/** [email protected]
vehicle/autoware_vehicle_info_utils/** [email protected] [email protected] [email protected]

### Copied from .github/CODEOWNERS-manual ###
Original file line number Diff line number Diff line change
Expand Up @@ -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"]
Expand Down
2 changes: 1 addition & 1 deletion common/global_parameter_loader/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<exec_depend>vehicle_info_util</exec_depend>
<exec_depend>autoware_vehicle_info_utils</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_localization_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_vehicle_info_utils</depend>
<depend>geometry_msgs</depend>
<depend>libqt5-core</depend>
<depend>libqt5-gui</depend>
Expand All @@ -20,7 +21,6 @@
<depend>rviz_common</depend>
<depend>rviz_default_plugins</depend>
<depend>tf2_ros</depend>
<depend>vehicle_info_util</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ void PoseHistoryFootprint::updateFootprint()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef POSE_HISTORY_FOOTPRINT__DISPLAY_HPP_
#define POSE_HISTORY_FOOTPRINT__DISPLAY_HPP_

#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rviz_common/message_filter_display.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <geometry_msgs/msg/pose_stamped.hpp>

Expand All @@ -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<geometry_msgs::msg::PoseStamped>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_
#define TIER4_PLANNING_RVIZ_PLUGIN__PATH__DISPLAY_BASE_HPP_

#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rviz_common/display_context.hpp>
#include <rviz_common/frame_manager_iface.hpp>
Expand All @@ -25,7 +26,6 @@
#include <rviz_common/properties/parse_color.hpp>
#include <rviz_common/validate_floats.hpp>
#include <rviz_rendering/objects/movable_text.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_planning_msgs/msg/path.hpp>

Expand Down Expand Up @@ -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 <typename T>
class AutowarePathBaseDisplay : public rviz_common::MessageFilterDisplay<T>
{
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_planning_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_planning_msgs</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>libqt5-core</depend>
<depend>libqt5-gui</depend>
<depend>libqt5-widgets</depend>
Expand All @@ -25,7 +26,6 @@
<depend>tf2_ros</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_planning_msgs</depend>
<depend>vehicle_info_util</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
6 changes: 3 additions & 3 deletions common/tier4_planning_rviz_plugin/src/path/display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ void AutowarePathWithLaneIdDisplay::preProcessMessageDetail()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
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(
Expand Down Expand Up @@ -107,7 +107,7 @@ void AutowarePathDisplay::preProcessMessageDetail()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
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(
Expand All @@ -124,7 +124,7 @@ void AutowareTrajectoryDisplay::preProcessMessageDetail()
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,13 @@
#ifndef AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_
#define AUTOWARE_AUTONOMOUS_EMERGENCY_BRAKING__NODE_HPP_

#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <motion_utils/trajectory/trajectory.hpp>
#include <pcl_ros/transforms.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/polling_subscriber.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <autoware_system_msgs/msg/autoware_state.hpp>
Expand Down Expand Up @@ -59,11 +59,11 @@ using nav_msgs::msg::Odometry;
using sensor_msgs::msg::Imu;
using sensor_msgs::msg::PointCloud2;
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
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<geometry_msgs::msg::Pose>;
Expand Down
2 changes: 1 addition & 1 deletion control/autoware_autonomous_emergency_braking/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<depend>autoware_control_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_system_msgs</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>diagnostic_updater</depend>
<depend>geometry_msgs</depend>
Expand All @@ -34,7 +35,6 @@
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_autoware_utils</depend>
<depend>vehicle_info_util</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down
4 changes: 2 additions & 2 deletions control/autoware_autonomous_emergency_braking/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion control/autoware_mpc_lateral_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

<depend>autoware_control_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>diagnostic_msgs</depend>
<depend>diagnostic_updater</depend>
Expand All @@ -35,7 +36,6 @@
<depend>tier4_autoware_utils</depend>
<depend>tier4_debug_msgs</depend>
<depend>trajectory_follower_base</depend>
<depend>vehicle_info_util</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <algorithm>
#include <deque>
Expand Down Expand Up @@ -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<double>(M_PI) / 180.0;
m_mpc->m_steer_lim = vehicle_info.max_steer_angle_rad;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,14 @@
#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"
#include "tf2_ros/buffer.h"
#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 <Eigen/Core>
#include <Eigen/Geometry>
Expand Down
2 changes: 1 addition & 1 deletion control/autoware_pid_longitudinal_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>diagnostic_msgs</depend>
<depend>diagnostic_updater</depend>
Expand All @@ -36,7 +37,6 @@
<depend>tier4_autoware_utils</depend>
<depend>tier4_debug_msgs</depend>
<depend>trajectory_follower_base</depend>
<depend>vehicle_info_util</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<double>("delay_compensation_time"); // [s]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="check_external_emergency_heartbeat" default="true"/>

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

<node pkg="autoware_vehicle_cmd_gate" exec="vehicle_cmd_gate_exe" name="vehicle_cmd_gate" output="screen">
<remap from="input/steering" to="/vehicle/status/steering_status"/>
Expand Down
2 changes: 1 addition & 1 deletion control/autoware_vehicle_cmd_gate/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>component_interface_specs</depend>
<depend>component_interface_utils</depend>
Expand All @@ -33,7 +34,6 @@
<depend>tier4_external_api_msgs</depend>
<depend>tier4_system_msgs</depend>
<depend>tier4_vehicle_msgs</depend>
<depend>vehicle_info_util</depend>
<depend>visualization_msgs</depend>

<exec_depend>rosidl_default_runtime</exec_depend>
Expand Down
4 changes: 2 additions & 2 deletions control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
declare_parameter<double>("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;
Expand Down Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,11 @@
#include "vehicle_cmd_filter.hpp"

#include <autoware_vehicle_cmd_gate/msg/is_filter_activated.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <diagnostic_updater/diagnostic_updater.hpp>
#include <motion_utils/vehicle/vehicle_state_checker.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/published_time_publisher.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -371,7 +371,7 @@ std::shared_ptr<VehicleCmdGate> 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",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
<arg name="output/driving_status_stamped" default="/control_performance/driving_status"/>

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

<node pkg="control_performance_analysis" exec="control_performance_analysis_exe" name="control_performance_analysis_exe" output="screen">
<param from="$(var control_performance_analysis_param_path)"/>
Expand Down
2 changes: 1 addition & 1 deletion control/control_performance_analysis/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@

<depend>autoware_control_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>geometry_msgs</depend>
<depend>libboost-dev</depend>
Expand All @@ -41,7 +42,6 @@
<depend>tf2_ros</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_debug_msgs</depend>
<depend>vehicle_info_util</depend>
<exec_depend>builtin_interfaces</exec_depend>
<exec_depend>global_parameter_loader</exec_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
Expand Down
Loading

0 comments on commit ed60229

Please sign in to comment.