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

Behaviors access result #3704

Merged
merged 3 commits into from Jul 27, 2023
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.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
10 changes: 5 additions & 5 deletions nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp
Expand Up @@ -105,7 +105,7 @@ class TimedBehavior : public nav2_core::Behavior
}

// an opportunity for a derived class to do something on action completion
virtual void onActionCompletion()
virtual void onActionCompletion(std::shared_ptr<typename ActionT::Result>/*result*/)
{
}

Expand Down Expand Up @@ -230,8 +230,8 @@ class TimedBehavior : public nav2_core::Behavior
RCLCPP_INFO(logger_, "Canceling %s", behavior_name_.c_str());
stopRobot();
result->total_elapsed_time = elasped_time_;
onActionCompletion(result);
action_server_->terminate_all(result);
onActionCompletion();
return;
}

Expand All @@ -243,8 +243,8 @@ class TimedBehavior : public nav2_core::Behavior
behavior_name_.c_str());
stopRobot();
result->total_elapsed_time = steady_clock_.now() - start_time;
onActionCompletion(result);
action_server_->terminate_current(result);
onActionCompletion();
return;
}

Expand All @@ -255,16 +255,16 @@ class TimedBehavior : public nav2_core::Behavior
logger_,
"%s completed successfully", behavior_name_.c_str());
result->total_elapsed_time = steady_clock_.now() - start_time;
onActionCompletion(result);
action_server_->succeeded_current(result);
onActionCompletion();
return;

case Status::FAILED:
RCLCPP_WARN(logger_, "%s failed", behavior_name_.c_str());
result->total_elapsed_time = steady_clock_.now() - start_time;
result->error_code = on_cycle_update_result.error_code;
onActionCompletion(result);
action_server_->terminate_current(result);
onActionCompletion();
return;

case Status::RUNNING:
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/plugins/assisted_teleop.cpp
Expand Up @@ -71,7 +71,7 @@ ResultStatus AssistedTeleop::onRun(const std::shared_ptr<const AssistedTeleopAct
return ResultStatus{Status::SUCCEEDED, AssistedTeleopActionResult::NONE};
}

void AssistedTeleop::onActionCompletion()
void AssistedTeleop::onActionCompletion(std::shared_ptr<AssistedTeleopActionResult>/*result*/)
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
{
teleop_twist_ = geometry_msgs::msg::Twist();
preempt_teleop_ = false;
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/plugins/assisted_teleop.hpp
Expand Up @@ -51,7 +51,7 @@ class AssistedTeleop : public TimedBehavior<AssistedTeleopAction>
/**
* @brief func to run at the completion of the action
*/
void onActionCompletion() override;
void onActionCompletion(std::shared_ptr<AssistedTeleopActionResult>/*result*/) override;

/**
* @brief Loop function to run behavior
Expand Down