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: apply mrm state to autoware state #81

Merged
merged 1 commit into from
Nov 30, 2022
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
1 change: 1 addition & 0 deletions autoware_iv_internal_api_adaptor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@

<build_depend>autoware_cmake</build_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_auto_system_msgs</depend>
Expand Down
19 changes: 9 additions & 10 deletions autoware_iv_internal_api_adaptor/src/iv_msgs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ IVMsgs::IVMsgs(const rclcpp::NodeOptions & options) : Node("external_api_iv_msgs
sub_state_ = create_subscription<AutowareStateAuto>(
"/autoware/state", rclcpp::QoS(1), std::bind(&IVMsgs::onState, this, _1));
sub_emergency_ = create_subscription<EmergencyStateAuto>(
"/system/emergency/emergency_state", rclcpp::QoS(1), std::bind(&IVMsgs::onEmergency, this, _1));
"/system/fail_safe/mrm_state", rclcpp::QoS(1), std::bind(&IVMsgs::onEmergency, this, _1));

pub_control_mode_ =
create_publisher<ControlModeAuto>("/api/iv_msgs/vehicle/status/control_mode", rclcpp::QoS(1));
Expand All @@ -44,24 +44,23 @@ IVMsgs::IVMsgs(const rclcpp::NodeOptions & options) : Node("external_api_iv_msgs
sub_tracked_objects_ = create_subscription<TrackedObjectsAuto>(
"/perception/object_recognition/tracking/objects", rclcpp::QoS(1),
std::bind(&IVMsgs::onTrackedObjects, this, _1));

is_emergency_ = false;
}

void IVMsgs::onState(const AutowareStateAuto::ConstSharedPtr message)
{
auto state = tier4_auto_msgs_converter::convert(*message);
if (emergency_) {
switch (emergency_->state) {
case EmergencyStateAuto::MRM_OPERATING:
case EmergencyStateAuto::MRM_SUCCEEDED:
case EmergencyStateAuto::MRM_FAILED:
state.state = AutowareStateIV::EMERGENCY;
break;
}
if (is_emergency_) {
state.state = AutowareStateIV::EMERGENCY;
}
pub_state_->publish(state);
}

void IVMsgs::onEmergency(const EmergencyStateAuto::ConstSharedPtr message) { emergency_ = message; }
void IVMsgs::onEmergency(const EmergencyStateAuto::ConstSharedPtr message)
{
is_emergency_ = message->state != EmergencyStateAuto::NORMAL;
}

void IVMsgs::onControlMode(const ControlModeAuto::ConstSharedPtr message)
{
Expand Down
6 changes: 3 additions & 3 deletions autoware_iv_internal_api_adaptor/src/iv_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@

#include <rclcpp/rclcpp.hpp>

#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
#include <autoware_auto_perception_msgs/msg/tracked_objects.hpp>
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
#include <autoware_auto_system_msgs/msg/autoware_state.hpp>
#include <autoware_auto_system_msgs/msg/emergency_state.hpp>
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
#include <tier4_perception_msgs/msg/dynamic_object_array.hpp>
#include <tier4_planning_msgs/msg/trajectory.hpp>
Expand All @@ -34,7 +34,7 @@ class IVMsgs : public rclcpp::Node
explicit IVMsgs(const rclcpp::NodeOptions & options);

private:
using EmergencyStateAuto = autoware_auto_system_msgs::msg::EmergencyState;
using EmergencyStateAuto = autoware_adapi_v1_msgs::msg::MrmState;
using AutowareStateAuto = autoware_auto_system_msgs::msg::AutowareState;
using AutowareStateIV = tier4_system_msgs::msg::AutowareState;
rclcpp::Subscription<EmergencyStateAuto>::SharedPtr sub_emergency_;
Expand All @@ -61,7 +61,7 @@ class IVMsgs : public rclcpp::Node
void onTrajectory(const TrajectoryAuto::ConstSharedPtr message);
void onTrackedObjects(const TrackedObjectsAuto::ConstSharedPtr message);

EmergencyStateAuto::ConstSharedPtr emergency_;
bool is_emergency_;
};

} // namespace internal_api
Expand Down