Skip to content

Commit 835a843

Browse files
TetsuKawamkuri
authored andcommitted
feat: change mrm state type to internal one (#1392)
Signed-off-by: TetsuKawa <kawaguchitnon@icloud.com>
1 parent d7609d8 commit 835a843

File tree

2 files changed

+61
-55
lines changed

2 files changed

+61
-55
lines changed

system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp

+6-5
Original file line numberDiff line numberDiff line change
@@ -25,12 +25,13 @@
2525
// Autoware
2626
#include <tier4_autoware_utils/ros/update_param.hpp>
2727

28-
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
2928
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
3029
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
3130
#include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
3231
#include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp>
32+
#include <tier4_system_msgs/msg/mrm_behavior.hpp>
3333
#include <tier4_system_msgs/msg/mrm_behavior_status.hpp>
34+
#include <tier4_system_msgs/msg/mrm_state.hpp>
3435
#include <tier4_system_msgs/msg/operation_mode_availability.hpp>
3536
#include <tier4_system_msgs/srv/operate_mrm.hpp>
3637

@@ -117,9 +118,9 @@ class MrmHandler : public rclcpp::Node
117118
void publishHazardCmd();
118119
void publishGearCmd();
119120

120-
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::MrmState>::SharedPtr pub_mrm_state_;
121+
rclcpp::Publisher<tier4_system_msgs::msg::MrmState>::SharedPtr pub_mrm_state_;
121122

122-
autoware_adapi_v1_msgs::msg::MrmState mrm_state_;
123+
tier4_system_msgs::msg::MrmState mrm_state_;
123124
void publishMrmState();
124125

125126
// parameter callback
@@ -136,7 +137,7 @@ class MrmHandler : public rclcpp::Node
136137
rclcpp::Client<tier4_system_msgs::srv::OperateMrm>::SharedPtr client_mrm_emergency_stop_;
137138

138139
bool requestMrmBehavior(
139-
const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior,
140+
const tier4_system_msgs::msg::MrmBehavior::_type_type & mrm_behavior,
140141
RequestType request_type) const;
141142
void logMrmCallingResult(
142143
const tier4_system_msgs::srv::OperateMrm::Response & result, const std::string & behavior,
@@ -164,7 +165,7 @@ class MrmHandler : public rclcpp::Node
164165
void updateMrmState();
165166
void operateMrm();
166167
void handleFailedRequest();
167-
autoware_adapi_v1_msgs::msg::MrmState::_behavior_type getCurrentMrmBehavior();
168+
tier4_system_msgs::msg::MrmBehavior::_type_type getCurrentMrmBehavior();
168169
bool isStopped();
169170
bool isEmergency() const;
170171
bool isArrivedAtGoal();

system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+55-50
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
6868
pub_gear_cmd_ =
6969
create_publisher<autoware_auto_vehicle_msgs::msg::GearCommand>("~/output/gear", rclcpp::QoS{1});
7070
pub_mrm_state_ =
71-
create_publisher<autoware_adapi_v1_msgs::msg::MrmState>("~/output/mrm/state", rclcpp::QoS{1});
71+
create_publisher<tier4_system_msgs::msg::MrmState>("~/output/mrm/state", rclcpp::QoS{1});
7272

7373
// Clients
7474
client_mrm_pull_over_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -95,8 +95,8 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
9595
mrm_emergency_stop_status_ = std::make_shared<const tier4_system_msgs::msg::MrmBehaviorStatus>();
9696
operation_mode_state_ = std::make_shared<const autoware_adapi_v1_msgs::msg::OperationModeState>();
9797
mrm_state_.stamp = this->now();
98-
mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::NORMAL;
99-
mrm_state_.behavior = autoware_adapi_v1_msgs::msg::MrmState::NONE;
98+
mrm_state_.state = tier4_system_msgs::msg::MrmState::NORMAL;
99+
mrm_state_.behavior.type = tier4_system_msgs::msg::MrmBehavior::NONE;
100100
is_operation_mode_availability_timeout = false;
101101

102102
// Timer
@@ -227,30 +227,31 @@ void MrmHandler::publishMrmState()
227227

228228
void MrmHandler::operateMrm()
229229
{
230-
using autoware_adapi_v1_msgs::msg::MrmState;
230+
using tier4_system_msgs::msg::MrmBehavior;
231+
using tier4_system_msgs::msg::MrmState;
231232

232233
if (mrm_state_.state == MrmState::NORMAL) {
233234
// Cancel MRM behavior when returning to NORMAL state
234-
const auto current_mrm_behavior = MrmState::NONE;
235-
if (current_mrm_behavior == mrm_state_.behavior) {
235+
const auto current_mrm_behavior = MrmBehavior::NONE;
236+
if (current_mrm_behavior == mrm_state_.behavior.type) {
236237
return;
237238
}
238-
if (requestMrmBehavior(mrm_state_.behavior, RequestType::CANCEL)) {
239-
mrm_state_.behavior = current_mrm_behavior;
239+
if (requestMrmBehavior(mrm_state_.behavior.type, RequestType::CANCEL)) {
240+
mrm_state_.behavior.type = current_mrm_behavior;
240241
} else {
241242
handleFailedRequest();
242243
}
243244
return;
244245
}
245246
if (mrm_state_.state == MrmState::MRM_OPERATING) {
246247
const auto current_mrm_behavior = getCurrentMrmBehavior();
247-
if (current_mrm_behavior == mrm_state_.behavior) {
248+
if (current_mrm_behavior == mrm_state_.behavior.type) {
248249
return;
249250
}
250-
if (!requestMrmBehavior(mrm_state_.behavior, RequestType::CANCEL)) {
251+
if (!requestMrmBehavior(mrm_state_.behavior.type, RequestType::CANCEL)) {
251252
handleFailedRequest();
252253
} else if (requestMrmBehavior(current_mrm_behavior, RequestType::CALL)) {
253-
mrm_state_.behavior = current_mrm_behavior;
254+
mrm_state_.behavior.type = current_mrm_behavior;
254255
} else {
255256
handleFailedRequest();
256257
}
@@ -270,21 +271,23 @@ void MrmHandler::operateMrm()
270271

271272
void MrmHandler::handleFailedRequest()
272273
{
273-
using autoware_adapi_v1_msgs::msg::MrmState;
274+
using tier4_system_msgs::msg::MrmBehavior;
275+
using tier4_system_msgs::msg::MrmState;
274276

275-
if (requestMrmBehavior(MrmState::EMERGENCY_STOP, CALL)) {
277+
if (requestMrmBehavior(MrmBehavior::EMERGENCY_STOP, CALL)) {
276278
if (mrm_state_.state != MrmState::MRM_OPERATING) transitionTo(MrmState::MRM_OPERATING);
277279
} else {
278280
transitionTo(MrmState::MRM_FAILED);
279281
}
280-
mrm_state_.behavior = MrmState::EMERGENCY_STOP;
282+
mrm_state_.behavior.type = MrmBehavior::EMERGENCY_STOP;
281283
}
282284

283285
bool MrmHandler::requestMrmBehavior(
284-
const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior,
286+
const tier4_system_msgs::msg::MrmBehavior::_type_type & mrm_behavior,
285287
RequestType request_type) const
286288
{
287-
using autoware_adapi_v1_msgs::msg::MrmState;
289+
using tier4_system_msgs::msg::MrmBehavior;
290+
using tier4_system_msgs::msg::MrmState;
288291

289292
auto request = std::make_shared<tier4_system_msgs::srv::OperateMrm::Request>();
290293
if (request_type == RequestType::CALL) {
@@ -300,35 +303,35 @@ bool MrmHandler::requestMrmBehavior(
300303
std::shared_future<std::shared_ptr<tier4_system_msgs::srv::OperateMrm::Response>> future;
301304

302305
const auto behavior2string = [](const int behavior) {
303-
if (behavior == MrmState::NONE) {
306+
if (behavior == MrmBehavior::NONE) {
304307
return "NONE";
305308
}
306-
if (behavior == MrmState::PULL_OVER) {
309+
if (behavior == MrmBehavior::PULL_OVER) {
307310
return "PULL_OVER";
308311
}
309-
if (behavior == MrmState::COMFORTABLE_STOP) {
312+
if (behavior == MrmBehavior::COMFORTABLE_STOP) {
310313
return "COMFORTABLE_STOP";
311314
}
312-
if (behavior == MrmState::EMERGENCY_STOP) {
315+
if (behavior == MrmBehavior::EMERGENCY_STOP) {
313316
return "EMERGENCY_STOP";
314317
}
315318
const auto msg = "invalid behavior: " + std::to_string(behavior);
316319
throw std::runtime_error(msg);
317320
};
318321

319322
switch (mrm_behavior) {
320-
case MrmState::NONE:
323+
case MrmBehavior::NONE:
321324
RCLCPP_WARN(this->get_logger(), "MRM behavior is None. Do nothing.");
322325
return true;
323-
case MrmState::PULL_OVER: {
326+
case MrmBehavior::PULL_OVER: {
324327
future = client_mrm_pull_over_->async_send_request(request).future.share();
325328
break;
326329
}
327-
case MrmState::COMFORTABLE_STOP: {
330+
case MrmBehavior::COMFORTABLE_STOP: {
328331
future = client_mrm_comfortable_stop_->async_send_request(request).future.share();
329332
break;
330333
}
331-
case MrmState::EMERGENCY_STOP: {
334+
case MrmBehavior::EMERGENCY_STOP: {
332335
future = client_mrm_emergency_stop_->async_send_request(request).future.share();
333336
break;
334337
}
@@ -433,7 +436,7 @@ void MrmHandler::onTimer()
433436

434437
void MrmHandler::transitionTo(const int new_state)
435438
{
436-
using autoware_adapi_v1_msgs::msg::MrmState;
439+
using tier4_system_msgs::msg::MrmState;
437440

438441
const auto state2string = [](const int state) {
439442
if (state == MrmState::NORMAL) {
@@ -462,8 +465,9 @@ void MrmHandler::transitionTo(const int new_state)
462465

463466
void MrmHandler::updateMrmState()
464467
{
465-
using autoware_adapi_v1_msgs::msg::MrmState;
466468
using autoware_auto_vehicle_msgs::msg::ControlModeReport;
469+
using tier4_system_msgs::msg::MrmBehavior;
470+
using tier4_system_msgs::msg::MrmState;
467471

468472
// Check emergency
469473
const bool is_emergency = isEmergency();
@@ -491,7 +495,7 @@ void MrmHandler::updateMrmState()
491495

492496
if (mrm_state_.state == MrmState::MRM_OPERATING) {
493497
// TODO(TetsuKawa): Check MRC is accomplished
494-
if (mrm_state_.behavior == MrmState::PULL_OVER) {
498+
if (mrm_state_.behavior.type == MrmBehavior::PULL_OVER) {
495499
if (isStopped() && isArrivedAtGoal()) {
496500
transitionTo(MrmState::MRM_SUCCEEDED);
497501
return;
@@ -504,7 +508,7 @@ void MrmHandler::updateMrmState()
504508
}
505509
} else if (mrm_state_.state == MrmState::MRM_SUCCEEDED) {
506510
const auto current_mrm_behavior = getCurrentMrmBehavior();
507-
if (current_mrm_behavior != mrm_state_.behavior) {
511+
if (current_mrm_behavior != mrm_state_.behavior.type) {
508512
transitionTo(MrmState::MRM_OPERATING);
509513
}
510514
} else if (mrm_state_.state == MrmState::MRM_FAILED) {
@@ -516,85 +520,86 @@ void MrmHandler::updateMrmState()
516520
}
517521
}
518522

519-
autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmBehavior()
523+
tier4_system_msgs::msg::MrmBehavior::_type_type MrmHandler::getCurrentMrmBehavior()
520524
{
521-
using autoware_adapi_v1_msgs::msg::MrmState;
525+
using tier4_system_msgs::msg::MrmBehavior;
526+
using tier4_system_msgs::msg::MrmState;
522527
using tier4_system_msgs::msg::OperationModeAvailability;
523528

524529
// State machine
525-
if (mrm_state_.behavior == MrmState::NONE) {
530+
if (mrm_state_.behavior.type == MrmBehavior::NONE) {
526531
if (is_operation_mode_availability_timeout) {
527-
return MrmState::EMERGENCY_STOP;
532+
return MrmBehavior::EMERGENCY_STOP;
528533
}
529534
if (operation_mode_availability_->pull_over) {
530535
if (param_.use_pull_over) {
531-
return MrmState::PULL_OVER;
536+
return MrmBehavior::PULL_OVER;
532537
}
533538
}
534539
if (operation_mode_availability_->comfortable_stop) {
535540
if (param_.use_comfortable_stop) {
536-
return MrmState::COMFORTABLE_STOP;
541+
return MrmBehavior::COMFORTABLE_STOP;
537542
}
538543
}
539544
if (!operation_mode_availability_->emergency_stop) {
540545
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
541546
}
542-
return MrmState::EMERGENCY_STOP;
547+
return MrmBehavior::EMERGENCY_STOP;
543548
}
544-
if (mrm_state_.behavior == MrmState::PULL_OVER) {
549+
if (mrm_state_.behavior.type == MrmBehavior::PULL_OVER) {
545550
if (is_operation_mode_availability_timeout) {
546-
return MrmState::EMERGENCY_STOP;
551+
return MrmBehavior::EMERGENCY_STOP;
547552
}
548553
if (operation_mode_availability_->pull_over) {
549554
if (param_.use_pull_over) {
550-
return MrmState::PULL_OVER;
555+
return MrmBehavior::PULL_OVER;
551556
}
552557
}
553558
if (operation_mode_availability_->comfortable_stop) {
554559
if (param_.use_comfortable_stop) {
555-
return MrmState::COMFORTABLE_STOP;
560+
return MrmBehavior::COMFORTABLE_STOP;
556561
}
557562
}
558563
if (!operation_mode_availability_->emergency_stop) {
559564
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
560565
}
561-
return MrmState::EMERGENCY_STOP;
566+
return MrmBehavior::EMERGENCY_STOP;
562567
}
563-
if (mrm_state_.behavior == MrmState::COMFORTABLE_STOP) {
568+
if (mrm_state_.behavior.type == MrmBehavior::COMFORTABLE_STOP) {
564569
if (is_operation_mode_availability_timeout) {
565-
return MrmState::EMERGENCY_STOP;
570+
return MrmBehavior::EMERGENCY_STOP;
566571
}
567572
if (isStopped() && operation_mode_availability_->pull_over) {
568573
if (param_.use_pull_over && param_.use_pull_over_after_stopped) {
569-
return MrmState::PULL_OVER;
574+
return MrmBehavior::PULL_OVER;
570575
}
571576
}
572577
if (operation_mode_availability_->comfortable_stop) {
573578
if (param_.use_comfortable_stop) {
574-
return MrmState::COMFORTABLE_STOP;
579+
return MrmBehavior::COMFORTABLE_STOP;
575580
}
576581
}
577582
if (!operation_mode_availability_->emergency_stop) {
578583
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
579584
}
580-
return MrmState::EMERGENCY_STOP;
585+
return MrmBehavior::EMERGENCY_STOP;
581586
}
582-
if (mrm_state_.behavior == MrmState::EMERGENCY_STOP) {
587+
if (mrm_state_.behavior.type == MrmBehavior::EMERGENCY_STOP) {
583588
if (is_operation_mode_availability_timeout) {
584-
return MrmState::EMERGENCY_STOP;
589+
return MrmBehavior::EMERGENCY_STOP;
585590
}
586591
if (isStopped() && operation_mode_availability_->pull_over) {
587592
if (param_.use_pull_over && param_.use_pull_over_after_stopped) {
588-
return MrmState::PULL_OVER;
593+
return MrmBehavior::PULL_OVER;
589594
}
590595
}
591596
if (!operation_mode_availability_->emergency_stop) {
592597
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
593598
}
594-
return MrmState::EMERGENCY_STOP;
599+
return MrmBehavior::EMERGENCY_STOP;
595600
}
596601

597-
return mrm_state_.behavior;
602+
return mrm_state_.behavior.type;
598603
}
599604

600605
bool MrmHandler::isStopped()

0 commit comments

Comments
 (0)