Skip to content

Commit 6a3ced5

Browse files
committed
use operation move availability
Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>
1 parent e8f3650 commit 6a3ced5

File tree

2 files changed

+13
-35
lines changed

2 files changed

+13
-35
lines changed

system/default_ad_api/src/operation_mode.cpp

+10-30
Original file line numberDiff line numberDiff line change
@@ -39,18 +39,15 @@ OperationModeNode::OperationModeNode(const rclcpp::NodeOptions & options)
3939
adaptor.init_cli(cli_mode_, group_cli_);
4040
adaptor.init_cli(cli_control_, group_cli_);
4141

42-
const std::vector<std::string> module_names = {
43-
"sensing", "perception", "map", "localization", "planning", "control", "vehicle", "system",
42+
const auto name = "/system/operation_mode/availability";
43+
const auto qos = rclcpp::QoS(1);
44+
const auto callback = [this](const OperationModeAvailability::ConstSharedPtr msg) {
45+
mode_available_[OperationModeState::Message::STOP] = msg->stop;
46+
mode_available_[OperationModeState::Message::AUTONOMOUS] = msg->autonomous;
47+
mode_available_[OperationModeState::Message::LOCAL] = msg->local;
48+
mode_available_[OperationModeState::Message::REMOTE] = msg->remote;
4449
};
45-
46-
for (size_t i = 0; i < module_names.size(); ++i) {
47-
const auto name = "/system/component_state_monitor/component/autonomous/" + module_names[i];
48-
const auto qos = rclcpp::QoS(1).transient_local();
49-
const auto callback = [this, i, module_names](const ModeChangeAvailable::ConstSharedPtr msg) {
50-
module_states_[module_names[i]] = msg->available;
51-
};
52-
sub_module_states_.push_back(create_subscription<ModeChangeAvailable>(name, qos, callback));
53-
}
50+
sub_availability_ = create_subscription<OperationModeAvailability>(name, qos, callback);
5451

5552
timer_ = rclcpp::create_timer(
5653
this, get_clock(), rclcpp::Rate(5.0).period(), std::bind(&OperationModeNode::on_timer, this));
@@ -60,8 +57,8 @@ OperationModeNode::OperationModeNode(const rclcpp::NodeOptions & options)
6057
mode_available_[OperationModeState::Message::UNKNOWN] = false;
6158
mode_available_[OperationModeState::Message::STOP] = true;
6259
mode_available_[OperationModeState::Message::AUTONOMOUS] = false;
63-
mode_available_[OperationModeState::Message::LOCAL] = true;
64-
mode_available_[OperationModeState::Message::REMOTE] = true;
60+
mode_available_[OperationModeState::Message::LOCAL] = false;
61+
mode_available_[OperationModeState::Message::REMOTE] = false;
6562
}
6663

6764
template <class ResponseT>
@@ -135,23 +132,6 @@ void OperationModeNode::on_state(const OperationModeState::Message::ConstSharedP
135132

136133
void OperationModeNode::on_timer()
137134
{
138-
bool autonomous_available = true;
139-
std::string unhealthy_components = "";
140-
for (const auto & state : module_states_) {
141-
if (!state.second) {
142-
unhealthy_components += unhealthy_components.empty() ? state.first : ", " + state.first;
143-
}
144-
autonomous_available &= state.second;
145-
}
146-
mode_available_[OperationModeState::Message::AUTONOMOUS] = autonomous_available;
147-
148-
if (!unhealthy_components.empty()) {
149-
RCLCPP_INFO_THROTTLE(
150-
get_logger(), *get_clock(), 3000,
151-
"%s component state is unhealthy. Autonomous is not available.",
152-
unhealthy_components.c_str());
153-
}
154-
155135
update_state();
156136
}
157137

system/default_ad_api/src/operation_mode.hpp

+3-5
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
#include <vector>
2626

2727
// TODO(Takagi, Isamu): define interface
28-
#include <tier4_system_msgs/msg/mode_change_available.hpp>
28+
#include <tier4_system_msgs/msg/operation_mode_availability.hpp>
2929

3030
// This file should be included after messages.
3131
#include "utils/types.hpp"
@@ -47,7 +47,7 @@ class OperationModeNode : public rclcpp::Node
4747
using ChangeToRemote = autoware_ad_api::operation_mode::ChangeToRemote;
4848
using OperationModeRequest = system_interface::ChangeOperationMode::Service::Request;
4949
using AutowareControlRequest = system_interface::ChangeAutowareControl::Service::Request;
50-
using ModeChangeAvailable = tier4_system_msgs::msg::ModeChangeAvailable;
50+
using OperationModeAvailability = tier4_system_msgs::msg::OperationModeAvailability;
5151

5252
OperationModeState::Message curr_state_;
5353
OperationModeState::Message prev_state_;
@@ -65,9 +65,7 @@ class OperationModeNode : public rclcpp::Node
6565
Sub<system_interface::OperationModeState> sub_state_;
6666
Cli<system_interface::ChangeOperationMode> cli_mode_;
6767
Cli<system_interface::ChangeAutowareControl> cli_control_;
68-
69-
std::unordered_map<std::string, bool> module_states_;
70-
std::vector<rclcpp::Subscription<ModeChangeAvailable>::SharedPtr> sub_module_states_;
68+
rclcpp::Subscription<OperationModeAvailability>::SharedPtr sub_availability_;
7169

7270
void on_change_to_stop(
7371
const ChangeToStop::Service::Request::SharedPtr req,

0 commit comments

Comments
 (0)