Skip to content

Commit

Permalink
Behaviors access result (#3704)
Browse files Browse the repository at this point in the history
* onCycle has access to the result

* revert

* pr review
  • Loading branch information
jwallace42 committed Jul 27, 2023
1 parent cb34d0c commit 2f1f9e4
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 7 deletions.
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*/)
{
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

0 comments on commit 2f1f9e4

Please sign in to comment.