Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/feature/mrm_behavior/pull_over' …
Browse files Browse the repository at this point in the history
…into feature/mrm_behavior/pull_over
  • Loading branch information
HansRobo committed Feb 21, 2024
2 parents ba46eba + 15ed7d2 commit 5b9de7f
Showing 1 changed file with 20 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -483,7 +483,7 @@ auto FieldOperatorApplicationFor<AutowareUniverse>::receiveEmergencyState(
}

template <typename T>
auto toMinimumRiskManeuverBehaviorString(const std::uint8_t & behavior_number)
auto toMinimumRiskManeuverBehaviorString(const std::uint8_t & behavior_number) -> std::string
{
static const std::unordered_map<std::uint8_t, std::string> behavior_string_map = [&]() {
std::unordered_map<std::uint8_t, std::string> behavior_string_map;
Expand Down Expand Up @@ -513,26 +513,28 @@ auto toMinimumRiskManeuverBehaviorString(const std::uint8_t & behavior_number)
}
}

auto FieldOperatorApplicationFor<AutowareUniverse>::receiveMrmState(
const autoware_adapi_v1_msgs::msg::MrmState & message) -> void
auto toMinimumRiskManeuverStateString(const std::uint8_t & state_number) -> std::string
{
auto to_minimum_risk_maneuver_state_string = [](const std::uint8_t & state_number) {
std::unordered_map<std::uint8_t, std::string> state_string_map = {
{autoware_adapi_v1_msgs::msg::MrmState::MRM_FAILED, "MRM_FAILED"},
{autoware_adapi_v1_msgs::msg::MrmState::MRM_OPERATING, "MRM_OPERATING"},
{autoware_adapi_v1_msgs::msg::MrmState::MRM_SUCCEEDED, "MRM_SUCCEEDED"},
{autoware_adapi_v1_msgs::msg::MrmState::NORMAL, "NORMAL"},
{autoware_adapi_v1_msgs::msg::MrmState::UNKNOWN, "UNKNOWN"},
};

if (const auto state = state_string_map.find(state_number); state == state_string_map.end()) {
throw common::Error("Unexpected MrmState::state, number: ", state_number);
} else {
return state->second;
}
static const std::unordered_map<std::uint8_t, std::string> state_string_map = {
{autoware_adapi_v1_msgs::msg::MrmState::MRM_FAILED, "MRM_FAILED"},
{autoware_adapi_v1_msgs::msg::MrmState::MRM_OPERATING, "MRM_OPERATING"},
{autoware_adapi_v1_msgs::msg::MrmState::MRM_SUCCEEDED, "MRM_SUCCEEDED"},
{autoware_adapi_v1_msgs::msg::MrmState::NORMAL, "NORMAL"},
{autoware_adapi_v1_msgs::msg::MrmState::UNKNOWN, "UNKNOWN"},
};

minimum_risk_maneuver_state = to_minimum_risk_maneuver_state_string(message.state);
if (const auto state = state_string_map.find(state_number); state == state_string_map.end()) {
throw common::Error(
"Unexpected autoware_adapi_v1_msgs::msg::MrmState::state, number: ", state_number);
} else {
return state->second;
}
}

auto FieldOperatorApplicationFor<AutowareUniverse>::receiveMrmState(
const autoware_adapi_v1_msgs::msg::MrmState & message) -> void
{
minimum_risk_maneuver_state = toMinimumRiskManeuverStateString(message.state);

minimum_risk_maneuver_behavior =
toMinimumRiskManeuverBehaviorString<autoware_adapi_v1_msgs::msg::MrmState>(message.behavior);
Expand Down

0 comments on commit 5b9de7f

Please sign in to comment.