@@ -39,18 +39,15 @@ OperationModeNode::OperationModeNode(const rclcpp::NodeOptions & options)
39
39
adaptor.init_cli (cli_mode_, group_cli_);
40
40
adaptor.init_cli (cli_control_, group_cli_);
41
41
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 ;
44
49
};
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);
54
51
55
52
timer_ = rclcpp::create_timer (
56
53
this , get_clock (), rclcpp::Rate (5.0 ).period (), std::bind (&OperationModeNode::on_timer, this ));
@@ -60,8 +57,8 @@ OperationModeNode::OperationModeNode(const rclcpp::NodeOptions & options)
60
57
mode_available_[OperationModeState::Message::UNKNOWN] = false ;
61
58
mode_available_[OperationModeState::Message::STOP] = true ;
62
59
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 ;
65
62
}
66
63
67
64
template <class ResponseT >
@@ -135,23 +132,6 @@ void OperationModeNode::on_state(const OperationModeState::Message::ConstSharedP
135
132
136
133
void OperationModeNode::on_timer ()
137
134
{
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
-
155
135
update_state ();
156
136
}
157
137
0 commit comments