Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(operation_mode_transition_manager): add guard to invalid parameter #2388

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 12 additions & 1 deletion control/operation_mode_transition_manager/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,12 +50,23 @@ OperationModeTransitionManager::OperationModeTransitionManager(const rclcpp::Nod
}

// initialize state
transition_timeout_ = declare_parameter<double>("transition_timeout");
current_mode_ = OperationMode::STOP;
transition_ = nullptr;
gate_operation_mode_.mode = OperationModeState::UNKNOWN;
gate_operation_mode_.is_in_transition = false;
control_mode_report_.mode = ControlModeReport::NO_COMMAND;
transition_timeout_ = declare_parameter<double>("transition_timeout");
{
// check `transition_timeout` value
const auto stable_duration = declare_parameter<double>("stable_check.duration");
const double TIMEOUT_MARGIN = 0.5;
if (transition_timeout_ < stable_duration + TIMEOUT_MARGIN) {
transition_timeout_ = stable_duration + TIMEOUT_MARGIN;
RCLCPP_WARN(
get_logger(), "`transition_timeout` must be somewhat larger than `stable_check.duration`");
RCLCPP_WARN_STREAM(get_logger(), "transition_timeout is set to " << transition_timeout_);
}
}

// modes
modes_[OperationMode::STOP] = std::make_unique<StopMode>();
Expand Down
2 changes: 1 addition & 1 deletion control/operation_mode_transition_manager/src/state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ AutonomousMode::AutonomousMode(rclcpp::Node * node)
// params for mode change completed
{
auto & p = stable_check_param_;
p.duration = node->declare_parameter<double>("stable_check.duration");
p.duration = node->get_parameter("stable_check.duration").as_double();
p.dist_threshold = node->declare_parameter<double>("stable_check.dist_threshold");
p.speed_upper_threshold = node->declare_parameter<double>("stable_check.speed_upper_threshold");
p.speed_lower_threshold = node->declare_parameter<double>("stable_check.speed_lower_threshold");
Expand Down