diff --git a/autoware_iv_external_api_adaptor/package.xml b/autoware_iv_external_api_adaptor/package.xml
index 1e0a952..508da09 100644
--- a/autoware_iv_external_api_adaptor/package.xml
+++ b/autoware_iv_external_api_adaptor/package.xml
@@ -11,10 +11,10 @@
autoware_cmake
autoware_ad_api_specs
- autoware_auto_control_msgs
- autoware_auto_system_msgs
- autoware_auto_vehicle_msgs
+ autoware_control_msgs
autoware_external_api_msgs
+ autoware_system_msgs
+ autoware_vehicle_msgs
component_interface_specs
component_interface_utils
nlohmann-json-dev
diff --git a/autoware_iv_external_api_adaptor/src/engage.cpp b/autoware_iv_external_api_adaptor/src/engage.cpp
index cbc5276..de123d3 100644
--- a/autoware_iv_external_api_adaptor/src/engage.cpp
+++ b/autoware_iv_external_api_adaptor/src/engage.cpp
@@ -35,9 +35,9 @@ Engage::Engage(const rclcpp::NodeOptions & options) : Node("external_api_engage"
"/api/autoware/set/operator", rmw_qos_profile_services_default);
pub_engage_status_ = create_publisher(
"/api/external/get/engage", rclcpp::QoS(1));
- sub_engage_status_ = create_subscription(
+ sub_engage_status_ = create_subscription(
"/api/autoware/get/engage", rclcpp::QoS(1), std::bind(&Engage::onEngageStatus, this, _1));
- sub_autoware_state_ = create_subscription(
+ sub_autoware_state_ = create_subscription(
"/autoware/state", rclcpp::QoS(1), std::bind(&Engage::onAutowareState, this, _1));
waiting_for_engage_ = false;
@@ -78,7 +78,7 @@ void Engage::setEngage(
response->status = resp->status;
}
-void Engage::onEngageStatus(const autoware_auto_vehicle_msgs::msg::Engage::SharedPtr message)
+void Engage::onEngageStatus(const autoware_vehicle_msgs::msg::Engage::SharedPtr message)
{
auto msg = tier4_external_api_msgs::build()
.stamp(message->stamp)
@@ -86,9 +86,9 @@ void Engage::onEngageStatus(const autoware_auto_vehicle_msgs::msg::Engage::Share
pub_engage_status_->publish(msg);
}
-void Engage::onAutowareState(const autoware_auto_system_msgs::msg::AutowareState::SharedPtr message)
+void Engage::onAutowareState(const autoware_system_msgs::msg::AutowareState::SharedPtr message)
{
- using autoware_auto_system_msgs::msg::AutowareState;
+ using autoware_system_msgs::msg::AutowareState;
waiting_for_engage_ = (message->state == AutowareState::WAITING_FOR_ENGAGE);
driving_ = (message->state == AutowareState::DRIVING);
}
diff --git a/autoware_iv_external_api_adaptor/src/engage.hpp b/autoware_iv_external_api_adaptor/src/engage.hpp
index 8a22dfd..0a7a174 100644
--- a/autoware_iv_external_api_adaptor/src/engage.hpp
+++ b/autoware_iv_external_api_adaptor/src/engage.hpp
@@ -18,8 +18,8 @@
#include "rclcpp/rclcpp.hpp"
#include "tier4_api_utils/tier4_api_utils.hpp"
-#include "autoware_auto_system_msgs/msg/autoware_state.hpp"
-#include "autoware_auto_vehicle_msgs/msg/engage.hpp"
+#include "autoware_system_msgs/msg/autoware_state.hpp"
+#include "autoware_vehicle_msgs/msg/engage.hpp"
#include "tier4_external_api_msgs/msg/engage_status.hpp"
#include "tier4_external_api_msgs/srv/engage.hpp"
#include "tier4_external_api_msgs/srv/set_operator.hpp"
@@ -36,8 +36,8 @@ class Engage : public rclcpp::Node
using ExternalEngage = tier4_external_api_msgs::srv::Engage;
using ExternalEngageStatus = tier4_external_api_msgs::msg::EngageStatus;
using SetOperator = tier4_external_api_msgs::srv::SetOperator;
- using VehicleEngageStatus = autoware_auto_vehicle_msgs::msg::Engage;
- using AutowareState = autoware_auto_system_msgs::msg::AutowareState;
+ using VehicleEngageStatus = autoware_vehicle_msgs::msg::Engage;
+ using AutowareState = autoware_system_msgs::msg::AutowareState;
// ros interface
rclcpp::CallbackGroup::SharedPtr group_;
@@ -57,8 +57,8 @@ class Engage : public rclcpp::Node
void setEngage(
const tier4_external_api_msgs::srv::Engage::Request::SharedPtr request,
const tier4_external_api_msgs::srv::Engage::Response::SharedPtr response);
- void onEngageStatus(const autoware_auto_vehicle_msgs::msg::Engage::SharedPtr message);
- void onAutowareState(const autoware_auto_system_msgs::msg::AutowareState::SharedPtr message);
+ void onEngageStatus(const autoware_vehicle_msgs::msg::Engage::SharedPtr message);
+ void onAutowareState(const autoware_system_msgs::msg::AutowareState::SharedPtr message);
};
} // namespace external_api
diff --git a/autoware_iv_external_api_adaptor/src/route.hpp b/autoware_iv_external_api_adaptor/src/route.hpp
index 817bc6f..fe32e19 100644
--- a/autoware_iv_external_api_adaptor/src/route.hpp
+++ b/autoware_iv_external_api_adaptor/src/route.hpp
@@ -20,7 +20,7 @@
#include "rclcpp/rclcpp.hpp"
#include "tier4_api_utils/tier4_api_utils.hpp"
-#include "autoware_auto_system_msgs/msg/autoware_state.hpp"
+#include "autoware_system_msgs/msg/autoware_state.hpp"
#include "tier4_external_api_msgs/msg/route.hpp"
#include "tier4_external_api_msgs/srv/clear_route.hpp"
#include "tier4_external_api_msgs/srv/set_route.hpp"
@@ -37,7 +37,7 @@ class Route : public rclcpp::Node
using SetRoute = tier4_external_api_msgs::srv::SetRoute;
using ClearRoute = tier4_external_api_msgs::srv::ClearRoute;
using RouteMsg = tier4_external_api_msgs::msg::Route;
- using AutowareState = autoware_auto_system_msgs::msg::AutowareState;
+ using AutowareState = autoware_system_msgs::msg::AutowareState;
// ros interface
rclcpp::CallbackGroup::SharedPtr group_;
diff --git a/autoware_iv_external_api_adaptor/src/vehicle_status.cpp b/autoware_iv_external_api_adaptor/src/vehicle_status.cpp
index 121f0be..a84850d 100644
--- a/autoware_iv_external_api_adaptor/src/vehicle_status.cpp
+++ b/autoware_iv_external_api_adaptor/src/vehicle_status.cpp
@@ -80,40 +80,40 @@ VehicleStatus::VehicleStatus(const rclcpp::NodeOptions & options)
"/api/external/get/vehicle/status", rclcpp::QoS(1));
timer_ = rclcpp::create_timer(this, get_clock(), 200ms, std::bind(&VehicleStatus::onTimer, this));
- sub_velocity_ = create_subscription(
+ sub_velocity_ = create_subscription(
"/vehicle/status/velocity_status", rclcpp::QoS(1),
- [this](const autoware_auto_vehicle_msgs::msg::VelocityReport::ConstSharedPtr msg) {
+ [this](const autoware_vehicle_msgs::msg::VelocityReport::ConstSharedPtr msg) {
velocity_ = msg;
});
- sub_steering_ = create_subscription(
+ sub_steering_ = create_subscription(
"/vehicle/status/steering_status", rclcpp::QoS(1),
- [this](const autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr msg) {
+ [this](const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr msg) {
steering_ = msg;
});
- sub_turn_indicators_ = create_subscription(
+ sub_turn_indicators_ = create_subscription(
"/vehicle/status/turn_indicators_status", rclcpp::QoS(1),
- [this](const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr msg) {
+ [this](const autoware_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr msg) {
turn_indicators_ = msg;
});
- sub_hazard_lights_ = create_subscription(
+ sub_hazard_lights_ = create_subscription(
"/vehicle/status/hazard_lights_status", rclcpp::QoS(1),
- [this](const autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr msg) {
+ [this](const autoware_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr msg) {
hazard_lights_ = msg;
});
- sub_gear_shift_ = create_subscription(
+ sub_gear_shift_ = create_subscription(
"/vehicle/status/gear_status", rclcpp::QoS(1),
- [this](const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg) {
+ [this](const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr msg) {
gear_shift_ = msg;
});
pub_cmd_ = create_publisher(
"/api/external/get/command/selected/vehicle", rclcpp::QoS(1));
- sub_cmd_ = create_subscription(
+ sub_cmd_ = create_subscription(
"/control/command/control_cmd", rclcpp::QoS(1),
- [this](const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg) {
+ [this](const autoware_control_msgs::msg::Control::ConstSharedPtr msg) {
tier4_external_api_msgs::msg::VehicleCommandStamped cmd;
cmd.stamp = msg->stamp;
- cmd.command.velocity = msg->longitudinal.speed;
+ cmd.command.velocity = msg->longitudinal.velocity;
cmd.command.acceleration = msg->longitudinal.acceleration;
pub_cmd_->publish(cmd);
});
diff --git a/autoware_iv_external_api_adaptor/src/vehicle_status.hpp b/autoware_iv_external_api_adaptor/src/vehicle_status.hpp
index e69ddbc..247cb2d 100644
--- a/autoware_iv_external_api_adaptor/src/vehicle_status.hpp
+++ b/autoware_iv_external_api_adaptor/src/vehicle_status.hpp
@@ -18,12 +18,12 @@
#include "rclcpp/rclcpp.hpp"
#include "tier4_api_utils/tier4_api_utils.hpp"
-#include "autoware_auto_control_msgs/msg/ackermann_control_command.hpp"
-#include "autoware_auto_vehicle_msgs/msg/gear_report.hpp"
-#include "autoware_auto_vehicle_msgs/msg/hazard_lights_report.hpp"
-#include "autoware_auto_vehicle_msgs/msg/steering_report.hpp"
-#include "autoware_auto_vehicle_msgs/msg/turn_indicators_report.hpp"
-#include "autoware_auto_vehicle_msgs/msg/velocity_report.hpp"
+#include "autoware_control_msgs/msg/control.hpp"
+#include "autoware_vehicle_msgs/msg/gear_report.hpp"
+#include "autoware_vehicle_msgs/msg/hazard_lights_report.hpp"
+#include "autoware_vehicle_msgs/msg/steering_report.hpp"
+#include "autoware_vehicle_msgs/msg/turn_indicators_report.hpp"
+#include "autoware_vehicle_msgs/msg/velocity_report.hpp"
#include "tier4_external_api_msgs/msg/vehicle_command_stamped.hpp"
#include "tier4_external_api_msgs/msg/vehicle_status_stamped.hpp"
@@ -39,28 +39,27 @@ class VehicleStatus : public rclcpp::Node
// ros interface for vehicle status
rclcpp::Publisher::SharedPtr pub_status_;
rclcpp::TimerBase::SharedPtr timer_;
- rclcpp::Subscription::SharedPtr sub_velocity_;
- rclcpp::Subscription::SharedPtr sub_steering_;
- rclcpp::Subscription::SharedPtr
+ rclcpp::Subscription::SharedPtr sub_velocity_;
+ rclcpp::Subscription::SharedPtr sub_steering_;
+ rclcpp::Subscription::SharedPtr
sub_turn_indicators_;
- rclcpp::Subscription::SharedPtr
+ rclcpp::Subscription::SharedPtr
sub_hazard_lights_;
- rclcpp::Subscription::SharedPtr sub_gear_shift_;
+ rclcpp::Subscription::SharedPtr sub_gear_shift_;
// ros interface for vehicle command
rclcpp::Publisher::SharedPtr pub_cmd_;
- rclcpp::Subscription::SharedPtr
- sub_cmd_;
+ rclcpp::Subscription::SharedPtr sub_cmd_;
// ros callback
void onTimer();
// vehicle status
- autoware_auto_vehicle_msgs::msg::VelocityReport::ConstSharedPtr velocity_;
- autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr steering_;
- autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr turn_indicators_;
- autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr hazard_lights_;
- autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr gear_shift_;
+ autoware_vehicle_msgs::msg::VelocityReport::ConstSharedPtr velocity_;
+ autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr steering_;
+ autoware_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr turn_indicators_;
+ autoware_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr hazard_lights_;
+ autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr gear_shift_;
};
} // namespace external_api
diff --git a/autoware_iv_internal_api_adaptor/launch/internal_api_relay.launch.xml b/autoware_iv_internal_api_adaptor/launch/internal_api_relay.launch.xml
index e850fb3..d49b50c 100644
--- a/autoware_iv_internal_api_adaptor/launch/internal_api_relay.launch.xml
+++ b/autoware_iv_internal_api_adaptor/launch/internal_api_relay.launch.xml
@@ -4,7 +4,7 @@
-
+
diff --git a/autoware_iv_internal_api_adaptor/package.xml b/autoware_iv_internal_api_adaptor/package.xml
index 41e21d3..df10b0a 100644
--- a/autoware_iv_internal_api_adaptor/package.xml
+++ b/autoware_iv_internal_api_adaptor/package.xml
@@ -11,10 +11,10 @@
autoware_cmake
autoware_adapi_v1_msgs
- autoware_auto_perception_msgs
- autoware_auto_planning_msgs
- autoware_auto_system_msgs
- autoware_auto_vehicle_msgs
+ autoware_perception_msgs
+ autoware_planning_msgs
+ autoware_system_msgs
+ autoware_vehicle_msgs
geometry_msgs
rclcpp
rclcpp_components
diff --git a/autoware_iv_internal_api_adaptor/src/iv_msgs.hpp b/autoware_iv_internal_api_adaptor/src/iv_msgs.hpp
index 35558f7..5d41135 100644
--- a/autoware_iv_internal_api_adaptor/src/iv_msgs.hpp
+++ b/autoware_iv_internal_api_adaptor/src/iv_msgs.hpp
@@ -18,10 +18,10 @@
#include
#include
-#include
-#include
-#include
-#include
+#include
+#include
+#include
+#include
#include
#include
#include
@@ -35,22 +35,22 @@ class IVMsgs : public rclcpp::Node
private:
using EmergencyStateAuto = autoware_adapi_v1_msgs::msg::MrmState;
- using AutowareStateAuto = autoware_auto_system_msgs::msg::AutowareState;
+ using AutowareStateAuto = autoware_system_msgs::msg::AutowareState;
using AutowareStateIV = tier4_system_msgs::msg::AutowareState;
rclcpp::Subscription::SharedPtr sub_emergency_;
rclcpp::Subscription::SharedPtr sub_state_;
rclcpp::Publisher::SharedPtr pub_state_;
- using ControlModeAuto = autoware_auto_vehicle_msgs::msg::ControlModeReport;
+ using ControlModeAuto = autoware_vehicle_msgs::msg::ControlModeReport;
rclcpp::Subscription::SharedPtr sub_control_mode_;
rclcpp::Publisher::SharedPtr pub_control_mode_;
- using TrajectoryAuto = autoware_auto_planning_msgs::msg::Trajectory;
+ using TrajectoryAuto = autoware_planning_msgs::msg::Trajectory;
using TrajectoryIV = tier4_planning_msgs::msg::Trajectory;
rclcpp::Subscription::SharedPtr sub_trajectory_;
rclcpp::Publisher::SharedPtr pub_trajectory_;
- using TrackedObjectsAuto = autoware_auto_perception_msgs::msg::TrackedObjects;
+ using TrackedObjectsAuto = autoware_perception_msgs::msg::TrackedObjects;
using DynamicObjectsIV = tier4_perception_msgs::msg::DynamicObjectArray;
rclcpp::Subscription::SharedPtr sub_tracked_objects_;
rclcpp::Publisher::SharedPtr pub_dynamic_objects_;
diff --git a/autoware_iv_internal_api_adaptor/src/operator.cpp b/autoware_iv_internal_api_adaptor/src/operator.cpp
index ce0e47a..7556d8a 100644
--- a/autoware_iv_internal_api_adaptor/src/operator.cpp
+++ b/autoware_iv_internal_api_adaptor/src/operator.cpp
@@ -52,10 +52,9 @@ Operator::Operator(const rclcpp::NodeOptions & options) : Node("external_api_ope
std::bind(&Operator::onExternalSelect, this, _1));
sub_gate_mode_ = create_subscription(
"/control/current_gate_mode", rclcpp::QoS(1), std::bind(&Operator::onGateMode, this, _1));
- sub_vehicle_control_mode_ =
- create_subscription(
- "/vehicle/status/control_mode", rclcpp::QoS(1),
- std::bind(&Operator::onVehicleControlMode, this, _1));
+ sub_vehicle_control_mode_ = create_subscription(
+ "/vehicle/status/control_mode", rclcpp::QoS(1),
+ std::bind(&Operator::onVehicleControlMode, this, _1));
sub_emergency_ = create_subscription(
"/api/autoware/get/emergency", 10, std::bind(&Operator::onEmergencyStatus, this, _1));
@@ -126,7 +125,7 @@ void Operator::onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPt
}
void Operator::onVehicleControlMode(
- const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr message)
+ const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr message)
{
vehicle_control_mode_ = message;
}
@@ -151,7 +150,7 @@ void Operator::publishOperator()
return;
}
- if (vehicle_control_mode_->mode == autoware_auto_vehicle_msgs::msg::ControlModeReport::MANUAL) {
+ if (vehicle_control_mode_->mode == autoware_vehicle_msgs::msg::ControlModeReport::MANUAL) {
pub_operator_->publish(build().mode(OperatorMsg::DRIVER));
return;
}
diff --git a/autoware_iv_internal_api_adaptor/src/operator.hpp b/autoware_iv_internal_api_adaptor/src/operator.hpp
index 2386f84..0c41bca 100644
--- a/autoware_iv_internal_api_adaptor/src/operator.hpp
+++ b/autoware_iv_internal_api_adaptor/src/operator.hpp
@@ -18,7 +18,7 @@
#include
#include
-#include
+#include
#include
#include
#include
@@ -44,7 +44,7 @@ class Operator : public rclcpp::Node
using ExternalCommandSelect = tier4_control_msgs::srv::ExternalCommandSelect;
using ExternalCommandSelectorMode = tier4_control_msgs::msg::ExternalCommandSelectorMode;
using GateMode = tier4_control_msgs::msg::GateMode;
- using ControlModeReport = autoware_auto_vehicle_msgs::msg::ControlModeReport;
+ using ControlModeReport = autoware_vehicle_msgs::msg::ControlModeReport;
using ChangeAutowareControl = tier4_system_msgs::srv::ChangeAutowareControl;
using ResponseStatus = tier4_external_api_msgs::msg::ResponseStatus;
@@ -74,14 +74,14 @@ class Operator : public rclcpp::Node
const tier4_control_msgs::msg::ExternalCommandSelectorMode::ConstSharedPtr message);
void onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr message);
void onVehicleControlMode(
- const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr message);
+ const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr message);
void onEmergencyStatus(const tier4_external_api_msgs::msg::Emergency::ConstSharedPtr msg);
void onTimer();
// class field
tier4_control_msgs::msg::ExternalCommandSelectorMode::ConstSharedPtr external_select_;
tier4_control_msgs::msg::GateMode::ConstSharedPtr gate_mode_;
- autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr vehicle_control_mode_;
+ autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr vehicle_control_mode_;
tier4_external_api_msgs::msg::Emergency::ConstSharedPtr emergency_status_;
bool send_engage_in_emergency_;
diff --git a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_state_publisher.hpp b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_state_publisher.hpp
index 47bb1e0..8c64d81 100644
--- a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_state_publisher.hpp
+++ b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_state_publisher.hpp
@@ -49,7 +49,7 @@ class AutowareIvAutowareStatePublisher
const tier4_system_msgs::msg::AutowareState::ConstSharedPtr & autoware_state_ptr,
tier4_api_msgs::msg::AwapiAutowareStatus * status);
void getControlModeInfo(
- const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr & control_mode_ptr,
+ const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr & control_mode_ptr,
tier4_api_msgs::msg::AwapiAutowareStatus * status);
void getGateModeInfo(
const tier4_control_msgs::msg::GateMode::ConstSharedPtr & gate_mode_ptr,
diff --git a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_util.hpp b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_util.hpp
index ebc089e..817da3d 100644
--- a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_util.hpp
+++ b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_autoware_util.hpp
@@ -18,15 +18,15 @@
#include
#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
#include
#include
#include
@@ -62,32 +62,32 @@ namespace autoware_api
struct AutowareInfo
{
std::shared_ptr current_pose_ptr;
- autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr steer_ptr;
- autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr vehicle_cmd_ptr;
- autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr turn_indicators_ptr;
- autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr hazard_lights_ptr;
+ autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr steer_ptr;
+ autoware_control_msgs::msg::Control::ConstSharedPtr vehicle_cmd_ptr;
+ autoware_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr turn_indicators_ptr;
+ autoware_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr hazard_lights_ptr;
nav_msgs::msg::Odometry::ConstSharedPtr odometry_ptr;
- autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr gear_ptr;
+ autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr gear_ptr;
tier4_vehicle_msgs::msg::BatteryStatus::ConstSharedPtr battery_ptr;
sensor_msgs::msg::NavSatFix::ConstSharedPtr nav_sat_ptr;
tier4_system_msgs::msg::AutowareState::ConstSharedPtr autoware_state_ptr;
- autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_ptr;
+ autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_ptr;
tier4_control_msgs::msg::GateMode::ConstSharedPtr gate_mode_ptr;
autoware_adapi_v1_msgs::msg::MrmState::ConstSharedPtr mrm_state_ptr;
- autoware_auto_system_msgs::msg::HazardStatusStamped::ConstSharedPtr hazard_status_ptr;
+ autoware_system_msgs::msg::HazardStatusStamped::ConstSharedPtr hazard_status_ptr;
tier4_planning_msgs::msg::StopReasonArray::ConstSharedPtr stop_reason_ptr;
tier4_v2x_msgs::msg::InfrastructureCommandArray::ConstSharedPtr v2x_command_ptr;
tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr v2x_state_ptr;
diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr diagnostic_ptr;
tier4_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr lane_change_available_ptr;
tier4_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr lane_change_ready_ptr;
- autoware_auto_planning_msgs::msg::Path::ConstSharedPtr lane_change_candidate_ptr;
+ autoware_planning_msgs::msg::Path::ConstSharedPtr lane_change_candidate_ptr;
tier4_planning_msgs::msg::IsAvoidancePossible::ConstSharedPtr obstacle_avoid_ready_ptr;
- autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr obstacle_avoid_candidate_ptr;
+ autoware_planning_msgs::msg::Trajectory::ConstSharedPtr obstacle_avoid_candidate_ptr;
tier4_api_msgs::msg::VelocityLimit::ConstSharedPtr max_velocity_ptr;
tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr current_max_velocity_ptr;
tier4_api_msgs::msg::StopCommand::ConstSharedPtr temporary_stop_ptr;
- autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr autoware_planning_traj_ptr;
+ autoware_planning_msgs::msg::Trajectory::ConstSharedPtr autoware_planning_traj_ptr;
};
template
@@ -120,11 +120,11 @@ double lowpass_filter(const double current_value, const double prev_value, const
namespace planning_util
{
bool calcClosestIndex(
- const autoware_auto_planning_msgs::msg::Trajectory & traj, const geometry_msgs::msg::Pose & pose,
+ const autoware_planning_msgs::msg::Trajectory & traj, const geometry_msgs::msg::Pose & pose,
size_t & output_closest_idx, const double dist_thr = 10.0, const double angle_thr = M_PI_4);
inline geometry_msgs::msg::Pose getPose(
- const autoware_auto_planning_msgs::msg::Trajectory & traj, const int idx)
+ const autoware_planning_msgs::msg::Trajectory & traj, const int idx)
{
return traj.points.at(idx).pose;
}
@@ -137,11 +137,11 @@ inline double calcDist2d(const geometry_msgs::msg::Point & a, const geometry_msg
double normalizeEulerAngle(double euler);
double calcArcLengthFromWayPoint(
- const autoware_auto_planning_msgs::msg::Trajectory & input_path, const size_t src_idx,
+ const autoware_planning_msgs::msg::Trajectory & input_path, const size_t src_idx,
const size_t dst_idx);
double calcDistanceAlongTrajectory(
- const autoware_auto_planning_msgs::msg::Trajectory & trajectory,
+ const autoware_planning_msgs::msg::Trajectory & trajectory,
const geometry_msgs::msg::Pose & current_pose, const geometry_msgs::msg::Pose & target_pose);
} // namespace planning_util
diff --git a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_awiv_adapter_core.hpp b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_awiv_adapter_core.hpp
index 9b426c8..6bf1001 100644
--- a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_awiv_adapter_core.hpp
+++ b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_awiv_adapter_core.hpp
@@ -27,14 +27,14 @@
#include
#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
#include
#include
#include
@@ -58,23 +58,21 @@ class AutowareIvAdapter : public rclcpp::Node
private:
// subscriber
- rclcpp::Subscription::SharedPtr sub_steer_;
- rclcpp::Subscription::SharedPtr
- sub_vehicle_cmd_;
- rclcpp::Subscription::SharedPtr
+ rclcpp::Subscription::SharedPtr sub_steer_;
+ rclcpp::Subscription::SharedPtr sub_vehicle_cmd_;
+ rclcpp::Subscription::SharedPtr
sub_turn_indicators_;
- rclcpp::Subscription::SharedPtr
+ rclcpp::Subscription::SharedPtr
sub_hazard_lights_;
rclcpp::Subscription::SharedPtr sub_odometry_;
- rclcpp::Subscription::SharedPtr sub_gear_;
+ rclcpp::Subscription::SharedPtr sub_gear_;
rclcpp::Subscription::SharedPtr sub_battery_;
rclcpp::Subscription::SharedPtr sub_nav_sat_;
rclcpp::Subscription::SharedPtr sub_autoware_state_;
- rclcpp::Subscription::SharedPtr
- sub_control_mode_;
+ rclcpp::Subscription::SharedPtr sub_control_mode_;
rclcpp::Subscription::SharedPtr sub_gate_mode_;
rclcpp::Subscription::SharedPtr sub_emergency_;
- rclcpp::Subscription::SharedPtr
+ rclcpp::Subscription::SharedPtr
sub_hazard_status_;
rclcpp::Subscription::SharedPtr sub_stop_reason_;
rclcpp::Subscription::SharedPtr sub_v2x_command_;
@@ -85,17 +83,16 @@ class AutowareIvAdapter : public rclcpp::Node
sub_lane_change_available_;
rclcpp::Subscription::SharedPtr
sub_lane_change_ready_;
- rclcpp::Subscription::SharedPtr
- sub_lane_change_candidate_;
+ rclcpp::Subscription::SharedPtr sub_lane_change_candidate_;
rclcpp::Subscription::SharedPtr
sub_obstacle_avoid_ready_;
- rclcpp::Subscription::SharedPtr
+ rclcpp::Subscription::SharedPtr
sub_obstacle_avoid_candidate_;
rclcpp::Subscription::SharedPtr sub_max_velocity_;
rclcpp::Subscription::SharedPtr
sub_current_max_velocity_;
rclcpp::Subscription::SharedPtr sub_temporary_stop_;
- rclcpp::Subscription::SharedPtr sub_autoware_traj_;
+ rclcpp::Subscription::SharedPtr sub_autoware_traj_;
// publisher
rclcpp::Publisher::SharedPtr pub_v2x_command_;
@@ -109,24 +106,23 @@ class AutowareIvAdapter : public rclcpp::Node
tf2_ros::TransformListener tf_listener_;
// callback function
- void callbackSteer(const autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr msg_ptr);
- void callbackVehicleCmd(
- const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg_ptr);
+ void callbackSteer(const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr msg_ptr);
+ void callbackVehicleCmd(const autoware_control_msgs::msg::Control::ConstSharedPtr msg_ptr);
void callbackTurnIndicators(
- const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr msg_ptr);
+ const autoware_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr msg_ptr);
void callbackHazardLights(
- const autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr msg_ptr);
+ const autoware_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr msg_ptr);
void callbackTwist(const nav_msgs::msg::Odometry::ConstSharedPtr msg_ptr);
- void callbackGear(const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg_ptr);
+ void callbackGear(const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr msg_ptr);
void callbackBattery(const tier4_vehicle_msgs::msg::BatteryStatus::ConstSharedPtr msg_ptr);
void callbackNavSat(const sensor_msgs::msg::NavSatFix::ConstSharedPtr msg_ptr);
void callbackAutowareState(const tier4_system_msgs::msg::AutowareState::ConstSharedPtr msg_ptr);
void callbackControlMode(
- const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg_ptr);
+ const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg_ptr);
void callbackGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg_ptr);
void callbackMrmState(const autoware_adapi_v1_msgs::msg::MrmState::ConstSharedPtr msg_ptr);
void callbackHazardStatus(
- const autoware_auto_system_msgs::msg::HazardStatusStamped::ConstSharedPtr msg_ptr);
+ const autoware_system_msgs::msg::HazardStatusStamped::ConstSharedPtr msg_ptr);
void callbackStopReason(const tier4_planning_msgs::msg::StopReasonArray::ConstSharedPtr msg_ptr);
void callbackV2XCommand(
const tier4_v2x_msgs::msg::InfrastructureCommandArray::ConstSharedPtr msg_ptr);
@@ -138,17 +134,17 @@ class AutowareIvAdapter : public rclcpp::Node
void callbackLaneChangeReady(
const tier4_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr msg_ptr);
void callbackLaneChangeCandidatePath(
- const autoware_auto_planning_msgs::msg::Path::ConstSharedPtr msg_ptr);
+ const autoware_planning_msgs::msg::Path::ConstSharedPtr msg_ptr);
void callbackLaneObstacleAvoidReady(
const tier4_planning_msgs::msg::IsAvoidancePossible::ConstSharedPtr msg_ptr);
void callbackLaneObstacleAvoidCandidatePath(
- const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr);
+ const autoware_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr);
void callbackMaxVelocity(const tier4_api_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr);
void callbackCurrentMaxVelocity(
const tier4_planning_msgs::msg::VelocityLimit::ConstSharedPtr msg_ptr);
void callbackTemporaryStop(const tier4_api_msgs::msg::StopCommand::ConstSharedPtr msg_ptr);
void callbackAutowareTrajectory(
- const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr);
+ const autoware_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr);
// timer function
void timerCallback();
diff --git a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_lane_change_state_publisher.hpp b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_lane_change_state_publisher.hpp
index d1ec3c5..adb87a5 100644
--- a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_lane_change_state_publisher.hpp
+++ b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_lane_change_state_publisher.hpp
@@ -43,7 +43,7 @@ class AutowareIvLaneChangeStatePublisher
const tier4_planning_msgs::msg::LaneChangeStatus::ConstSharedPtr & ready_ptr,
tier4_api_msgs::msg::LaneChangeStatus * status);
void getCandidatePathInfo(
- const autoware_auto_planning_msgs::msg::Path::ConstSharedPtr & path_ptr,
+ const autoware_planning_msgs::msg::Path::ConstSharedPtr & path_ptr,
tier4_api_msgs::msg::LaneChangeStatus * status);
};
diff --git a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_obstacle_avoidance_state_publisher.hpp b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_obstacle_avoidance_state_publisher.hpp
index 122faec..e54d5e3 100644
--- a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_obstacle_avoidance_state_publisher.hpp
+++ b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_obstacle_avoidance_state_publisher.hpp
@@ -40,7 +40,7 @@ class AutowareIvObstacleAvoidanceStatePublisher
const tier4_planning_msgs::msg::IsAvoidancePossible::ConstSharedPtr & ready_ptr,
tier4_api_msgs::msg::ObstacleAvoidanceStatus * status);
void getCandidatePathInfo(
- const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr & path_ptr,
+ const autoware_planning_msgs::msg::Trajectory::ConstSharedPtr & path_ptr,
tier4_api_msgs::msg::ObstacleAvoidanceStatus * status);
};
diff --git a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_vehicle_state_publisher.hpp b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_vehicle_state_publisher.hpp
index d8a1165..3e6901d 100644
--- a/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_vehicle_state_publisher.hpp
+++ b/awapi_awiv_adapter/include/awapi_awiv_adapter/awapi_vehicle_state_publisher.hpp
@@ -40,22 +40,20 @@ class AutowareIvVehicleStatePublisher
const std::shared_ptr & pose_ptr,
tier4_api_msgs::msg::AwapiVehicleStatus * status);
void getSteerInfo(
- const autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & steer_ptr,
+ const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & steer_ptr,
tier4_api_msgs::msg::AwapiVehicleStatus * status);
void getVehicleCmdInfo(
- const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr &
- vehicle_cmd_ptr,
+ const autoware_control_msgs::msg::Control::ConstSharedPtr & vehicle_cmd_ptr,
tier4_api_msgs::msg::AwapiVehicleStatus * status);
void getTurnSignalInfo(
- const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr &
- turn_indicators_ptr,
- const autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr & hazard_lights_ptr,
+ const autoware_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr & turn_indicators_ptr,
+ const autoware_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr & hazard_lights_ptr,
tier4_api_msgs::msg::AwapiVehicleStatus * status);
void getTwistInfo(
const nav_msgs::msg::Odometry::ConstSharedPtr & odometry_ptr,
tier4_api_msgs::msg::AwapiVehicleStatus * status);
void getGearInfo(
- const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr & gear_ptr,
+ const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr & gear_ptr,
tier4_api_msgs::msg::AwapiVehicleStatus * status);
void getBatteryInfo(
const tier4_vehicle_msgs::msg::BatteryStatus::ConstSharedPtr & battery_ptr,
@@ -69,7 +67,7 @@ class AutowareIvVehicleStatePublisher
// parameters
nav_msgs::msg::Odometry::ConstSharedPtr previous_odometry_ptr_;
- autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr previous_steer_ptr_;
+ autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr previous_steer_ptr_;
double prev_accel_;
double prev_steer_vel_;
diff --git a/awapi_awiv_adapter/package.xml b/awapi_awiv_adapter/package.xml
index 03045aa..b920dec 100644
--- a/awapi_awiv_adapter/package.xml
+++ b/awapi_awiv_adapter/package.xml
@@ -11,10 +11,10 @@
autoware_cmake
autoware_adapi_v1_msgs
- autoware_auto_control_msgs
- autoware_auto_planning_msgs
- autoware_auto_system_msgs
- autoware_auto_vehicle_msgs
+ autoware_control_msgs
+ autoware_planning_msgs
+ autoware_system_msgs
+ autoware_vehicle_msgs
diagnostic_msgs
geometry_msgs
nav_msgs
diff --git a/awapi_awiv_adapter/src/awapi_autoware_state_publisher.cpp b/awapi_awiv_adapter/src/awapi_autoware_state_publisher.cpp
index 11d68ac..bd0237b 100644
--- a/awapi_awiv_adapter/src/awapi_autoware_state_publisher.cpp
+++ b/awapi_awiv_adapter/src/awapi_autoware_state_publisher.cpp
@@ -72,7 +72,7 @@ void AutowareIvAutowareStatePublisher::getAutowareStateInfo(
}
void AutowareIvAutowareStatePublisher::getControlModeInfo(
- const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr & control_mode_ptr,
+ const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr & control_mode_ptr,
tier4_api_msgs::msg::AwapiAutowareStatus * status)
{
if (!control_mode_ptr) {
@@ -197,7 +197,7 @@ void AutowareIvAutowareStatePublisher::getDiagInfo(
void AutowareIvAutowareStatePublisher::getErrorDiagInfo(
const AutowareInfo & aw_info, tier4_api_msgs::msg::AwapiAutowareStatus * status)
{
- using autoware_auto_vehicle_msgs::msg::ControlModeReport;
+ using autoware_vehicle_msgs::msg::ControlModeReport;
using tier4_system_msgs::msg::AutowareState;
if (!aw_info.autoware_state_ptr) {
diff --git a/awapi_awiv_adapter/src/awapi_autoware_util.cpp b/awapi_awiv_adapter/src/awapi_autoware_util.cpp
index 830aeb2..9b4a763 100644
--- a/awapi_awiv_adapter/src/awapi_autoware_util.cpp
+++ b/awapi_awiv_adapter/src/awapi_autoware_util.cpp
@@ -26,7 +26,7 @@ double lowpass_filter(const double current_value, const double prev_value, const
namespace planning_util
{
bool calcClosestIndex(
- const autoware_auto_planning_msgs::msg::Trajectory & traj, const geometry_msgs::msg::Pose & pose,
+ const autoware_planning_msgs::msg::Trajectory & traj, const geometry_msgs::msg::Pose & pose,
size_t & output_closest_idx, const double dist_thr, const double angle_thr)
{
double dist_min = std::numeric_limits::max();
@@ -74,7 +74,7 @@ double normalizeEulerAngle(double euler)
}
double calcArcLengthFromWayPoint(
- const autoware_auto_planning_msgs::msg::Trajectory & input_path, const size_t src_idx,
+ const autoware_planning_msgs::msg::Trajectory & input_path, const size_t src_idx,
const size_t dst_idx)
{
double length = 0;
@@ -89,7 +89,7 @@ double calcArcLengthFromWayPoint(
}
double calcDistanceAlongTrajectory(
- const autoware_auto_planning_msgs::msg::Trajectory & trajectory,
+ const autoware_planning_msgs::msg::Trajectory & trajectory,
const geometry_msgs::msg::Pose & current_pose, const geometry_msgs::msg::Pose & target_pose)
{
size_t self_idx;
diff --git a/awapi_awiv_adapter/src/awapi_awiv_adapter_core.cpp b/awapi_awiv_adapter/src/awapi_awiv_adapter_core.cpp
index 18bcdc4..02ec938 100644
--- a/awapi_awiv_adapter/src/awapi_awiv_adapter_core.cpp
+++ b/awapi_awiv_adapter/src/awapi_awiv_adapter_core.cpp
@@ -58,21 +58,18 @@ AutowareIvAdapter::AutowareIvAdapter()
auto durable_qos = rclcpp::QoS{1}.transient_local();
- sub_steer_ = this->create_subscription(
+ sub_steer_ = this->create_subscription(
"input/steer", 1, std::bind(&AutowareIvAdapter::callbackSteer, this, _1));
- sub_vehicle_cmd_ =
- this->create_subscription(
- "input/vehicle_cmd", durable_qos,
- std::bind(&AutowareIvAdapter::callbackVehicleCmd, this, _1));
+ sub_vehicle_cmd_ = this->create_subscription(
+ "input/vehicle_cmd", durable_qos, std::bind(&AutowareIvAdapter::callbackVehicleCmd, this, _1));
sub_turn_indicators_ =
- this->create_subscription(
+ this->create_subscription(
"input/turn_indicators", 1, std::bind(&AutowareIvAdapter::callbackTurnIndicators, this, _1));
- sub_hazard_lights_ =
- this->create_subscription(
- "input/hazard_lights", 1, std::bind(&AutowareIvAdapter::callbackHazardLights, this, _1));
+ sub_hazard_lights_ = this->create_subscription(
+ "input/hazard_lights", 1, std::bind(&AutowareIvAdapter::callbackHazardLights, this, _1));
sub_odometry_ = this->create_subscription(
"input/odometry", 1, std::bind(&AutowareIvAdapter::callbackTwist, this, _1));
- sub_gear_ = this->create_subscription(
+ sub_gear_ = this->create_subscription(
"input/gear", 1, std::bind(&AutowareIvAdapter::callbackGear, this, _1));
sub_battery_ = this->create_subscription(
"input/battery", 1, std::bind(&AutowareIvAdapter::callbackBattery, this, _1));
@@ -80,15 +77,14 @@ AutowareIvAdapter::AutowareIvAdapter()
"input/nav_sat", 1, std::bind(&AutowareIvAdapter::callbackNavSat, this, _1));
sub_autoware_state_ = this->create_subscription(
"input/autoware_state", 1, std::bind(&AutowareIvAdapter::callbackAutowareState, this, _1));
- sub_control_mode_ = this->create_subscription(
+ sub_control_mode_ = this->create_subscription(
"input/control_mode", 1, std::bind(&AutowareIvAdapter::callbackControlMode, this, _1));
sub_gate_mode_ = this->create_subscription(
"input/gate_mode", durable_qos, std::bind(&AutowareIvAdapter::callbackGateMode, this, _1));
sub_emergency_ = this->create_subscription(
"input/mrm_state", 1, std::bind(&AutowareIvAdapter::callbackMrmState, this, _1));
- sub_hazard_status_ =
- this->create_subscription(
- "input/hazard_status", 1, std::bind(&AutowareIvAdapter::callbackHazardStatus, this, _1));
+ sub_hazard_status_ = this->create_subscription(
+ "input/hazard_status", 1, std::bind(&AutowareIvAdapter::callbackHazardStatus, this, _1));
sub_stop_reason_ = this->create_subscription(
"input/stop_reason", 100, std::bind(&AutowareIvAdapter::callbackStopReason, this, _1));
sub_v2x_command_ = this->create_subscription(
@@ -103,7 +99,7 @@ AutowareIvAdapter::AutowareIvAdapter()
std::bind(&AutowareIvAdapter::callbackLaneChangeAvailable, this, _1));
sub_lane_change_ready_ = this->create_subscription(
"input/lane_change_ready", 1, std::bind(&AutowareIvAdapter::callbackLaneChangeReady, this, _1));
- sub_lane_change_candidate_ = this->create_subscription(
+ sub_lane_change_candidate_ = this->create_subscription(
"input/lane_change_candidate_path", 1,
std::bind(&AutowareIvAdapter::callbackLaneChangeCandidatePath, this, _1));
sub_obstacle_avoid_ready_ =
@@ -111,7 +107,7 @@ AutowareIvAdapter::AutowareIvAdapter()
"input/obstacle_avoid_ready", durable_qos,
std::bind(&AutowareIvAdapter::callbackLaneObstacleAvoidReady, this, _1));
sub_obstacle_avoid_candidate_ =
- this->create_subscription(
+ this->create_subscription(
"input/obstacle_avoid_candidate_path", durable_qos,
std::bind(&AutowareIvAdapter::callbackLaneObstacleAvoidCandidatePath, this, _1));
sub_max_velocity_ = this->create_subscription(
@@ -121,7 +117,7 @@ AutowareIvAdapter::AutowareIvAdapter()
std::bind(&AutowareIvAdapter::callbackCurrentMaxVelocity, this, _1));
sub_temporary_stop_ = this->create_subscription(
"input/temporary_stop", 1, std::bind(&AutowareIvAdapter::callbackTemporaryStop, this, _1));
- sub_autoware_traj_ = this->create_subscription(
+ sub_autoware_traj_ = this->create_subscription(
"input/autoware_trajectory", 1,
std::bind(&AutowareIvAdapter::callbackAutowareTrajectory, this, _1));
@@ -170,25 +166,25 @@ void AutowareIvAdapter::timerCallback()
}
void AutowareIvAdapter::callbackSteer(
- const autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr msg_ptr)
+ const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr msg_ptr)
{
aw_info_.steer_ptr = msg_ptr;
}
void AutowareIvAdapter::callbackVehicleCmd(
- const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg_ptr)
+ const autoware_control_msgs::msg::Control::ConstSharedPtr msg_ptr)
{
aw_info_.vehicle_cmd_ptr = msg_ptr;
}
void AutowareIvAdapter::callbackTurnIndicators(
- const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr msg_ptr)
+ const autoware_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr msg_ptr)
{
aw_info_.turn_indicators_ptr = msg_ptr;
}
void AutowareIvAdapter::callbackHazardLights(
- const autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr msg_ptr)
+ const autoware_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr msg_ptr)
{
aw_info_.hazard_lights_ptr = msg_ptr;
}
@@ -199,7 +195,7 @@ void AutowareIvAdapter::callbackTwist(const nav_msgs::msg::Odometry::ConstShared
}
void AutowareIvAdapter::callbackGear(
- const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg_ptr)
+ const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr msg_ptr)
{
aw_info_.gear_ptr = msg_ptr;
}
@@ -238,7 +234,7 @@ void AutowareIvAdapter::callbackAutowareState(
aw_info_.autoware_state_ptr = msg_ptr;
}
void AutowareIvAdapter::callbackControlMode(
- const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg_ptr)
+ const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg_ptr)
{
aw_info_.control_mode_ptr = msg_ptr;
}
@@ -256,7 +252,7 @@ void AutowareIvAdapter::callbackMrmState(
}
void AutowareIvAdapter::callbackHazardStatus(
- const autoware_auto_system_msgs::msg::HazardStatusStamped::ConstSharedPtr msg_ptr)
+ const autoware_system_msgs::msg::HazardStatusStamped::ConstSharedPtr msg_ptr)
{
aw_info_.hazard_status_ptr = msg_ptr;
}
@@ -298,7 +294,7 @@ void AutowareIvAdapter::callbackLaneChangeReady(
}
void AutowareIvAdapter::callbackLaneChangeCandidatePath(
- const autoware_auto_planning_msgs::msg::Path::ConstSharedPtr msg_ptr)
+ const autoware_planning_msgs::msg::Path::ConstSharedPtr msg_ptr)
{
aw_info_.lane_change_candidate_ptr = msg_ptr;
}
@@ -310,7 +306,7 @@ void AutowareIvAdapter::callbackLaneObstacleAvoidReady(
}
void AutowareIvAdapter::callbackLaneObstacleAvoidCandidatePath(
- const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr)
+ const autoware_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr)
{
aw_info_.obstacle_avoid_candidate_ptr = msg_ptr;
}
@@ -343,7 +339,7 @@ void AutowareIvAdapter::callbackTemporaryStop(
}
void AutowareIvAdapter::callbackAutowareTrajectory(
- const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr)
+ const autoware_planning_msgs::msg::Trajectory::ConstSharedPtr msg_ptr)
{
aw_info_.autoware_planning_traj_ptr = msg_ptr;
}
diff --git a/awapi_awiv_adapter/src/awapi_lane_change_state_publisher.cpp b/awapi_awiv_adapter/src/awapi_lane_change_state_publisher.cpp
index eb9cd8c..b5da0c3 100644
--- a/awapi_awiv_adapter/src/awapi_lane_change_state_publisher.cpp
+++ b/awapi_awiv_adapter/src/awapi_lane_change_state_publisher.cpp
@@ -72,7 +72,7 @@ void AutowareIvLaneChangeStatePublisher::getLaneChangeReadyInfo(
}
void AutowareIvLaneChangeStatePublisher::getCandidatePathInfo(
- const autoware_auto_planning_msgs::msg::Path::ConstSharedPtr & path_ptr,
+ const autoware_planning_msgs::msg::Path::ConstSharedPtr & path_ptr,
tier4_api_msgs::msg::LaneChangeStatus * status)
{
if (!path_ptr) {
diff --git a/awapi_awiv_adapter/src/awapi_obstacle_avoidance_state_publisher.cpp b/awapi_awiv_adapter/src/awapi_obstacle_avoidance_state_publisher.cpp
index feda2ed..47ddcad 100644
--- a/awapi_awiv_adapter/src/awapi_obstacle_avoidance_state_publisher.cpp
+++ b/awapi_awiv_adapter/src/awapi_obstacle_avoidance_state_publisher.cpp
@@ -58,7 +58,7 @@ void AutowareIvObstacleAvoidanceStatePublisher::getObstacleAvoidReadyInfo(
}
void AutowareIvObstacleAvoidanceStatePublisher::getCandidatePathInfo(
- const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr & path_ptr,
+ const autoware_planning_msgs::msg::Trajectory::ConstSharedPtr & path_ptr,
tier4_api_msgs::msg::ObstacleAvoidanceStatus * status)
{
if (!path_ptr) {
diff --git a/awapi_awiv_adapter/src/awapi_vehicle_state_publisher.cpp b/awapi_awiv_adapter/src/awapi_vehicle_state_publisher.cpp
index 4036ff5..d1aa6da 100644
--- a/awapi_awiv_adapter/src/awapi_vehicle_state_publisher.cpp
+++ b/awapi_awiv_adapter/src/awapi_vehicle_state_publisher.cpp
@@ -83,7 +83,7 @@ void AutowareIvVehicleStatePublisher::getPoseInfo(
}
void AutowareIvVehicleStatePublisher::getSteerInfo(
- const autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & steer_ptr,
+ const autoware_vehicle_msgs::msg::SteeringReport::ConstSharedPtr & steer_ptr,
tier4_api_msgs::msg::AwapiVehicleStatus * status)
{
if (!steer_ptr) {
@@ -112,7 +112,7 @@ void AutowareIvVehicleStatePublisher::getSteerInfo(
previous_steer_ptr_ = steer_ptr;
}
void AutowareIvVehicleStatePublisher::getVehicleCmdInfo(
- const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr & vehicle_cmd_ptr,
+ const autoware_control_msgs::msg::Control::ConstSharedPtr & vehicle_cmd_ptr,
tier4_api_msgs::msg::AwapiVehicleStatus * status)
{
if (!vehicle_cmd_ptr) {
@@ -122,14 +122,14 @@ void AutowareIvVehicleStatePublisher::getVehicleCmdInfo(
// get command
status->target_acceleration = vehicle_cmd_ptr->longitudinal.acceleration;
- status->target_velocity = vehicle_cmd_ptr->longitudinal.speed;
+ status->target_velocity = vehicle_cmd_ptr->longitudinal.velocity;
status->target_steering = vehicle_cmd_ptr->lateral.steering_tire_angle;
status->target_steering_velocity = vehicle_cmd_ptr->lateral.steering_tire_rotation_rate;
}
void AutowareIvVehicleStatePublisher::getTurnSignalInfo(
- const autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr & turn_indicators_ptr,
- const autoware_auto_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr & hazard_lights_ptr,
+ const autoware_vehicle_msgs::msg::TurnIndicatorsReport::ConstSharedPtr & turn_indicators_ptr,
+ const autoware_vehicle_msgs::msg::HazardLightsReport::ConstSharedPtr & hazard_lights_ptr,
tier4_api_msgs::msg::AwapiVehicleStatus * status)
{
if (!turn_indicators_ptr) {
@@ -181,7 +181,7 @@ void AutowareIvVehicleStatePublisher::getTwistInfo(
}
void AutowareIvVehicleStatePublisher::getGearInfo(
- const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr & gear_ptr,
+ const autoware_vehicle_msgs::msg::GearReport::ConstSharedPtr & gear_ptr,
tier4_api_msgs::msg::AwapiVehicleStatus * status)
{
if (!gear_ptr) {