Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_raw_vehicle_cmd_converter)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_raw_vehicle_cmd_converter #9924

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,10 @@

#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
#include <autoware_control_msgs/msg/control.hpp>
#include <autoware_internal_debug_msgs/msg/float32_multi_array_stamped.hpp>
#include <autoware_vehicle_msgs/msg/steering_report.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <tier4_debug_msgs/msg/float32_multi_array_stamped.hpp>
#include <tier4_vehicle_msgs/msg/actuation_command_stamped.hpp>
#include <tier4_vehicle_msgs/msg/actuation_status_stamped.hpp>

Expand All @@ -42,7 +42,7 @@
namespace autoware::raw_vehicle_cmd_converter
{
using Control = autoware_control_msgs::msg::Control;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using autoware_internal_debug_msgs::msg::Float32MultiArrayStamped;
using tier4_vehicle_msgs::msg::ActuationCommandStamped;
using tier4_vehicle_msgs::msg::ActuationStatusStamped;
using TwistStamped = geometry_msgs::msg::TwistStamped;
Expand Down
2 changes: 1 addition & 1 deletion vehicle/autoware_raw_vehicle_cmd_converter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,13 +23,13 @@

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_control_msgs</depend>
<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_interpolation</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>geometry_msgs</depend>
<depend>nav_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_vehicle_msgs</depend>

<exec_depend>rclpy</exec_depend>
Expand Down
2 changes: 1 addition & 1 deletion vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -245,7 +245,7 @@ double RawVehicleCommandConverterNode::calculateSteerFromMap(
debug_steer_.setValues(DebugValues::TYPE::ERROR_P, pid_errors.at(0));
debug_steer_.setValues(DebugValues::TYPE::ERROR_I, pid_errors.at(1));
debug_steer_.setValues(DebugValues::TYPE::ERROR_D, pid_errors.at(2));
tier4_debug_msgs::msg::Float32MultiArrayStamped msg{};
autoware_internal_debug_msgs::msg::Float32MultiArrayStamped msg{};
for (const auto & v : debug_steer_.getValues()) {
msg.data.push_back(v);
}
Expand Down
Loading