Skip to content

Commit

Permalink
feat: remove autoware_auto messages (#124)
Browse files Browse the repository at this point in the history
Signed-off-by: Takagi, Isamu <[email protected]>
  • Loading branch information
isamu-takagi authored Aug 7, 2024
1 parent d800841 commit d409b66
Show file tree
Hide file tree
Showing 6 changed files with 19 additions and 45 deletions.
1 change: 0 additions & 1 deletion autoware_iv_internal_api_adaptor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_system_msgs</depend>
Expand Down
13 changes: 0 additions & 13 deletions autoware_iv_internal_api_adaptor/src/iv_msgs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,6 @@ IVMsgs::IVMsgs(const rclcpp::NodeOptions & options) : Node("external_api_iv_msgs
sub_emergency_ = create_subscription<EmergencyStateInput>(
"/system/fail_safe/mrm_state", rclcpp::QoS(1), std::bind(&IVMsgs::onEmergency, this, _1));

pub_control_mode_ =
create_publisher<ControlModeOutput>("/api/iv_msgs/vehicle/status/control_mode", rclcpp::QoS(1));
sub_control_mode_ = create_subscription<ControlModeInput>(
"/vehicle/status/control_mode", rclcpp::QoS(1), std::bind(&IVMsgs::onControlMode, this, _1));

pub_trajectory_ = create_publisher<TrajectoryOutput>(
"/api/iv_msgs/planning/scenario_planning/trajectory", rclcpp::QoS(1));
sub_trajectory_ = create_subscription<TrajectoryInput>(
Expand Down Expand Up @@ -62,14 +57,6 @@ void IVMsgs::onEmergency(const EmergencyStateInput::ConstSharedPtr message)
is_emergency_ = message->state != EmergencyStateInput::NORMAL;
}

void IVMsgs::onControlMode(const ControlModeInput::ConstSharedPtr message)
{
ControlModeOutput control_mode;
control_mode.stamp = message->stamp;
control_mode.mode = message->mode;
pub_control_mode_->publish(control_mode);
}

void IVMsgs::onTrajectory(const TrajectoryInput::ConstSharedPtr message)
{
pub_trajectory_->publish(tier4_auto_msgs_converter::convert(*message));
Expand Down
7 changes: 0 additions & 7 deletions autoware_iv_internal_api_adaptor/src/iv_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <rclcpp/rclcpp.hpp>

#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
#include <autoware_perception_msgs/msg/tracked_objects.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
#include <autoware_system_msgs/msg/autoware_state.hpp>
Expand All @@ -42,11 +41,6 @@ class IVMsgs : public rclcpp::Node
rclcpp::Subscription<AutowareStateInput>::SharedPtr sub_state_;
rclcpp::Publisher<AutowareStateOutput>::SharedPtr pub_state_;

using ControlModeInput = autoware_vehicle_msgs::msg::ControlModeReport;
using ControlModeOutput = autoware_auto_vehicle_msgs::msg::ControlModeReport;
rclcpp::Subscription<ControlModeInput>::SharedPtr sub_control_mode_;
rclcpp::Publisher<ControlModeOutput>::SharedPtr pub_control_mode_;

using TrajectoryInput = autoware_planning_msgs::msg::Trajectory;
using TrajectoryOutput = tier4_planning_msgs::msg::Trajectory;
rclcpp::Subscription<TrajectoryInput>::SharedPtr sub_trajectory_;
Expand All @@ -59,7 +53,6 @@ class IVMsgs : public rclcpp::Node

void onState(const AutowareStateInput::ConstSharedPtr message);
void onEmergency(const EmergencyStateInput::ConstSharedPtr message);
void onControlMode(const ControlModeInput::ConstSharedPtr message);
void onTrajectory(const TrajectoryInput::ConstSharedPtr message);
void onTrackedObjects(const TrackedObjectsInput::ConstSharedPtr message);

Expand Down
38 changes: 19 additions & 19 deletions awapi_awiv_adapter/Readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -107,30 +107,30 @@
### /awapi/traffic_light/get/traffic_signals

- get recognition result of traffic light
- MessageType: autoware_auto_perception_msgs/msg/TrafficSignalArray
- MessageType: autoware_perception_msgs/msg/TrafficSignalArray

|| type | name | unit | note |
| --- | :--------------------------------------------------- | :--- | :--- | :--- |
| | autoware_auto_perception_msgs/msg/TrafficSignalArray | | | |
|| type | name | unit | note |
| --- | :---------------------------------------------- | :--- | :--- | :--- |
| | autoware_perception_msgs/msg/TrafficSignalArray | | | |

### /awapi/traffic_light/get/nearest_traffic_signal

- get recognition result of nearest traffic light
- MessageType: autoware_auto_perception_msgs/LookingTrafficSignal
- MessageType: autoware_perception_msgs/LookingTrafficSignal

| | type | name | unit | note |
| --- | :--------------------------------------------------- | :--------- | :--- | :------------------------------------------------------------ |
| | std_msgs/Header | header | | |
| | autoware_auto_perception_msgs/TrafficSignalWithJudge | perception | | traffic light information from autoware perception module |
| | autoware_auto_perception_msgs/TrafficSignalWithJudge | external | | traffic light information from external tool/module |
| | autoware_auto_perception_msgs/TrafficSignalWithJudge | final | | traffic light information used by the planning module finally |
| | type | name | unit | note |
| --- | :---------------------------------------------- | :--------- | :--- | :------------------------------------------------------------ |
| | std_msgs/Header | header | | |
| | autoware_perception_msgs/TrafficSignalWithJudge | perception | | traffic light information from autoware perception module |
| | autoware_perception_msgs/TrafficSignalWithJudge | external | | traffic light information from external tool/module |
| | autoware_perception_msgs/TrafficSignalWithJudge | final | | traffic light information used by the planning module finally |

- The contents of TrafficSignalWithJudge.msg is following.

| | type | name | unit | note |
| --- | :------------------------------------------ | :----- | :------------------- | :------------------------------------------------------------- |
| | autoware_auto_perception_msgs/TrafficSignal | signal | | traffic light color/arrow |
| | uint8 | judge | 0:NONE, 1:STOP, 2:GO | go/stop judgment based on the color/arrow of the traffic light |
| | type | name | unit | note |
| --- | :------------------------------------- | :----- | :------------------- | :------------------------------------------------------------- |
| | autoware_perception_msgs/TrafficSignal | signal | | traffic light color/arrow |
| | uint8 | judge | 0:NONE, 1:STOP, 2:GO | go/stop judgment based on the color/arrow of the traffic light |

## put topic

Expand Down Expand Up @@ -234,11 +234,11 @@
### /awapi/traffic_light/put/traffic_signals

- Overwrite the recognition result of traffic light
- MessageType: autoware_auto_perception_msgs/TrafficSignalArray
- MessageType: autoware_perception_msgs/TrafficSignalArray

|| type | name | unit | note |
| --- | :----------------------------------------------- | :--- | :--- | :--- |
| | autoware_auto_perception_msgs/TrafficSignalArray | | | |
|| type | name | unit | note |
| --- | :------------------------------------------ | :--- | :--- | :--- |
| | autoware_perception_msgs/TrafficSignalArray | | | |

### /awapi/autoware/put/crosswalk_states

Expand Down
1 change: 0 additions & 1 deletion awapi_awiv_adapter/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@
<depend>tier4_v2x_msgs</depend>
<depend>tier4_vehicle_msgs</depend>

<exec_depend>autoware_auto_perception_msgs</exec_depend>
<exec_depend>tier4_perception_msgs</exec_depend>
<exec_depend>topic_tools</exec_depend>

Expand Down
4 changes: 0 additions & 4 deletions build_depends.repos
Original file line number Diff line number Diff line change
@@ -1,8 +1,4 @@
repositories:
core/autoware_msgs:
type: git
url: https:/tier4/autoware_auto_msgs.git # TODO(TIER IV): Move to autowarefoundation/autoware_msgs
version: tier4/main
core/common:
type: git
url: https:/autowarefoundation/autoware_common.git
Expand Down

0 comments on commit d409b66

Please sign in to comment.