@@ -51,7 +51,7 @@ MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler"
51
51
pub_gear_cmd_ =
52
52
create_publisher<autoware_vehicle_msgs::msg::GearCommand>(" ~/output/gear" , rclcpp::QoS{1 });
53
53
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 });
55
55
56
56
// Clients
57
57
client_mrm_pull_over_group_ = create_callback_group (rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -77,8 +77,8 @@ MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler"
77
77
78
78
// Initialize
79
79
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;
82
82
is_operation_mode_availability_timeout = false ;
83
83
84
84
// Timer
@@ -163,30 +163,31 @@ void MrmHandler::publishMrmState()
163
163
164
164
void MrmHandler::operateMrm ()
165
165
{
166
- using autoware_adapi_v1_msgs::msg::MrmState;
166
+ using tier4_system_msgs::msg::MrmBehavior;
167
+ using tier4_system_msgs::msg::MrmState;
167
168
168
169
if (mrm_state_.state == MrmState::NORMAL) {
169
170
// 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 ) {
172
173
return ;
173
174
}
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;
176
177
} else {
177
178
handleFailedRequest ();
178
179
}
179
180
return ;
180
181
}
181
182
if (mrm_state_.state == MrmState::MRM_OPERATING) {
182
183
const auto current_mrm_behavior = getCurrentMrmBehavior ();
183
- if (current_mrm_behavior == mrm_state_.behavior ) {
184
+ if (current_mrm_behavior == mrm_state_.behavior . type ) {
184
185
return ;
185
186
}
186
- if (!requestMrmBehavior (mrm_state_.behavior , RequestType::CANCEL)) {
187
+ if (!requestMrmBehavior (mrm_state_.behavior . type , RequestType::CANCEL)) {
187
188
handleFailedRequest ();
188
189
} else if (requestMrmBehavior (current_mrm_behavior, RequestType::CALL)) {
189
- mrm_state_.behavior = current_mrm_behavior;
190
+ mrm_state_.behavior . type = current_mrm_behavior;
190
191
} else {
191
192
handleFailedRequest ();
192
193
}
@@ -206,21 +207,23 @@ void MrmHandler::operateMrm()
206
207
207
208
void MrmHandler::handleFailedRequest ()
208
209
{
209
- using autoware_adapi_v1_msgs::msg::MrmState;
210
+ using tier4_system_msgs::msg::MrmBehavior;
211
+ using tier4_system_msgs::msg::MrmState;
210
212
211
- if (requestMrmBehavior (MrmState ::EMERGENCY_STOP, CALL)) {
213
+ if (requestMrmBehavior (MrmBehavior ::EMERGENCY_STOP, CALL)) {
212
214
if (mrm_state_.state != MrmState::MRM_OPERATING) transitionTo (MrmState::MRM_OPERATING);
213
215
} else {
214
216
transitionTo (MrmState::MRM_FAILED);
215
217
}
216
- mrm_state_.behavior = MrmState ::EMERGENCY_STOP;
218
+ mrm_state_.behavior . type = MrmBehavior ::EMERGENCY_STOP;
217
219
}
218
220
219
221
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,
221
223
RequestType request_type) const
222
224
{
223
- using autoware_adapi_v1_msgs::msg::MrmState;
225
+ using tier4_system_msgs::msg::MrmBehavior;
226
+ using tier4_system_msgs::msg::MrmState;
224
227
225
228
auto request = std::make_shared<tier4_system_msgs::srv::OperateMrm::Request>();
226
229
if (request_type == RequestType::CALL) {
@@ -236,35 +239,35 @@ bool MrmHandler::requestMrmBehavior(
236
239
std::shared_future<std::shared_ptr<tier4_system_msgs::srv::OperateMrm::Response>> future;
237
240
238
241
const auto behavior2string = [](const int behavior) {
239
- if (behavior == MrmState ::NONE) {
242
+ if (behavior == MrmBehavior ::NONE) {
240
243
return " NONE" ;
241
244
}
242
- if (behavior == MrmState ::PULL_OVER) {
245
+ if (behavior == MrmBehavior ::PULL_OVER) {
243
246
return " PULL_OVER" ;
244
247
}
245
- if (behavior == MrmState ::COMFORTABLE_STOP) {
248
+ if (behavior == MrmBehavior ::COMFORTABLE_STOP) {
246
249
return " COMFORTABLE_STOP" ;
247
250
}
248
- if (behavior == MrmState ::EMERGENCY_STOP) {
251
+ if (behavior == MrmBehavior ::EMERGENCY_STOP) {
249
252
return " EMERGENCY_STOP" ;
250
253
}
251
254
const auto msg = " invalid behavior: " + std::to_string (behavior);
252
255
throw std::runtime_error (msg);
253
256
};
254
257
255
258
switch (mrm_behavior) {
256
- case MrmState ::NONE:
259
+ case MrmBehavior ::NONE:
257
260
RCLCPP_WARN (this ->get_logger (), " MRM behavior is None. Do nothing." );
258
261
return true ;
259
- case MrmState ::PULL_OVER: {
262
+ case MrmBehavior ::PULL_OVER: {
260
263
future = client_mrm_pull_over_->async_send_request (request).future .share ();
261
264
break ;
262
265
}
263
- case MrmState ::COMFORTABLE_STOP: {
266
+ case MrmBehavior ::COMFORTABLE_STOP: {
264
267
future = client_mrm_comfortable_stop_->async_send_request (request).future .share ();
265
268
break ;
266
269
}
267
- case MrmState ::EMERGENCY_STOP: {
270
+ case MrmBehavior ::EMERGENCY_STOP: {
268
271
future = client_mrm_emergency_stop_->async_send_request (request).future .share ();
269
272
break ;
270
273
}
@@ -364,7 +367,7 @@ void MrmHandler::onTimer()
364
367
365
368
void MrmHandler::transitionTo (const int new_state)
366
369
{
367
- using autoware_adapi_v1_msgs ::msg::MrmState;
370
+ using tier4_system_msgs ::msg::MrmState;
368
371
369
372
const auto state2string = [](const int state) {
370
373
if (state == MrmState::NORMAL) {
@@ -393,8 +396,9 @@ void MrmHandler::transitionTo(const int new_state)
393
396
394
397
void MrmHandler::updateMrmState ()
395
398
{
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;
398
402
399
403
// Check emergency
400
404
const bool is_emergency = isEmergency ();
@@ -433,6 +437,7 @@ void MrmHandler::updateMrmState()
433
437
434
438
case MrmState::MRM_SUCCEEDED:
435
439
if (mrm_state_.behavior != getCurrentMrmBehavior ()) {
440
+
436
441
transitionTo (MrmState::MRM_OPERATING);
437
442
}
438
443
return ;
@@ -448,85 +453,86 @@ void MrmHandler::updateMrmState()
448
453
}
449
454
}
450
455
451
- autoware_adapi_v1_msgs ::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmBehavior ()
456
+ tier4_system_msgs ::msg::MrmBehavior::_type_type MrmHandler::getCurrentMrmBehavior ()
452
457
{
453
- using autoware_adapi_v1_msgs::msg::MrmState;
458
+ using tier4_system_msgs::msg::MrmBehavior;
459
+ using tier4_system_msgs::msg::MrmState;
454
460
using tier4_system_msgs::msg::OperationModeAvailability;
455
461
456
462
// State machine
457
- if (mrm_state_.behavior == MrmState ::NONE) {
463
+ if (mrm_state_.behavior . type == MrmBehavior ::NONE) {
458
464
if (is_operation_mode_availability_timeout) {
459
- return MrmState ::EMERGENCY_STOP;
465
+ return MrmBehavior ::EMERGENCY_STOP;
460
466
}
461
467
if (operation_mode_availability_->pull_over ) {
462
468
if (param_.use_pull_over ) {
463
- return MrmState ::PULL_OVER;
469
+ return MrmBehavior ::PULL_OVER;
464
470
}
465
471
}
466
472
if (operation_mode_availability_->comfortable_stop ) {
467
473
if (param_.use_comfortable_stop ) {
468
- return MrmState ::COMFORTABLE_STOP;
474
+ return MrmBehavior ::COMFORTABLE_STOP;
469
475
}
470
476
}
471
477
if (!operation_mode_availability_->emergency_stop ) {
472
478
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
473
479
}
474
- return MrmState ::EMERGENCY_STOP;
480
+ return MrmBehavior ::EMERGENCY_STOP;
475
481
}
476
- if (mrm_state_.behavior == MrmState ::PULL_OVER) {
482
+ if (mrm_state_.behavior . type == MrmBehavior ::PULL_OVER) {
477
483
if (is_operation_mode_availability_timeout) {
478
- return MrmState ::EMERGENCY_STOP;
484
+ return MrmBehavior ::EMERGENCY_STOP;
479
485
}
480
486
if (operation_mode_availability_->pull_over ) {
481
487
if (param_.use_pull_over ) {
482
- return MrmState ::PULL_OVER;
488
+ return MrmBehavior ::PULL_OVER;
483
489
}
484
490
}
485
491
if (operation_mode_availability_->comfortable_stop ) {
486
492
if (param_.use_comfortable_stop ) {
487
- return MrmState ::COMFORTABLE_STOP;
493
+ return MrmBehavior ::COMFORTABLE_STOP;
488
494
}
489
495
}
490
496
if (!operation_mode_availability_->emergency_stop ) {
491
497
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
492
498
}
493
- return MrmState ::EMERGENCY_STOP;
499
+ return MrmBehavior ::EMERGENCY_STOP;
494
500
}
495
- if (mrm_state_.behavior == MrmState ::COMFORTABLE_STOP) {
501
+ if (mrm_state_.behavior . type == MrmBehavior ::COMFORTABLE_STOP) {
496
502
if (is_operation_mode_availability_timeout) {
497
- return MrmState ::EMERGENCY_STOP;
503
+ return MrmBehavior ::EMERGENCY_STOP;
498
504
}
499
505
if (isStopped () && operation_mode_availability_->pull_over ) {
500
506
if (param_.use_pull_over && param_.use_pull_over_after_stopped ) {
501
- return MrmState ::PULL_OVER;
507
+ return MrmBehavior ::PULL_OVER;
502
508
}
503
509
}
504
510
if (operation_mode_availability_->comfortable_stop ) {
505
511
if (param_.use_comfortable_stop ) {
506
- return MrmState ::COMFORTABLE_STOP;
512
+ return MrmBehavior ::COMFORTABLE_STOP;
507
513
}
508
514
}
509
515
if (!operation_mode_availability_->emergency_stop ) {
510
516
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
511
517
}
512
- return MrmState ::EMERGENCY_STOP;
518
+ return MrmBehavior ::EMERGENCY_STOP;
513
519
}
514
- if (mrm_state_.behavior == MrmState ::EMERGENCY_STOP) {
520
+ if (mrm_state_.behavior . type == MrmBehavior ::EMERGENCY_STOP) {
515
521
if (is_operation_mode_availability_timeout) {
516
- return MrmState ::EMERGENCY_STOP;
522
+ return MrmBehavior ::EMERGENCY_STOP;
517
523
}
518
524
if (isStopped () && operation_mode_availability_->pull_over ) {
519
525
if (param_.use_pull_over && param_.use_pull_over_after_stopped ) {
520
- return MrmState ::PULL_OVER;
526
+ return MrmBehavior ::PULL_OVER;
521
527
}
522
528
}
523
529
if (!operation_mode_availability_->emergency_stop ) {
524
530
RCLCPP_WARN (this ->get_logger (), " no mrm operation available: operate emergency_stop" );
525
531
}
526
- return MrmState ::EMERGENCY_STOP;
532
+ return MrmBehavior ::EMERGENCY_STOP;
527
533
}
528
534
529
- return mrm_state_.behavior ;
535
+ return mrm_state_.behavior . type ;
530
536
}
531
537
532
538
bool MrmHandler::isStopped ()
0 commit comments