@@ -68,7 +68,7 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
68
68
pub_gear_cmd_ =
69
69
create_publisher<autoware_auto_vehicle_msgs::msg::GearCommand>(" ~/output/gear" , rclcpp::QoS{1 });
70
70
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 });
72
72
73
73
// Clients
74
74
client_mrm_pull_over_group_ = create_callback_group (rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -95,8 +95,8 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
95
95
mrm_emergency_stop_status_ = std::make_shared<const tier4_system_msgs::msg::MrmBehaviorStatus>();
96
96
operation_mode_state_ = std::make_shared<const autoware_adapi_v1_msgs::msg::OperationModeState>();
97
97
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;
100
100
is_operation_mode_availability_timeout = false ;
101
101
102
102
// Timer
@@ -227,30 +227,31 @@ void MrmHandler::publishMrmState()
227
227
228
228
void MrmHandler::operateMrm ()
229
229
{
230
- using autoware_adapi_v1_msgs::msg::MrmState;
230
+ using tier4_system_msgs::msg::MrmBehavior;
231
+ using tier4_system_msgs::msg::MrmState;
231
232
232
233
if (mrm_state_.state == MrmState::NORMAL) {
233
234
// 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 ) {
236
237
return ;
237
238
}
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;
240
241
} else {
241
242
handleFailedRequest ();
242
243
}
243
244
return ;
244
245
}
245
246
if (mrm_state_.state == MrmState::MRM_OPERATING) {
246
247
const auto current_mrm_behavior = getCurrentMrmBehavior ();
247
- if (current_mrm_behavior == mrm_state_.behavior ) {
248
+ if (current_mrm_behavior == mrm_state_.behavior . type ) {
248
249
return ;
249
250
}
250
- if (!requestMrmBehavior (mrm_state_.behavior , RequestType::CANCEL)) {
251
+ if (!requestMrmBehavior (mrm_state_.behavior . type , RequestType::CANCEL)) {
251
252
handleFailedRequest ();
252
253
} else if (requestMrmBehavior (current_mrm_behavior, RequestType::CALL)) {
253
- mrm_state_.behavior = current_mrm_behavior;
254
+ mrm_state_.behavior . type = current_mrm_behavior;
254
255
} else {
255
256
handleFailedRequest ();
256
257
}
@@ -270,21 +271,23 @@ void MrmHandler::operateMrm()
270
271
271
272
void MrmHandler::handleFailedRequest ()
272
273
{
273
- using autoware_adapi_v1_msgs::msg::MrmState;
274
+ using tier4_system_msgs::msg::MrmBehavior;
275
+ using tier4_system_msgs::msg::MrmState;
274
276
275
- if (requestMrmBehavior (MrmState ::EMERGENCY_STOP, CALL)) {
277
+ if (requestMrmBehavior (MrmBehavior ::EMERGENCY_STOP, CALL)) {
276
278
if (mrm_state_.state != MrmState::MRM_OPERATING) transitionTo (MrmState::MRM_OPERATING);
277
279
} else {
278
280
transitionTo (MrmState::MRM_FAILED);
279
281
}
280
- mrm_state_.behavior = MrmState ::EMERGENCY_STOP;
282
+ mrm_state_.behavior . type = MrmBehavior ::EMERGENCY_STOP;
281
283
}
282
284
283
285
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,
285
287
RequestType request_type) const
286
288
{
287
- using autoware_adapi_v1_msgs::msg::MrmState;
289
+ using tier4_system_msgs::msg::MrmBehavior;
290
+ using tier4_system_msgs::msg::MrmState;
288
291
289
292
auto request = std::make_shared<tier4_system_msgs::srv::OperateMrm::Request>();
290
293
if (request_type == RequestType::CALL) {
@@ -300,35 +303,35 @@ bool MrmHandler::requestMrmBehavior(
300
303
std::shared_future<std::shared_ptr<tier4_system_msgs::srv::OperateMrm::Response>> future;
301
304
302
305
const auto behavior2string = [](const int behavior) {
303
- if (behavior == MrmState ::NONE) {
306
+ if (behavior == MrmBehavior ::NONE) {
304
307
return " NONE" ;
305
308
}
306
- if (behavior == MrmState ::PULL_OVER) {
309
+ if (behavior == MrmBehavior ::PULL_OVER) {
307
310
return " PULL_OVER" ;
308
311
}
309
- if (behavior == MrmState ::COMFORTABLE_STOP) {
312
+ if (behavior == MrmBehavior ::COMFORTABLE_STOP) {
310
313
return " COMFORTABLE_STOP" ;
311
314
}
312
- if (behavior == MrmState ::EMERGENCY_STOP) {
315
+ if (behavior == MrmBehavior ::EMERGENCY_STOP) {
313
316
return " EMERGENCY_STOP" ;
314
317
}
315
318
const auto msg = " invalid behavior: " + std::to_string (behavior);
316
319
throw std::runtime_error (msg);
317
320
};
318
321
319
322
switch (mrm_behavior) {
320
- case MrmState ::NONE:
323
+ case MrmBehavior ::NONE:
321
324
RCLCPP_WARN (this ->get_logger (), " MRM behavior is None. Do nothing." );
322
325
return true ;
323
- case MrmState ::PULL_OVER: {
326
+ case MrmBehavior ::PULL_OVER: {
324
327
future = client_mrm_pull_over_->async_send_request (request).future .share ();
325
328
break ;
326
329
}
327
- case MrmState ::COMFORTABLE_STOP: {
330
+ case MrmBehavior ::COMFORTABLE_STOP: {
328
331
future = client_mrm_comfortable_stop_->async_send_request (request).future .share ();
329
332
break ;
330
333
}
331
- case MrmState ::EMERGENCY_STOP: {
334
+ case MrmBehavior ::EMERGENCY_STOP: {
332
335
future = client_mrm_emergency_stop_->async_send_request (request).future .share ();
333
336
break ;
334
337
}
@@ -433,7 +436,7 @@ void MrmHandler::onTimer()
433
436
434
437
void MrmHandler::transitionTo (const int new_state)
435
438
{
436
- using autoware_adapi_v1_msgs ::msg::MrmState;
439
+ using tier4_system_msgs ::msg::MrmState;
437
440
438
441
const auto state2string = [](const int state) {
439
442
if (state == MrmState::NORMAL) {
@@ -462,8 +465,9 @@ void MrmHandler::transitionTo(const int new_state)
462
465
463
466
void MrmHandler::updateMrmState ()
464
467
{
465
- using autoware_adapi_v1_msgs::msg::MrmState;
466
468
using autoware_auto_vehicle_msgs::msg::ControlModeReport;
469
+ using tier4_system_msgs::msg::MrmBehavior;
470
+ using tier4_system_msgs::msg::MrmState;
467
471
468
472
// Check emergency
469
473
const bool is_emergency = isEmergency ();
@@ -491,7 +495,7 @@ void MrmHandler::updateMrmState()
491
495
492
496
if (mrm_state_.state == MrmState::MRM_OPERATING) {
493
497
// TODO(TetsuKawa): Check MRC is accomplished
494
- if (mrm_state_.behavior == MrmState ::PULL_OVER) {
498
+ if (mrm_state_.behavior . type == MrmBehavior ::PULL_OVER) {
495
499
if (isStopped () && isArrivedAtGoal ()) {
496
500
transitionTo (MrmState::MRM_SUCCEEDED);
497
501
return ;
@@ -504,7 +508,7 @@ void MrmHandler::updateMrmState()
504
508
}
505
509
} else if (mrm_state_.state == MrmState::MRM_SUCCEEDED) {
506
510
const auto current_mrm_behavior = getCurrentMrmBehavior ();
507
- if (current_mrm_behavior != mrm_state_.behavior ) {
511
+ if (current_mrm_behavior != mrm_state_.behavior . type ) {
508
512
transitionTo (MrmState::MRM_OPERATING);
509
513
}
510
514
} else if (mrm_state_.state == MrmState::MRM_FAILED) {
@@ -516,85 +520,86 @@ void MrmHandler::updateMrmState()
516
520
}
517
521
}
518
522
519
- autoware_adapi_v1_msgs ::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmBehavior ()
523
+ tier4_system_msgs ::msg::MrmBehavior::_type_type MrmHandler::getCurrentMrmBehavior ()
520
524
{
521
- using autoware_adapi_v1_msgs::msg::MrmState;
525
+ using tier4_system_msgs::msg::MrmBehavior;
526
+ using tier4_system_msgs::msg::MrmState;
522
527
using tier4_system_msgs::msg::OperationModeAvailability;
523
528
524
529
// State machine
525
- if (mrm_state_.behavior == MrmState ::NONE) {
530
+ if (mrm_state_.behavior . type == MrmBehavior ::NONE) {
526
531
if (is_operation_mode_availability_timeout) {
527
- return MrmState ::EMERGENCY_STOP;
532
+ return MrmBehavior ::EMERGENCY_STOP;
528
533
}
529
534
if (operation_mode_availability_->pull_over ) {
530
535
if (param_.use_pull_over ) {
531
- return MrmState ::PULL_OVER;
536
+ return MrmBehavior ::PULL_OVER;
532
537
}
533
538
}
534
539
if (operation_mode_availability_->comfortable_stop ) {
535
540
if (param_.use_comfortable_stop ) {
536
- return MrmState ::COMFORTABLE_STOP;
541
+ return MrmBehavior ::COMFORTABLE_STOP;
537
542
}
538
543
}
539
544
if (!operation_mode_availability_->emergency_stop ) {
540
545
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
541
546
}
542
- return MrmState ::EMERGENCY_STOP;
547
+ return MrmBehavior ::EMERGENCY_STOP;
543
548
}
544
- if (mrm_state_.behavior == MrmState ::PULL_OVER) {
549
+ if (mrm_state_.behavior . type == MrmBehavior ::PULL_OVER) {
545
550
if (is_operation_mode_availability_timeout) {
546
- return MrmState ::EMERGENCY_STOP;
551
+ return MrmBehavior ::EMERGENCY_STOP;
547
552
}
548
553
if (operation_mode_availability_->pull_over ) {
549
554
if (param_.use_pull_over ) {
550
- return MrmState ::PULL_OVER;
555
+ return MrmBehavior ::PULL_OVER;
551
556
}
552
557
}
553
558
if (operation_mode_availability_->comfortable_stop ) {
554
559
if (param_.use_comfortable_stop ) {
555
- return MrmState ::COMFORTABLE_STOP;
560
+ return MrmBehavior ::COMFORTABLE_STOP;
556
561
}
557
562
}
558
563
if (!operation_mode_availability_->emergency_stop ) {
559
564
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
560
565
}
561
- return MrmState ::EMERGENCY_STOP;
566
+ return MrmBehavior ::EMERGENCY_STOP;
562
567
}
563
- if (mrm_state_.behavior == MrmState ::COMFORTABLE_STOP) {
568
+ if (mrm_state_.behavior . type == MrmBehavior ::COMFORTABLE_STOP) {
564
569
if (is_operation_mode_availability_timeout) {
565
- return MrmState ::EMERGENCY_STOP;
570
+ return MrmBehavior ::EMERGENCY_STOP;
566
571
}
567
572
if (isStopped () && operation_mode_availability_->pull_over ) {
568
573
if (param_.use_pull_over && param_.use_pull_over_after_stopped ) {
569
- return MrmState ::PULL_OVER;
574
+ return MrmBehavior ::PULL_OVER;
570
575
}
571
576
}
572
577
if (operation_mode_availability_->comfortable_stop ) {
573
578
if (param_.use_comfortable_stop ) {
574
- return MrmState ::COMFORTABLE_STOP;
579
+ return MrmBehavior ::COMFORTABLE_STOP;
575
580
}
576
581
}
577
582
if (!operation_mode_availability_->emergency_stop ) {
578
583
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
579
584
}
580
- return MrmState ::EMERGENCY_STOP;
585
+ return MrmBehavior ::EMERGENCY_STOP;
581
586
}
582
- if (mrm_state_.behavior == MrmState ::EMERGENCY_STOP) {
587
+ if (mrm_state_.behavior . type == MrmBehavior ::EMERGENCY_STOP) {
583
588
if (is_operation_mode_availability_timeout) {
584
- return MrmState ::EMERGENCY_STOP;
589
+ return MrmBehavior ::EMERGENCY_STOP;
585
590
}
586
591
if (isStopped () && operation_mode_availability_->pull_over ) {
587
592
if (param_.use_pull_over && param_.use_pull_over_after_stopped ) {
588
- return MrmState ::PULL_OVER;
593
+ return MrmBehavior ::PULL_OVER;
589
594
}
590
595
}
591
596
if (!operation_mode_availability_->emergency_stop ) {
592
597
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
593
598
}
594
- return MrmState ::EMERGENCY_STOP;
599
+ return MrmBehavior ::EMERGENCY_STOP;
595
600
}
596
601
597
- return mrm_state_.behavior ;
602
+ return mrm_state_.behavior . type ;
598
603
}
599
604
600
605
bool MrmHandler::isStopped ()
0 commit comments