Skip to content

Commit

Permalink
Merge pull request autowarefoundation#187 from tier4/sync-upstream
Browse files Browse the repository at this point in the history
chore: sync upstream
  • Loading branch information
tier4-autoware-public-bot[bot] authored Nov 24, 2022
2 parents 784db07 + 40fc564 commit d13c23b
Show file tree
Hide file tree
Showing 49 changed files with 916 additions and 2,724 deletions.
1 change: 0 additions & 1 deletion .github/CODEOWNERS
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,6 @@ sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp @autowarefoundation/
simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp @autowarefoundation/autoware-global-codeowners
simulator/fault_injection/** keisuke.shima@tier4.jp @autowarefoundation/autoware-global-codeowners
simulator/simple_planning_simulator/** takamasa.horibe@tier4.jp @autowarefoundation/autoware-global-codeowners
system/ad_service_state_monitor/** kenji.miyake@tier4.jp @autowarefoundation/autoware-global-codeowners
system/bluetooth_monitor/** fumihito.ito@tier4.jp @autowarefoundation/autoware-global-codeowners
system/component_state_monitor/** isamu.takagi@tier4.jp @autowarefoundation/autoware-global-codeowners
system/default_ad_api/** isamu.takagi@tier4.jp @autowarefoundation/autoware-global-codeowners
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**:
ros__parameters:
transition_timeout: 3.0
transition_timeout: 10.0
frequency_hz: 10.0
engage_acceptable_limits:
allow_autonomous_in_stopped: true # no check if the velocity is zero, always allowed.
Expand Down
15 changes: 9 additions & 6 deletions control/operation_mode_transition_manager/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,8 +124,8 @@ void OperationModeTransitionManager::changeOperationMode(std::optional<Operation
throw component_interface_utils::NoEffectWarning("Autoware already controls the vehicle.");
}

// TODO(Takagi, Isamu): overwrite transition between operation modes
if (transition_) {
// TODO(Takagi, Isamu): Consider mode change request during transition.
if (transition_ && request_mode != OperationMode::STOP) {
throw component_interface_utils::ServiceException(
ServiceResponse::ERROR_IN_TRANSITION, "The mode transition is in progress.");
}
Expand All @@ -150,12 +150,13 @@ void OperationModeTransitionManager::cancelTransition()
{
const auto & previous = transition_->previous;
if (previous) {
compatibility_transition_ = now();
current_mode_ = previous.value();
} else {
compatibility_transition_ = std::nullopt;
changeControlMode(ControlModeCommand::Request::MANUAL);
}
transition_.reset();
compatibility_transition_ = std::nullopt;
}

void OperationModeTransitionManager::processTransition()
Expand Down Expand Up @@ -211,7 +212,7 @@ void OperationModeTransitionManager::onTimer()

// Check sync timeout to the compatible interface.
if (compatibility_transition_) {
if (transition_timeout_ < (now() - compatibility_transition_.value()).seconds()) {
if (compatibility_timeout_ < (now() - compatibility_transition_.value()).seconds()) {
compatibility_transition_ = std::nullopt;
}
}
Expand All @@ -224,8 +225,10 @@ void OperationModeTransitionManager::onTimer()
}

// Reset sync timeout when it is completed.
if (current_mode_ == compatibility_.get_mode()) {
compatibility_transition_ = std::nullopt;
if (compatibility_transition_) {
if (current_mode_ == compatibility_.get_mode()) {
compatibility_transition_ = std::nullopt;
}
}

if (transition_) {
Expand Down
1 change: 1 addition & 0 deletions control/operation_mode_transition_manager/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ class OperationModeTransitionManager : public rclcpp::Node

std::optional<OperationModeStateAPI::Message> prev_state_;

static constexpr double compatibility_timeout_ = 1.0;
Compatibility compatibility_;
std::optional<rclcpp::Time> compatibility_transition_;
};
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**:
ros__parameters:
transition_timeout: 3.0
transition_timeout: 10.0
frequency_hz: 10.0
engage_acceptable_limits:
allow_autonomous_in_stopped: true # no check if the velocity is zero, always allowed.
Expand Down

This file was deleted.

This file was deleted.

Loading

0 comments on commit d13c23b

Please sign in to comment.