Skip to content

Commit 0035d50

Browse files
TetsuKawamkuri
authored andcommitted
feat: change mrm state type to internal one (#1392)
Signed-off-by: TetsuKawa <kawaguchitnon@icloud.com> Signed-off-by: Makoto Kurihara <mkuri8m@gmail.com>
1 parent db76fff commit 0035d50

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
@@ -22,12 +22,13 @@
2222
#include <variant>
2323

2424
// Autoware
25-
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
2625
#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
2726
#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
2827
#include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
2928
#include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp>
29+
#include <tier4_system_msgs/msg/mrm_behavior.hpp>
3030
#include <tier4_system_msgs/msg/mrm_behavior_status.hpp>
31+
#include <tier4_system_msgs/msg/mrm_state.hpp>
3132
#include <tier4_system_msgs/msg/operation_mode_availability.hpp>
3233
#include <tier4_system_msgs/srv/operate_mrm.hpp>
3334

@@ -112,9 +113,9 @@ class MrmHandler : public rclcpp::Node
112113
void publishHazardCmd();
113114
void publishGearCmd();
114115

115-
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::MrmState>::SharedPtr pub_mrm_state_;
116+
rclcpp::Publisher<tier4_system_msgs::msg::MrmState>::SharedPtr pub_mrm_state_;
116117

117-
autoware_adapi_v1_msgs::msg::MrmState mrm_state_;
118+
tier4_system_msgs::msg::MrmState mrm_state_;
118119
void publishMrmState();
119120

120121
// Clients
@@ -126,7 +127,7 @@ class MrmHandler : public rclcpp::Node
126127
rclcpp::Client<tier4_system_msgs::srv::OperateMrm>::SharedPtr client_mrm_emergency_stop_;
127128

128129
bool requestMrmBehavior(
129-
const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior,
130+
const tier4_system_msgs::msg::MrmBehavior::_type_type & mrm_behavior,
130131
RequestType request_type) const;
131132
void logMrmCallingResult(
132133
const tier4_system_msgs::srv::OperateMrm::Response & result, const std::string & behavior,
@@ -153,7 +154,7 @@ class MrmHandler : public rclcpp::Node
153154
void updateMrmState();
154155
void operateMrm();
155156
void handleFailedRequest();
156-
autoware_adapi_v1_msgs::msg::MrmState::_behavior_type getCurrentMrmBehavior();
157+
tier4_system_msgs::msg::MrmBehavior::_type_type getCurrentMrmBehavior();
157158
bool isStopped();
158159
bool isEmergency() const;
159160
bool isArrivedAtGoal();

system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp

+55-50
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
6565
pub_gear_cmd_ =
6666
create_publisher<autoware_auto_vehicle_msgs::msg::GearCommand>("~/output/gear", rclcpp::QoS{1});
6767
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});
6969

7070
// Clients
7171
client_mrm_pull_over_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
@@ -92,8 +92,8 @@ MrmHandler::MrmHandler() : Node("mrm_handler")
9292
mrm_emergency_stop_status_ = std::make_shared<const tier4_system_msgs::msg::MrmBehaviorStatus>();
9393
operation_mode_state_ = std::make_shared<const autoware_adapi_v1_msgs::msg::OperationModeState>();
9494
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;
9797
is_operation_mode_availability_timeout = false;
9898

9999
// Timer
@@ -208,30 +208,31 @@ void MrmHandler::publishMrmState()
208208

209209
void MrmHandler::operateMrm()
210210
{
211-
using autoware_adapi_v1_msgs::msg::MrmState;
211+
using tier4_system_msgs::msg::MrmBehavior;
212+
using tier4_system_msgs::msg::MrmState;
212213

213214
if (mrm_state_.state == MrmState::NORMAL) {
214215
// 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) {
217218
return;
218219
}
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;
221222
} else {
222223
handleFailedRequest();
223224
}
224225
return;
225226
}
226227
if (mrm_state_.state == MrmState::MRM_OPERATING) {
227228
const auto current_mrm_behavior = getCurrentMrmBehavior();
228-
if (current_mrm_behavior == mrm_state_.behavior) {
229+
if (current_mrm_behavior == mrm_state_.behavior.type) {
229230
return;
230231
}
231-
if (!requestMrmBehavior(mrm_state_.behavior, RequestType::CANCEL)) {
232+
if (!requestMrmBehavior(mrm_state_.behavior.type, RequestType::CANCEL)) {
232233
handleFailedRequest();
233234
} else if (requestMrmBehavior(current_mrm_behavior, RequestType::CALL)) {
234-
mrm_state_.behavior = current_mrm_behavior;
235+
mrm_state_.behavior.type = current_mrm_behavior;
235236
} else {
236237
handleFailedRequest();
237238
}
@@ -251,21 +252,23 @@ void MrmHandler::operateMrm()
251252

252253
void MrmHandler::handleFailedRequest()
253254
{
254-
using autoware_adapi_v1_msgs::msg::MrmState;
255+
using tier4_system_msgs::msg::MrmBehavior;
256+
using tier4_system_msgs::msg::MrmState;
255257

256-
if (requestMrmBehavior(MrmState::EMERGENCY_STOP, CALL)) {
258+
if (requestMrmBehavior(MrmBehavior::EMERGENCY_STOP, CALL)) {
257259
if (mrm_state_.state != MrmState::MRM_OPERATING) transitionTo(MrmState::MRM_OPERATING);
258260
} else {
259261
transitionTo(MrmState::MRM_FAILED);
260262
}
261-
mrm_state_.behavior = MrmState::EMERGENCY_STOP;
263+
mrm_state_.behavior.type = MrmBehavior::EMERGENCY_STOP;
262264
}
263265

264266
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,
266268
RequestType request_type) const
267269
{
268-
using autoware_adapi_v1_msgs::msg::MrmState;
270+
using tier4_system_msgs::msg::MrmBehavior;
271+
using tier4_system_msgs::msg::MrmState;
269272

270273
auto request = std::make_shared<tier4_system_msgs::srv::OperateMrm::Request>();
271274
if (request_type == RequestType::CALL) {
@@ -281,35 +284,35 @@ bool MrmHandler::requestMrmBehavior(
281284
std::shared_future<std::shared_ptr<tier4_system_msgs::srv::OperateMrm::Response>> future;
282285

283286
const auto behavior2string = [](const int behavior) {
284-
if (behavior == MrmState::NONE) {
287+
if (behavior == MrmBehavior::NONE) {
285288
return "NONE";
286289
}
287-
if (behavior == MrmState::PULL_OVER) {
290+
if (behavior == MrmBehavior::PULL_OVER) {
288291
return "PULL_OVER";
289292
}
290-
if (behavior == MrmState::COMFORTABLE_STOP) {
293+
if (behavior == MrmBehavior::COMFORTABLE_STOP) {
291294
return "COMFORTABLE_STOP";
292295
}
293-
if (behavior == MrmState::EMERGENCY_STOP) {
296+
if (behavior == MrmBehavior::EMERGENCY_STOP) {
294297
return "EMERGENCY_STOP";
295298
}
296299
const auto msg = "invalid behavior: " + std::to_string(behavior);
297300
throw std::runtime_error(msg);
298301
};
299302

300303
switch (mrm_behavior) {
301-
case MrmState::NONE:
304+
case MrmBehavior::NONE:
302305
RCLCPP_WARN(this->get_logger(), "MRM behavior is None. Do nothing.");
303306
return true;
304-
case MrmState::PULL_OVER: {
307+
case MrmBehavior::PULL_OVER: {
305308
future = client_mrm_pull_over_->async_send_request(request).future.share();
306309
break;
307310
}
308-
case MrmState::COMFORTABLE_STOP: {
311+
case MrmBehavior::COMFORTABLE_STOP: {
309312
future = client_mrm_comfortable_stop_->async_send_request(request).future.share();
310313
break;
311314
}
312-
case MrmState::EMERGENCY_STOP: {
315+
case MrmBehavior::EMERGENCY_STOP: {
313316
future = client_mrm_emergency_stop_->async_send_request(request).future.share();
314317
break;
315318
}
@@ -414,7 +417,7 @@ void MrmHandler::onTimer()
414417

415418
void MrmHandler::transitionTo(const int new_state)
416419
{
417-
using autoware_adapi_v1_msgs::msg::MrmState;
420+
using tier4_system_msgs::msg::MrmState;
418421

419422
const auto state2string = [](const int state) {
420423
if (state == MrmState::NORMAL) {
@@ -443,8 +446,9 @@ void MrmHandler::transitionTo(const int new_state)
443446

444447
void MrmHandler::updateMrmState()
445448
{
446-
using autoware_adapi_v1_msgs::msg::MrmState;
447449
using autoware_auto_vehicle_msgs::msg::ControlModeReport;
450+
using tier4_system_msgs::msg::MrmBehavior;
451+
using tier4_system_msgs::msg::MrmState;
448452

449453
// Check emergency
450454
const bool is_emergency = isEmergency();
@@ -471,7 +475,7 @@ void MrmHandler::updateMrmState()
471475

472476
if (mrm_state_.state == MrmState::MRM_OPERATING) {
473477
// TODO(TetsuKawa): Check MRC is accomplished
474-
if (mrm_state_.behavior == MrmState::PULL_OVER) {
478+
if (mrm_state_.behavior.type == MrmBehavior::PULL_OVER) {
475479
if (isStopped() && isArrivedAtGoal()) {
476480
transitionTo(MrmState::MRM_SUCCEEDED);
477481
return;
@@ -484,7 +488,7 @@ void MrmHandler::updateMrmState()
484488
}
485489
} else if (mrm_state_.state == MrmState::MRM_SUCCEEDED) {
486490
const auto current_mrm_behavior = getCurrentMrmBehavior();
487-
if (current_mrm_behavior != mrm_state_.behavior) {
491+
if (current_mrm_behavior != mrm_state_.behavior.type) {
488492
transitionTo(MrmState::MRM_OPERATING);
489493
}
490494
} else if (mrm_state_.state == MrmState::MRM_FAILED) {
@@ -496,85 +500,86 @@ void MrmHandler::updateMrmState()
496500
}
497501
}
498502

499-
autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmBehavior()
503+
tier4_system_msgs::msg::MrmBehavior::_type_type MrmHandler::getCurrentMrmBehavior()
500504
{
501-
using autoware_adapi_v1_msgs::msg::MrmState;
505+
using tier4_system_msgs::msg::MrmBehavior;
506+
using tier4_system_msgs::msg::MrmState;
502507
using tier4_system_msgs::msg::OperationModeAvailability;
503508

504509
// State machine
505-
if (mrm_state_.behavior == MrmState::NONE) {
510+
if (mrm_state_.behavior.type == MrmBehavior::NONE) {
506511
if (is_operation_mode_availability_timeout) {
507-
return MrmState::EMERGENCY_STOP;
512+
return MrmBehavior::EMERGENCY_STOP;
508513
}
509514
if (operation_mode_availability_->pull_over) {
510515
if (param_.use_pull_over) {
511-
return MrmState::PULL_OVER;
516+
return MrmBehavior::PULL_OVER;
512517
}
513518
}
514519
if (operation_mode_availability_->comfortable_stop) {
515520
if (param_.use_comfortable_stop) {
516-
return MrmState::COMFORTABLE_STOP;
521+
return MrmBehavior::COMFORTABLE_STOP;
517522
}
518523
}
519524
if (!operation_mode_availability_->emergency_stop) {
520525
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
521526
}
522-
return MrmState::EMERGENCY_STOP;
527+
return MrmBehavior::EMERGENCY_STOP;
523528
}
524-
if (mrm_state_.behavior == MrmState::PULL_OVER) {
529+
if (mrm_state_.behavior.type == MrmBehavior::PULL_OVER) {
525530
if (is_operation_mode_availability_timeout) {
526-
return MrmState::EMERGENCY_STOP;
531+
return MrmBehavior::EMERGENCY_STOP;
527532
}
528533
if (operation_mode_availability_->pull_over) {
529534
if (param_.use_pull_over) {
530-
return MrmState::PULL_OVER;
535+
return MrmBehavior::PULL_OVER;
531536
}
532537
}
533538
if (operation_mode_availability_->comfortable_stop) {
534539
if (param_.use_comfortable_stop) {
535-
return MrmState::COMFORTABLE_STOP;
540+
return MrmBehavior::COMFORTABLE_STOP;
536541
}
537542
}
538543
if (!operation_mode_availability_->emergency_stop) {
539544
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
540545
}
541-
return MrmState::EMERGENCY_STOP;
546+
return MrmBehavior::EMERGENCY_STOP;
542547
}
543-
if (mrm_state_.behavior == MrmState::COMFORTABLE_STOP) {
548+
if (mrm_state_.behavior.type == MrmBehavior::COMFORTABLE_STOP) {
544549
if (is_operation_mode_availability_timeout) {
545-
return MrmState::EMERGENCY_STOP;
550+
return MrmBehavior::EMERGENCY_STOP;
546551
}
547552
if (isStopped() && operation_mode_availability_->pull_over) {
548553
if (param_.use_pull_over) {
549-
return MrmState::PULL_OVER;
554+
return MrmBehavior::PULL_OVER;
550555
}
551556
}
552557
if (operation_mode_availability_->comfortable_stop) {
553558
if (param_.use_comfortable_stop) {
554-
return MrmState::COMFORTABLE_STOP;
559+
return MrmBehavior::COMFORTABLE_STOP;
555560
}
556561
}
557562
if (!operation_mode_availability_->emergency_stop) {
558563
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
559564
}
560-
return MrmState::EMERGENCY_STOP;
565+
return MrmBehavior::EMERGENCY_STOP;
561566
}
562-
if (mrm_state_.behavior == MrmState::EMERGENCY_STOP) {
567+
if (mrm_state_.behavior.type == MrmBehavior::EMERGENCY_STOP) {
563568
if (is_operation_mode_availability_timeout) {
564-
return MrmState::EMERGENCY_STOP;
569+
return MrmBehavior::EMERGENCY_STOP;
565570
}
566571
if (isStopped() && operation_mode_availability_->pull_over) {
567572
if (param_.use_pull_over) {
568-
return MrmState::PULL_OVER;
573+
return MrmBehavior::PULL_OVER;
569574
}
570575
}
571576
if (!operation_mode_availability_->emergency_stop) {
572577
RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop");
573578
}
574-
return MrmState::EMERGENCY_STOP;
579+
return MrmBehavior::EMERGENCY_STOP;
575580
}
576581

577-
return mrm_state_.behavior;
582+
return mrm_state_.behavior.type;
578583
}
579584

580585
bool MrmHandler::isStopped()

0 commit comments

Comments
 (0)