@@ -65,7 +65,7 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
65
65
pub_gear_cmd_ =
66
66
create_publisher<autoware_auto_vehicle_msgs::msg::GearCommand>(" ~/output/gear" , rclcpp::QoS{1 });
67
67
pub_mrm_state_ =
68
- create_publisher<autoware_adapi_v1_msgs ::msg::MrmState>(" ~/output/mrm/state" , rclcpp::QoS{1 });
68
+ create_publisher<tier4_system_msgs ::msg::MrmState>(" ~/output/mrm/state" , rclcpp::QoS{1 });
69
69
70
70
// Clients
71
71
client_mrm_pull_over_group_ = create_callback_group (rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -92,8 +92,8 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
92
92
mrm_emergency_stop_status_ = std::make_shared<const tier4_system_msgs::msg::MrmBehaviorStatus>();
93
93
operation_mode_state_ = std::make_shared<const autoware_adapi_v1_msgs::msg::OperationModeState>();
94
94
mrm_state_.stamp = this ->now ();
95
- mrm_state_.state = autoware_adapi_v1_msgs ::msg::MrmState::NORMAL;
96
- mrm_state_.behavior = autoware_adapi_v1_msgs ::msg::MrmState ::NONE;
95
+ mrm_state_.state = tier4_system_msgs ::msg::MrmState::NORMAL;
96
+ mrm_state_.behavior . type = tier4_system_msgs ::msg::MrmBehavior ::NONE;
97
97
is_operation_mode_availability_timeout = false ;
98
98
99
99
// Timer
@@ -208,30 +208,31 @@ void MrmHandler::publishMrmState()
208
208
209
209
void MrmHandler::operateMrm ()
210
210
{
211
- using autoware_adapi_v1_msgs::msg::MrmState;
211
+ using tier4_system_msgs::msg::MrmBehavior;
212
+ using tier4_system_msgs::msg::MrmState;
212
213
213
214
if (mrm_state_.state == MrmState::NORMAL) {
214
215
// Cancel MRM behavior when returning to NORMAL state
215
- const auto current_mrm_behavior = MrmState ::NONE;
216
- if (current_mrm_behavior == mrm_state_.behavior ) {
216
+ const auto current_mrm_behavior = MrmBehavior ::NONE;
217
+ if (current_mrm_behavior == mrm_state_.behavior . type ) {
217
218
return ;
218
219
}
219
- if (requestMrmBehavior (mrm_state_.behavior , RequestType::CANCEL)) {
220
- mrm_state_.behavior = current_mrm_behavior;
220
+ if (requestMrmBehavior (mrm_state_.behavior . type , RequestType::CANCEL)) {
221
+ mrm_state_.behavior . type = current_mrm_behavior;
221
222
} else {
222
223
handleFailedRequest ();
223
224
}
224
225
return ;
225
226
}
226
227
if (mrm_state_.state == MrmState::MRM_OPERATING) {
227
228
const auto current_mrm_behavior = getCurrentMrmBehavior ();
228
- if (current_mrm_behavior == mrm_state_.behavior ) {
229
+ if (current_mrm_behavior == mrm_state_.behavior . type ) {
229
230
return ;
230
231
}
231
- if (!requestMrmBehavior (mrm_state_.behavior , RequestType::CANCEL)) {
232
+ if (!requestMrmBehavior (mrm_state_.behavior . type , RequestType::CANCEL)) {
232
233
handleFailedRequest ();
233
234
} else if (requestMrmBehavior (current_mrm_behavior, RequestType::CALL)) {
234
- mrm_state_.behavior = current_mrm_behavior;
235
+ mrm_state_.behavior . type = current_mrm_behavior;
235
236
} else {
236
237
handleFailedRequest ();
237
238
}
@@ -251,21 +252,23 @@ void MrmHandler::operateMrm()
251
252
252
253
void MrmHandler::handleFailedRequest ()
253
254
{
254
- using autoware_adapi_v1_msgs::msg::MrmState;
255
+ using tier4_system_msgs::msg::MrmBehavior;
256
+ using tier4_system_msgs::msg::MrmState;
255
257
256
- if (requestMrmBehavior (MrmState ::EMERGENCY_STOP, CALL)) {
258
+ if (requestMrmBehavior (MrmBehavior ::EMERGENCY_STOP, CALL)) {
257
259
if (mrm_state_.state != MrmState::MRM_OPERATING) transitionTo (MrmState::MRM_OPERATING);
258
260
} else {
259
261
transitionTo (MrmState::MRM_FAILED);
260
262
}
261
- mrm_state_.behavior = MrmState ::EMERGENCY_STOP;
263
+ mrm_state_.behavior . type = MrmBehavior ::EMERGENCY_STOP;
262
264
}
263
265
264
266
bool MrmHandler::requestMrmBehavior (
265
- const autoware_adapi_v1_msgs ::msg::MrmState::_behavior_type & mrm_behavior,
267
+ const tier4_system_msgs ::msg::MrmBehavior::_type_type & mrm_behavior,
266
268
RequestType request_type) const
267
269
{
268
- using autoware_adapi_v1_msgs::msg::MrmState;
270
+ using tier4_system_msgs::msg::MrmBehavior;
271
+ using tier4_system_msgs::msg::MrmState;
269
272
270
273
auto request = std::make_shared<tier4_system_msgs::srv::OperateMrm::Request>();
271
274
if (request_type == RequestType::CALL) {
@@ -281,35 +284,35 @@ bool MrmHandler::requestMrmBehavior(
281
284
std::shared_future<std::shared_ptr<tier4_system_msgs::srv::OperateMrm::Response>> future;
282
285
283
286
const auto behavior2string = [](const int behavior) {
284
- if (behavior == MrmState ::NONE) {
287
+ if (behavior == MrmBehavior ::NONE) {
285
288
return " NONE" ;
286
289
}
287
- if (behavior == MrmState ::PULL_OVER) {
290
+ if (behavior == MrmBehavior ::PULL_OVER) {
288
291
return " PULL_OVER" ;
289
292
}
290
- if (behavior == MrmState ::COMFORTABLE_STOP) {
293
+ if (behavior == MrmBehavior ::COMFORTABLE_STOP) {
291
294
return " COMFORTABLE_STOP" ;
292
295
}
293
- if (behavior == MrmState ::EMERGENCY_STOP) {
296
+ if (behavior == MrmBehavior ::EMERGENCY_STOP) {
294
297
return " EMERGENCY_STOP" ;
295
298
}
296
299
const auto msg = " invalid behavior: " + std::to_string (behavior);
297
300
throw std::runtime_error (msg);
298
301
};
299
302
300
303
switch (mrm_behavior) {
301
- case MrmState ::NONE:
304
+ case MrmBehavior ::NONE:
302
305
RCLCPP_WARN (this ->get_logger (), " MRM behavior is None. Do nothing." );
303
306
return true ;
304
- case MrmState ::PULL_OVER: {
307
+ case MrmBehavior ::PULL_OVER: {
305
308
future = client_mrm_pull_over_->async_send_request (request).future .share ();
306
309
break ;
307
310
}
308
- case MrmState ::COMFORTABLE_STOP: {
311
+ case MrmBehavior ::COMFORTABLE_STOP: {
309
312
future = client_mrm_comfortable_stop_->async_send_request (request).future .share ();
310
313
break ;
311
314
}
312
- case MrmState ::EMERGENCY_STOP: {
315
+ case MrmBehavior ::EMERGENCY_STOP: {
313
316
future = client_mrm_emergency_stop_->async_send_request (request).future .share ();
314
317
break ;
315
318
}
@@ -414,7 +417,7 @@ void MrmHandler::onTimer()
414
417
415
418
void MrmHandler::transitionTo (const int new_state)
416
419
{
417
- using autoware_adapi_v1_msgs ::msg::MrmState;
420
+ using tier4_system_msgs ::msg::MrmState;
418
421
419
422
const auto state2string = [](const int state) {
420
423
if (state == MrmState::NORMAL) {
@@ -443,8 +446,9 @@ void MrmHandler::transitionTo(const int new_state)
443
446
444
447
void MrmHandler::updateMrmState ()
445
448
{
446
- using autoware_adapi_v1_msgs::msg::MrmState;
447
449
using autoware_auto_vehicle_msgs::msg::ControlModeReport;
450
+ using tier4_system_msgs::msg::MrmBehavior;
451
+ using tier4_system_msgs::msg::MrmState;
448
452
449
453
// Check emergency
450
454
const bool is_emergency = isEmergency ();
@@ -471,7 +475,7 @@ void MrmHandler::updateMrmState()
471
475
472
476
if (mrm_state_.state == MrmState::MRM_OPERATING) {
473
477
// TODO(TetsuKawa): Check MRC is accomplished
474
- if (mrm_state_.behavior == MrmState ::PULL_OVER) {
478
+ if (mrm_state_.behavior . type == MrmBehavior ::PULL_OVER) {
475
479
if (isStopped () && isArrivedAtGoal ()) {
476
480
transitionTo (MrmState::MRM_SUCCEEDED);
477
481
return ;
@@ -484,7 +488,7 @@ void MrmHandler::updateMrmState()
484
488
}
485
489
} else if (mrm_state_.state == MrmState::MRM_SUCCEEDED) {
486
490
const auto current_mrm_behavior = getCurrentMrmBehavior ();
487
- if (current_mrm_behavior != mrm_state_.behavior ) {
491
+ if (current_mrm_behavior != mrm_state_.behavior . type ) {
488
492
transitionTo (MrmState::MRM_OPERATING);
489
493
}
490
494
} else if (mrm_state_.state == MrmState::MRM_FAILED) {
@@ -496,85 +500,86 @@ void MrmHandler::updateMrmState()
496
500
}
497
501
}
498
502
499
- autoware_adapi_v1_msgs ::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmBehavior ()
503
+ tier4_system_msgs ::msg::MrmBehavior::_type_type MrmHandler::getCurrentMrmBehavior ()
500
504
{
501
- using autoware_adapi_v1_msgs::msg::MrmState;
505
+ using tier4_system_msgs::msg::MrmBehavior;
506
+ using tier4_system_msgs::msg::MrmState;
502
507
using tier4_system_msgs::msg::OperationModeAvailability;
503
508
504
509
// State machine
505
- if (mrm_state_.behavior == MrmState ::NONE) {
510
+ if (mrm_state_.behavior . type == MrmBehavior ::NONE) {
506
511
if (is_operation_mode_availability_timeout) {
507
- return MrmState ::EMERGENCY_STOP;
512
+ return MrmBehavior ::EMERGENCY_STOP;
508
513
}
509
514
if (operation_mode_availability_->pull_over ) {
510
515
if (param_.use_pull_over ) {
511
- return MrmState ::PULL_OVER;
516
+ return MrmBehavior ::PULL_OVER;
512
517
}
513
518
}
514
519
if (operation_mode_availability_->comfortable_stop ) {
515
520
if (param_.use_comfortable_stop ) {
516
- return MrmState ::COMFORTABLE_STOP;
521
+ return MrmBehavior ::COMFORTABLE_STOP;
517
522
}
518
523
}
519
524
if (!operation_mode_availability_->emergency_stop ) {
520
525
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
521
526
}
522
- return MrmState ::EMERGENCY_STOP;
527
+ return MrmBehavior ::EMERGENCY_STOP;
523
528
}
524
- if (mrm_state_.behavior == MrmState ::PULL_OVER) {
529
+ if (mrm_state_.behavior . type == MrmBehavior ::PULL_OVER) {
525
530
if (is_operation_mode_availability_timeout) {
526
- return MrmState ::EMERGENCY_STOP;
531
+ return MrmBehavior ::EMERGENCY_STOP;
527
532
}
528
533
if (operation_mode_availability_->pull_over ) {
529
534
if (param_.use_pull_over ) {
530
- return MrmState ::PULL_OVER;
535
+ return MrmBehavior ::PULL_OVER;
531
536
}
532
537
}
533
538
if (operation_mode_availability_->comfortable_stop ) {
534
539
if (param_.use_comfortable_stop ) {
535
- return MrmState ::COMFORTABLE_STOP;
540
+ return MrmBehavior ::COMFORTABLE_STOP;
536
541
}
537
542
}
538
543
if (!operation_mode_availability_->emergency_stop ) {
539
544
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
540
545
}
541
- return MrmState ::EMERGENCY_STOP;
546
+ return MrmBehavior ::EMERGENCY_STOP;
542
547
}
543
- if (mrm_state_.behavior == MrmState ::COMFORTABLE_STOP) {
548
+ if (mrm_state_.behavior . type == MrmBehavior ::COMFORTABLE_STOP) {
544
549
if (is_operation_mode_availability_timeout) {
545
- return MrmState ::EMERGENCY_STOP;
550
+ return MrmBehavior ::EMERGENCY_STOP;
546
551
}
547
552
if (isStopped () && operation_mode_availability_->pull_over ) {
548
553
if (param_.use_pull_over ) {
549
- return MrmState ::PULL_OVER;
554
+ return MrmBehavior ::PULL_OVER;
550
555
}
551
556
}
552
557
if (operation_mode_availability_->comfortable_stop ) {
553
558
if (param_.use_comfortable_stop ) {
554
- return MrmState ::COMFORTABLE_STOP;
559
+ return MrmBehavior ::COMFORTABLE_STOP;
555
560
}
556
561
}
557
562
if (!operation_mode_availability_->emergency_stop ) {
558
563
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
559
564
}
560
- return MrmState ::EMERGENCY_STOP;
565
+ return MrmBehavior ::EMERGENCY_STOP;
561
566
}
562
- if (mrm_state_.behavior == MrmState ::EMERGENCY_STOP) {
567
+ if (mrm_state_.behavior . type == MrmBehavior ::EMERGENCY_STOP) {
563
568
if (is_operation_mode_availability_timeout) {
564
- return MrmState ::EMERGENCY_STOP;
569
+ return MrmBehavior ::EMERGENCY_STOP;
565
570
}
566
571
if (isStopped () && operation_mode_availability_->pull_over ) {
567
572
if (param_.use_pull_over ) {
568
- return MrmState ::PULL_OVER;
573
+ return MrmBehavior ::PULL_OVER;
569
574
}
570
575
}
571
576
if (!operation_mode_availability_->emergency_stop ) {
572
577
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
573
578
}
574
- return MrmState ::EMERGENCY_STOP;
579
+ return MrmBehavior ::EMERGENCY_STOP;
575
580
}
576
581
577
- return mrm_state_.behavior ;
582
+ return mrm_state_.behavior . type ;
578
583
}
579
584
580
585
bool MrmHandler::isStopped ()
0 commit comments