Skip to content

Commit 55dc707

Browse files
committed
feat: change mrm state type to internal one (#1392)
Signed-off-by: TetsuKawa <kawaguchitnon@icloud.com>
1 parent de3fb70 commit 55dc707

File tree

2 files changed

+64
-57
lines changed

2 files changed

+64
-57
lines changed

system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp

+9-8
Original file line numberDiff line numberDiff line change
@@ -24,12 +24,13 @@
2424
// Autoware
2525
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
2626

27-
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
2827
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
29-
#include <autoware_vehicle_msgs/msg/control_mode_report.hpp>
30-
#include <autoware_vehicle_msgs/msg/gear_command.hpp>
31-
#include <autoware_vehicle_msgs/msg/hazard_lights_command.hpp>
28+
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
29+
#include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
30+
#include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp>
31+
#include <tier4_system_msgs/msg/mrm_behavior.hpp>
3232
#include <tier4_system_msgs/msg/mrm_behavior_status.hpp>
33+
#include <tier4_system_msgs/msg/mrm_state.hpp>
3334
#include <tier4_system_msgs/msg/operation_mode_availability.hpp>
3435
#include <tier4_system_msgs/srv/operate_mrm.hpp>
3536

@@ -110,9 +111,9 @@ class MrmHandler : public rclcpp::Node
110111
void publishHazardCmd();
111112
void publishGearCmd();
112113

113-
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::MrmState>::SharedPtr pub_mrm_state_;
114+
rclcpp::Publisher<tier4_system_msgs::msg::MrmState>::SharedPtr pub_mrm_state_;
114115

115-
autoware_adapi_v1_msgs::msg::MrmState mrm_state_;
116+
tier4_system_msgs::msg::MrmState mrm_state_;
116117
void publishMrmState();
117118

118119
// Clients
@@ -127,7 +128,7 @@ class MrmHandler : public rclcpp::Node
127128
rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr service_recover_mrm_;
128129

129130
bool requestMrmBehavior(
130-
const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior,
131+
const tier4_system_msgs::msg::MrmBehavior::_type_type & mrm_behavior,
131132
RequestType request_type) const;
132133
void logMrmCallingResult(
133134
const tier4_system_msgs::srv::OperateMrm::Response & result, const std::string & behavior,
@@ -156,7 +157,7 @@ class MrmHandler : public rclcpp::Node
156157
void updateMrmState();
157158
void operateMrm();
158159
void handleFailedRequest();
159-
autoware_adapi_v1_msgs::msg::MrmState::_behavior_type getCurrentMrmBehavior();
160+
tier4_system_msgs::msg::MrmBehavior::_type_type getCurrentMrmBehavior();
160161
bool isStopped();
161162
bool isEmergency() const;
162163
bool isControlModeAutonomous();

system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+55-49
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler"
5151
pub_gear_cmd_ =
5252
create_publisher<autoware_vehicle_msgs::msg::GearCommand>("~/output/gear", rclcpp::QoS{1});
5353
pub_mrm_state_ =
54-
create_publisher<autoware_adapi_v1_msgs::msg::MrmState>("~/output/mrm/state", rclcpp::QoS{1});
54+
create_publisher<tier4_system_msgs::msg::MrmState>("~/output/mrm/state", rclcpp::QoS{1});
5555

5656
// Clients
5757
client_mrm_pull_over_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -77,8 +77,8 @@ MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler"
7777

7878
// Initialize
7979
mrm_state_.stamp = this->now();
80-
mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::NORMAL;
81-
mrm_state_.behavior = autoware_adapi_v1_msgs::msg::MrmState::NONE;
80+
mrm_state_.state = tier4_system_msgs::msg::MrmState::NORMAL;
81+
mrm_state_.behavior.type = tier4_system_msgs::msg::MrmBehavior::NONE;
8282
is_operation_mode_availability_timeout = false;
8383

8484
// Timer
@@ -163,30 +163,31 @@ void MrmHandler::publishMrmState()
163163

164164
void MrmHandler::operateMrm()
165165
{
166-
using autoware_adapi_v1_msgs::msg::MrmState;
166+
using tier4_system_msgs::msg::MrmBehavior;
167+
using tier4_system_msgs::msg::MrmState;
167168

168169
if (mrm_state_.state == MrmState::NORMAL) {
169170
// Cancel MRM behavior when returning to NORMAL state
170-
const auto current_mrm_behavior = MrmState::NONE;
171-
if (current_mrm_behavior == mrm_state_.behavior) {
171+
const auto current_mrm_behavior = MrmBehavior::NONE;
172+
if (current_mrm_behavior == mrm_state_.behavior.type) {
172173
return;
173174
}
174-
if (requestMrmBehavior(mrm_state_.behavior, RequestType::CANCEL)) {
175-
mrm_state_.behavior = current_mrm_behavior;
175+
if (requestMrmBehavior(mrm_state_.behavior.type, RequestType::CANCEL)) {
176+
mrm_state_.behavior.type = current_mrm_behavior;
176177
} else {
177178
handleFailedRequest();
178179
}
179180
return;
180181
}
181182
if (mrm_state_.state == MrmState::MRM_OPERATING) {
182183
const auto current_mrm_behavior = getCurrentMrmBehavior();
183-
if (current_mrm_behavior == mrm_state_.behavior) {
184+
if (current_mrm_behavior == mrm_state_.behavior.type) {
184185
return;
185186
}
186-
if (!requestMrmBehavior(mrm_state_.behavior, RequestType::CANCEL)) {
187+
if (!requestMrmBehavior(mrm_state_.behavior.type, RequestType::CANCEL)) {
187188
handleFailedRequest();
188189
} else if (requestMrmBehavior(current_mrm_behavior, RequestType::CALL)) {
189-
mrm_state_.behavior = current_mrm_behavior;
190+
mrm_state_.behavior.type = current_mrm_behavior;
190191
} else {
191192
handleFailedRequest();
192193
}
@@ -206,21 +207,23 @@ void MrmHandler::operateMrm()
206207

207208
void MrmHandler::handleFailedRequest()
208209
{
209-
using autoware_adapi_v1_msgs::msg::MrmState;
210+
using tier4_system_msgs::msg::MrmBehavior;
211+
using tier4_system_msgs::msg::MrmState;
210212

211-
if (requestMrmBehavior(MrmState::EMERGENCY_STOP, CALL)) {
213+
if (requestMrmBehavior(MrmBehavior::EMERGENCY_STOP, CALL)) {
212214
if (mrm_state_.state != MrmState::MRM_OPERATING) transitionTo(MrmState::MRM_OPERATING);
213215
} else {
214216
transitionTo(MrmState::MRM_FAILED);
215217
}
216-
mrm_state_.behavior = MrmState::EMERGENCY_STOP;
218+
mrm_state_.behavior.type = MrmBehavior::EMERGENCY_STOP;
217219
}
218220

219221
bool MrmHandler::requestMrmBehavior(
220-
const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior,
222+
const tier4_system_msgs::msg::MrmBehavior::_type_type & mrm_behavior,
221223
RequestType request_type) const
222224
{
223-
using autoware_adapi_v1_msgs::msg::MrmState;
225+
using tier4_system_msgs::msg::MrmBehavior;
226+
using tier4_system_msgs::msg::MrmState;
224227

225228
auto request = std::make_shared<tier4_system_msgs::srv::OperateMrm::Request>();
226229
if (request_type == RequestType::CALL) {
@@ -236,35 +239,35 @@ bool MrmHandler::requestMrmBehavior(
236239
std::shared_future<std::shared_ptr<tier4_system_msgs::srv::OperateMrm::Response>> future;
237240

238241
const auto behavior2string = [](const int behavior) {
239-
if (behavior == MrmState::NONE) {
242+
if (behavior == MrmBehavior::NONE) {
240243
return "NONE";
241244
}
242-
if (behavior == MrmState::PULL_OVER) {
245+
if (behavior == MrmBehavior::PULL_OVER) {
243246
return "PULL_OVER";
244247
}
245-
if (behavior == MrmState::COMFORTABLE_STOP) {
248+
if (behavior == MrmBehavior::COMFORTABLE_STOP) {
246249
return "COMFORTABLE_STOP";
247250
}
248-
if (behavior == MrmState::EMERGENCY_STOP) {
251+
if (behavior == MrmBehavior::EMERGENCY_STOP) {
249252
return "EMERGENCY_STOP";
250253
}
251254
const auto msg = "invalid behavior: " + std::to_string(behavior);
252255
throw std::runtime_error(msg);
253256
};
254257

255258
switch (mrm_behavior) {
256-
case MrmState::NONE:
259+
case MrmBehavior::NONE:
257260
RCLCPP_WARN(this->get_logger(), "MRM behavior is None. Do nothing.");
258261
return true;
259-
case MrmState::PULL_OVER: {
262+
case MrmBehavior::PULL_OVER: {
260263
future = client_mrm_pull_over_->async_send_request(request).future.share();
261264
break;
262265
}
263-
case MrmState::COMFORTABLE_STOP: {
266+
case MrmBehavior::COMFORTABLE_STOP: {
264267
future = client_mrm_comfortable_stop_->async_send_request(request).future.share();
265268
break;
266269
}
267-
case MrmState::EMERGENCY_STOP: {
270+
case MrmBehavior::EMERGENCY_STOP: {
268271
future = client_mrm_emergency_stop_->async_send_request(request).future.share();
269272
break;
270273
}
@@ -364,7 +367,7 @@ void MrmHandler::onTimer()
364367

365368
void MrmHandler::transitionTo(const int new_state)
366369
{
367-
using autoware_adapi_v1_msgs::msg::MrmState;
370+
using tier4_system_msgs::msg::MrmState;
368371

369372
const auto state2string = [](const int state) {
370373
if (state == MrmState::NORMAL) {
@@ -393,8 +396,9 @@ void MrmHandler::transitionTo(const int new_state)
393396

394397
void MrmHandler::updateMrmState()
395398
{
396-
using autoware_adapi_v1_msgs::msg::MrmState;
397-
using autoware_vehicle_msgs::msg::ControlModeReport;
399+
using autoware_auto_vehicle_msgs::msg::ControlModeReport;
400+
using tier4_system_msgs::msg::MrmBehavior;
401+
using tier4_system_msgs::msg::MrmState;
398402

399403
// Check emergency
400404
const bool is_emergency = isEmergency();
@@ -433,6 +437,7 @@ void MrmHandler::updateMrmState()
433437

434438
case MrmState::MRM_SUCCEEDED:
435439
if (mrm_state_.behavior != getCurrentMrmBehavior()) {
440+
436441
transitionTo(MrmState::MRM_OPERATING);
437442
}
438443
return;
@@ -448,85 +453,86 @@ void MrmHandler::updateMrmState()
448453
}
449454
}
450455

451-
autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmBehavior()
456+
tier4_system_msgs::msg::MrmBehavior::_type_type MrmHandler::getCurrentMrmBehavior()
452457
{
453-
using autoware_adapi_v1_msgs::msg::MrmState;
458+
using tier4_system_msgs::msg::MrmBehavior;
459+
using tier4_system_msgs::msg::MrmState;
454460
using tier4_system_msgs::msg::OperationModeAvailability;
455461

456462
// State machine
457-
if (mrm_state_.behavior == MrmState::NONE) {
463+
if (mrm_state_.behavior.type == MrmBehavior::NONE) {
458464
if (is_operation_mode_availability_timeout) {
459-
return MrmState::EMERGENCY_STOP;
465+
return MrmBehavior::EMERGENCY_STOP;
460466
}
461467
if (operation_mode_availability_->pull_over) {
462468
if (param_.use_pull_over) {
463-
return MrmState::PULL_OVER;
469+
return MrmBehavior::PULL_OVER;
464470
}
465471
}
466472
if (operation_mode_availability_->comfortable_stop) {
467473
if (param_.use_comfortable_stop) {
468-
return MrmState::COMFORTABLE_STOP;
474+
return MrmBehavior::COMFORTABLE_STOP;
469475
}
470476
}
471477
if (!operation_mode_availability_->emergency_stop) {
472478
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
473479
}
474-
return MrmState::EMERGENCY_STOP;
480+
return MrmBehavior::EMERGENCY_STOP;
475481
}
476-
if (mrm_state_.behavior == MrmState::PULL_OVER) {
482+
if (mrm_state_.behavior.type == MrmBehavior::PULL_OVER) {
477483
if (is_operation_mode_availability_timeout) {
478-
return MrmState::EMERGENCY_STOP;
484+
return MrmBehavior::EMERGENCY_STOP;
479485
}
480486
if (operation_mode_availability_->pull_over) {
481487
if (param_.use_pull_over) {
482-
return MrmState::PULL_OVER;
488+
return MrmBehavior::PULL_OVER;
483489
}
484490
}
485491
if (operation_mode_availability_->comfortable_stop) {
486492
if (param_.use_comfortable_stop) {
487-
return MrmState::COMFORTABLE_STOP;
493+
return MrmBehavior::COMFORTABLE_STOP;
488494
}
489495
}
490496
if (!operation_mode_availability_->emergency_stop) {
491497
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
492498
}
493-
return MrmState::EMERGENCY_STOP;
499+
return MrmBehavior::EMERGENCY_STOP;
494500
}
495-
if (mrm_state_.behavior == MrmState::COMFORTABLE_STOP) {
501+
if (mrm_state_.behavior.type == MrmBehavior::COMFORTABLE_STOP) {
496502
if (is_operation_mode_availability_timeout) {
497-
return MrmState::EMERGENCY_STOP;
503+
return MrmBehavior::EMERGENCY_STOP;
498504
}
499505
if (isStopped() && operation_mode_availability_->pull_over) {
500506
if (param_.use_pull_over && param_.use_pull_over_after_stopped) {
501-
return MrmState::PULL_OVER;
507+
return MrmBehavior::PULL_OVER;
502508
}
503509
}
504510
if (operation_mode_availability_->comfortable_stop) {
505511
if (param_.use_comfortable_stop) {
506-
return MrmState::COMFORTABLE_STOP;
512+
return MrmBehavior::COMFORTABLE_STOP;
507513
}
508514
}
509515
if (!operation_mode_availability_->emergency_stop) {
510516
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
511517
}
512-
return MrmState::EMERGENCY_STOP;
518+
return MrmBehavior::EMERGENCY_STOP;
513519
}
514-
if (mrm_state_.behavior == MrmState::EMERGENCY_STOP) {
520+
if (mrm_state_.behavior.type == MrmBehavior::EMERGENCY_STOP) {
515521
if (is_operation_mode_availability_timeout) {
516-
return MrmState::EMERGENCY_STOP;
522+
return MrmBehavior::EMERGENCY_STOP;
517523
}
518524
if (isStopped() && operation_mode_availability_->pull_over) {
519525
if (param_.use_pull_over && param_.use_pull_over_after_stopped) {
520-
return MrmState::PULL_OVER;
526+
return MrmBehavior::PULL_OVER;
521527
}
522528
}
523529
if (!operation_mode_availability_->emergency_stop) {
524530
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
525531
}
526-
return MrmState::EMERGENCY_STOP;
532+
return MrmBehavior::EMERGENCY_STOP;
527533
}
528534

529-
return mrm_state_.behavior;
535+
return mrm_state_.behavior.type;
530536
}
531537

532538
bool MrmHandler::isStopped()

0 commit comments

Comments
 (0)