Skip to content

Commit 8cba1c8

Browse files
committed
fix(autoware_iv_internal_api_adaptor): iv msg types
Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>
1 parent c2f6a89 commit 8cba1c8

File tree

2 files changed

+43
-43
lines changed

2 files changed

+43
-43
lines changed

autoware_iv_internal_api_adaptor/src/iv_msgs.cpp

+20-20
Original file line numberDiff line numberDiff line change
@@ -22,60 +22,60 @@ IVMsgs::IVMsgs(const rclcpp::NodeOptions & options) : Node("external_api_iv_msgs
2222
{
2323
using std::placeholders::_1;
2424

25-
pub_state_ = create_publisher<AutowareStateIV>("/api/iv_msgs/autoware/state", rclcpp::QoS(1));
26-
sub_state_ = create_subscription<AutowareStateAuto>(
25+
pub_state_ = create_publisher<AutowareStateOutput>("/api/iv_msgs/autoware/state", rclcpp::QoS(1));
26+
sub_state_ = create_subscription<AutowareStateInput>(
2727
"/autoware/state", rclcpp::QoS(1), std::bind(&IVMsgs::onState, this, _1));
28-
sub_emergency_ = create_subscription<EmergencyStateAuto>(
28+
sub_emergency_ = create_subscription<EmergencyStateInput>(
2929
"/system/fail_safe/mrm_state", rclcpp::QoS(1), std::bind(&IVMsgs::onEmergency, this, _1));
3030

3131
pub_control_mode_ =
32-
create_publisher<ControlModeAuto>("/api/iv_msgs/vehicle/status/control_mode", rclcpp::QoS(1));
33-
sub_control_mode_ = create_subscription<ControlMode>(
32+
create_publisher<ControlModeOutput>("/api/iv_msgs/vehicle/status/control_mode", rclcpp::QoS(1));
33+
sub_control_mode_ = create_subscription<ControlModeInput>(
3434
"/vehicle/status/control_mode", rclcpp::QoS(1), std::bind(&IVMsgs::onControlMode, this, _1));
3535

36-
pub_trajectory_ = create_publisher<TrajectoryIV>(
36+
pub_trajectory_ = create_publisher<TrajectoryOutput>(
3737
"/api/iv_msgs/planning/scenario_planning/trajectory", rclcpp::QoS(1));
38-
sub_trajectory_ = create_subscription<TrajectoryAuto>(
38+
sub_trajectory_ = create_subscription<TrajectoryInput>(
3939
"/planning/scenario_planning/trajectory", rclcpp::QoS(1),
4040
std::bind(&IVMsgs::onTrajectory, this, _1));
4141

42-
pub_dynamic_objects_ = create_publisher<DynamicObjectsIV>(
42+
pub_dynamic_objects_ = create_publisher<DynamicObjectsOutput>(
4343
"/api/iv_msgs/perception/object_recognition/tracking/objects", rclcpp::QoS(1));
44-
sub_tracked_objects_ = create_subscription<TrackedObjectsAuto>(
44+
sub_tracked_objects_ = create_subscription<TrackedObjectsInput>(
4545
"/perception/object_recognition/tracking/objects", rclcpp::QoS(1),
4646
std::bind(&IVMsgs::onTrackedObjects, this, _1));
4747

4848
is_emergency_ = false;
4949
}
5050

51-
void IVMsgs::onState(const AutowareStateAuto::ConstSharedPtr message)
51+
void IVMsgs::onState(const AutowareStateInput::ConstSharedPtr message)
5252
{
5353
auto state = tier4_auto_msgs_converter::convert(*message);
5454
if (is_emergency_) {
55-
state.state = AutowareStateIV::EMERGENCY;
55+
state.state = AutowareStateOutput::EMERGENCY;
5656
}
5757
pub_state_->publish(state);
5858
}
5959

60-
void IVMsgs::onEmergency(const EmergencyStateAuto::ConstSharedPtr message)
60+
void IVMsgs::onEmergency(const EmergencyStateInput::ConstSharedPtr message)
6161
{
62-
is_emergency_ = message->state != EmergencyStateAuto::NORMAL;
62+
is_emergency_ = message->state != EmergencyStateInput::NORMAL;
6363
}
6464

65-
void IVMsgs::onControlMode(const ControlMode::ConstSharedPtr message)
65+
void IVMsgs::onControlMode(const ControlModeInput::ConstSharedPtr message)
6666
{
67-
ControlModeAuto control_mode_auto;
68-
control_mode_auto.stamp = message->stamp;
69-
control_mode_auto.mode = message->mode;
70-
pub_control_mode_->publish(control_mode_auto);
67+
ControlModeOutput control_mode;
68+
control_mode.stamp = message->stamp;
69+
control_mode.mode = message->mode;
70+
pub_control_mode_->publish(control_mode);
7171
}
7272

73-
void IVMsgs::onTrajectory(const TrajectoryAuto::ConstSharedPtr message)
73+
void IVMsgs::onTrajectory(const TrajectoryInput::ConstSharedPtr message)
7474
{
7575
pub_trajectory_->publish(tier4_auto_msgs_converter::convert(*message));
7676
}
7777

78-
void IVMsgs::onTrackedObjects(const TrackedObjectsAuto::ConstSharedPtr message)
78+
void IVMsgs::onTrackedObjects(const TrackedObjectsInput::ConstSharedPtr message)
7979
{
8080
pub_dynamic_objects_->publish(tier4_auto_msgs_converter::convert(*message));
8181
}

autoware_iv_internal_api_adaptor/src/iv_msgs.hpp

+23-23
Original file line numberDiff line numberDiff line change
@@ -35,33 +35,33 @@ class IVMsgs : public rclcpp::Node
3535
explicit IVMsgs(const rclcpp::NodeOptions & options);
3636

3737
private:
38-
using EmergencyStateAuto = autoware_adapi_v1_msgs::msg::MrmState;
39-
using AutowareStateAuto = autoware_system_msgs::msg::AutowareState;
40-
using AutowareStateIV = tier4_system_msgs::msg::AutowareState;
41-
rclcpp::Subscription<EmergencyStateAuto>::SharedPtr sub_emergency_;
42-
rclcpp::Subscription<AutowareStateAuto>::SharedPtr sub_state_;
43-
rclcpp::Publisher<AutowareStateIV>::SharedPtr pub_state_;
38+
using EmergencyStateInput = autoware_adapi_v1_msgs::msg::MrmState;
39+
using AutowareStateInput = autoware_system_msgs::msg::AutowareState;
40+
using AutowareStateOutput = tier4_system_msgs::msg::AutowareState;
41+
rclcpp::Subscription<EmergencyStateInput>::SharedPtr sub_emergency_;
42+
rclcpp::Subscription<AutowareStateInput>::SharedPtr sub_state_;
43+
rclcpp::Publisher<AutowareStateOutput>::SharedPtr pub_state_;
4444

45-
using ControlModeAuto = autoware_vehicle_msgs::msg::ControlModeReport;
46-
using ControlMode = autoware_auto_vehicle_msgs::msg::ControlModeReport;
47-
rclcpp::Subscription<ControlMode>::SharedPtr sub_control_mode_;
48-
rclcpp::Publisher<ControlModeAuto>::SharedPtr pub_control_mode_;
45+
using ControlModeInput = autoware_vehicle_msgs::msg::ControlModeReport;
46+
using ControlModeOutput = autoware_auto_vehicle_msgs::msg::ControlModeReport;
47+
rclcpp::Subscription<ControlModeInput>::SharedPtr sub_control_mode_;
48+
rclcpp::Publisher<ControlModeOutput>::SharedPtr pub_control_mode_;
4949

50-
using TrajectoryAuto = autoware_planning_msgs::msg::Trajectory;
51-
using TrajectoryIV = tier4_planning_msgs::msg::Trajectory;
52-
rclcpp::Subscription<TrajectoryAuto>::SharedPtr sub_trajectory_;
53-
rclcpp::Publisher<TrajectoryIV>::SharedPtr pub_trajectory_;
50+
using TrajectoryInput = autoware_planning_msgs::msg::Trajectory;
51+
using TrajectoryOutput = tier4_planning_msgs::msg::Trajectory;
52+
rclcpp::Subscription<TrajectoryInput>::SharedPtr sub_trajectory_;
53+
rclcpp::Publisher<TrajectoryOutput>::SharedPtr pub_trajectory_;
5454

55-
using TrackedObjectsAuto = autoware_perception_msgs::msg::TrackedObjects;
56-
using DynamicObjectsIV = tier4_perception_msgs::msg::DynamicObjectArray;
57-
rclcpp::Subscription<TrackedObjectsAuto>::SharedPtr sub_tracked_objects_;
58-
rclcpp::Publisher<DynamicObjectsIV>::SharedPtr pub_dynamic_objects_;
55+
using TrackedObjectsInput = autoware_perception_msgs::msg::TrackedObjects;
56+
using DynamicObjectsOutput = tier4_perception_msgs::msg::DynamicObjectArray;
57+
rclcpp::Subscription<TrackedObjectsInput>::SharedPtr sub_tracked_objects_;
58+
rclcpp::Publisher<DynamicObjectsOutput>::SharedPtr pub_dynamic_objects_;
5959

60-
void onState(const AutowareStateAuto::ConstSharedPtr message);
61-
void onEmergency(const EmergencyStateAuto::ConstSharedPtr message);
62-
void onControlMode(const ControlMode::ConstSharedPtr message);
63-
void onTrajectory(const TrajectoryAuto::ConstSharedPtr message);
64-
void onTrackedObjects(const TrackedObjectsAuto::ConstSharedPtr message);
60+
void onState(const AutowareStateInput::ConstSharedPtr message);
61+
void onEmergency(const EmergencyStateInput::ConstSharedPtr message);
62+
void onControlMode(const ControlModeInput::ConstSharedPtr message);
63+
void onTrajectory(const TrajectoryInput::ConstSharedPtr message);
64+
void onTrackedObjects(const TrackedObjectsInput::ConstSharedPtr message);
6565

6666
bool is_emergency_;
6767
};

0 commit comments

Comments
 (0)