diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_action.hpp index 22cde94c35f..a151bc62920 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_action.hpp @@ -29,6 +29,10 @@ namespace nav2_behavior_tree */ class AssistedTeleopAction : public BtActionNode { + using Action = nav2_msgs::action::AssistedTeleop; + using ActionGoal = Action::Goal; + using ActionResult = Action::Result; + public: /** * @brief A constructor for nav2_behavior_tree::nav2_msgs::action::AssistedTeleop @@ -46,8 +50,21 @@ class AssistedTeleopAction : public BtActionNode("time_allowance", 10.0, "Allowed time for running assisted teleop"), - BT::InputPort("is_recovery", false, "If true the recovery count will be incremented") + BT::InputPort("is_recovery", false, "If true the recovery count will be incremented"), + BT::OutputPort( + "error_code_id", "The assisted teleop behavior server error code") }); } diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_action.hpp index 4481198972f..d94685e3444 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_action.hpp @@ -28,6 +28,10 @@ namespace nav2_behavior_tree */ class BackUpAction : public BtActionNode { + using Action = nav2_msgs::action::BackUp; + using ActionGoal = Action::Goal; + using ActionResult = Action::Result; + public: /** * @brief A constructor for nav2_behavior_tree::BackUpAction @@ -45,6 +49,22 @@ class BackUpAction : public BtActionNode */ void on_tick() override; + + /** + * @brief Function to perform some user-defined operation upon successful completion of the action + */ + BT::NodeStatus on_success() override; + + /** + * @brief Function to perform some user-defined operation upon abortion of the action + */ + BT::NodeStatus on_aborted() override; + + /** + * @brief Function to perform some user-defined operation upon cancellation of the action + */ + BT::NodeStatus on_cancelled() override; + /** * @brief Creates list of BT ports * @return BT::PortsList Containing basic ports along with node-specific ports @@ -55,7 +75,9 @@ class BackUpAction : public BtActionNode { BT::InputPort("backup_dist", 0.15, "Distance to backup"), BT::InputPort("backup_speed", 0.025, "Speed at which to backup"), - BT::InputPort("time_allowance", 10.0, "Allowed time for reversing") + BT::InputPort("time_allowance", 10.0, "Allowed time for reversing"), + BT::OutputPort( + "error_code_id", "The back up behavior server error code") }); } }; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_action.hpp index 5632a7551e6..877132441c5 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_action.hpp @@ -28,6 +28,10 @@ namespace nav2_behavior_tree */ class DriveOnHeadingAction : public BtActionNode { + using Action = nav2_msgs::action::DriveOnHeading; + using ActionGoal = Action::Goal; + using ActionResult = Action::Goal; + public: /** * @brief A constructor for nav2_behavior_tree::DriveOnHeadingAction @@ -50,11 +54,27 @@ class DriveOnHeadingAction : public BtActionNode("dist_to_travel", 0.15, "Distance to travel"), BT::InputPort("speed", 0.025, "Speed at which to travel"), - BT::InputPort("time_allowance", 10.0, "Allowed time for driving on heading") + BT::InputPort("time_allowance", 10.0, "Allowed time for driving on heading"), + BT::OutputPort( + "error_code_id", "The drive on heading behavior server error code") }); } + + /** + * @brief Function to perform some user-defined operation upon successful completion of the action + */ + BT::NodeStatus on_success() override; + + /** + * @brief Function to perform some user-defined operation upon abortion of the action + */ + BT::NodeStatus on_aborted() override; + + /** + * @brief Function to perform some user-defined operation upon cancellation of the action + */ + BT::NodeStatus on_cancelled() override; }; } // namespace nav2_behavior_tree - #endif // NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__DRIVE_ON_HEADING_ACTION_HPP_ diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_action.hpp index 76496ba7ed2..d692ba6756d 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_action.hpp @@ -28,6 +28,10 @@ namespace nav2_behavior_tree */ class SpinAction : public BtActionNode { + using Action = nav2_msgs::action::Spin; + using ActionResult = Action::Result; + using ActionGoal = Action::Goal; + public: /** * @brief A constructor for nav2_behavior_tree::SpinAction @@ -55,10 +59,27 @@ class SpinAction : public BtActionNode { BT::InputPort("spin_dist", 1.57, "Spin distance"), BT::InputPort("time_allowance", 10.0, "Allowed time for spinning"), - BT::InputPort("is_recovery", true, "True if recovery") + BT::InputPort("is_recovery", true, "True if recovery"), + BT::OutputPort( + "error_code_id", "The spin behavior error code") }); } + /** + * @brief Function to perform some user-defined operation upon successful completion of the action + */ + BT::NodeStatus on_success() override; + + /** + * @brief Function to perform some user-defined operation upon abortion of the action + */ + BT::NodeStatus on_aborted() override; + + /** + * @brief Function to perform some user-defined operation upon cancellation of the action + */ + BT::NodeStatus on_cancelled() override; + private: bool is_recovery_; }; diff --git a/nav2_behavior_tree/nav2_tree_nodes.xml b/nav2_behavior_tree/nav2_tree_nodes.xml index cf2bbed4b22..a70000e1761 100644 --- a/nav2_behavior_tree/nav2_tree_nodes.xml +++ b/nav2_behavior_tree/nav2_tree_nodes.xml @@ -13,6 +13,7 @@ Allowed time for reversing Server name Server timeout + "Back up error code" @@ -21,6 +22,7 @@ Allowed time for reversing Server name Server timeout + "Drive on heading error code" @@ -184,6 +186,7 @@ Allowed time for spinning Server name Server timeout + Spin error code @@ -197,6 +200,7 @@ If true recovery count will be incremented Service name Server timeout + Assisted teleop error code diff --git a/nav2_behavior_tree/plugins/action/assisted_teleop_action.cpp b/nav2_behavior_tree/plugins/action/assisted_teleop_action.cpp index 025f4786fc5..1f63a281c3e 100644 --- a/nav2_behavior_tree/plugins/action/assisted_teleop_action.cpp +++ b/nav2_behavior_tree/plugins/action/assisted_teleop_action.cpp @@ -41,11 +41,24 @@ void AssistedTeleopAction::on_tick() } } +BT::NodeStatus AssistedTeleopAction::on_success() +{ + setOutput("error_code_id", ActionGoal::NONE); + return BT::NodeStatus::SUCCESS; +} + BT::NodeStatus AssistedTeleopAction::on_aborted() { + setOutput("error_code_id", result_.result->error_code); return is_recovery_ ? BT::NodeStatus::FAILURE : BT::NodeStatus::SUCCESS; } +BT::NodeStatus AssistedTeleopAction::on_cancelled() +{ + setOutput("error_code_id", ActionGoal::NONE); + return BT::NodeStatus::SUCCESS; +} + } // namespace nav2_behavior_tree #include "behaviortree_cpp_v3/bt_factory.h" diff --git a/nav2_behavior_tree/plugins/action/back_up_action.cpp b/nav2_behavior_tree/plugins/action/back_up_action.cpp index b72afaf8106..9013a1244c1 100644 --- a/nav2_behavior_tree/plugins/action/back_up_action.cpp +++ b/nav2_behavior_tree/plugins/action/back_up_action.cpp @@ -46,6 +46,24 @@ void BackUpAction::on_tick() increment_recovery_count(); } +BT::NodeStatus BackUpAction::on_success() +{ + setOutput("error_code_id", ActionGoal::NONE); + return BT::NodeStatus::SUCCESS; +} + +BT::NodeStatus BackUpAction::on_aborted() +{ + setOutput("error_code_id", result_.result->error_code); + return BT::NodeStatus::FAILURE; +} + +BT::NodeStatus BackUpAction::on_cancelled() +{ + setOutput("error_code_id", ActionGoal::NONE); + return BT::NodeStatus::SUCCESS; +} + } // namespace nav2_behavior_tree #include "behaviortree_cpp_v3/bt_factory.h" diff --git a/nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp b/nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp index 81a93a63628..73036ccddd6 100644 --- a/nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp +++ b/nav2_behavior_tree/plugins/action/drive_on_heading_action.cpp @@ -41,6 +41,24 @@ DriveOnHeadingAction::DriveOnHeadingAction( goal_.time_allowance = rclcpp::Duration::from_seconds(time_allowance); } +BT::NodeStatus DriveOnHeadingAction::on_success() +{ + setOutput("error_code_id", ActionGoal::NONE); + return BT::NodeStatus::SUCCESS; +} + +BT::NodeStatus DriveOnHeadingAction::on_aborted() +{ + setOutput("error_code_id", result_.result->error_code); + return BT::NodeStatus::FAILURE; +} + +BT::NodeStatus DriveOnHeadingAction::on_cancelled() +{ + setOutput("error_code_id", ActionGoal::NONE); + return BT::NodeStatus::SUCCESS; +} + } // namespace nav2_behavior_tree #include "behaviortree_cpp_v3/bt_factory.h" diff --git a/nav2_behavior_tree/plugins/action/spin_action.cpp b/nav2_behavior_tree/plugins/action/spin_action.cpp index 73dc8c589fb..dd203499502 100644 --- a/nav2_behavior_tree/plugins/action/spin_action.cpp +++ b/nav2_behavior_tree/plugins/action/spin_action.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include #include #include "nav2_behavior_tree/plugins/action/spin_action.hpp" @@ -42,6 +41,24 @@ void SpinAction::on_tick() } } +BT::NodeStatus SpinAction::on_success() +{ + setOutput("error_code_id", ActionGoal::NONE); + return BT::NodeStatus::SUCCESS; +} + +BT::NodeStatus SpinAction::on_aborted() +{ + setOutput("error_code_id", result_.result->error_code); + return BT::NodeStatus::FAILURE; +} + +BT::NodeStatus SpinAction::on_cancelled() +{ + setOutput("error_code_id", ActionGoal::NONE); + return BT::NodeStatus::SUCCESS; +} + } // namespace nav2_behavior_tree #include "behaviortree_cpp_v3/bt_factory.h" diff --git a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp index 579a2fd0ce9..eb640780d3d 100644 --- a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp +++ b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp @@ -15,6 +15,8 @@ #ifndef NAV2_BEHAVIORS__TIMED_BEHAVIOR_HPP_ #define NAV2_BEHAVIORS__TIMED_BEHAVIOR_HPP_ + +#include #include #include #include @@ -35,6 +37,7 @@ #include "tf2/utils.h" #pragma GCC diagnostic pop + namespace nav2_behaviors { @@ -45,6 +48,12 @@ enum class Status : int8_t RUNNING = 3, }; +struct ResultStatus +{ + Status status; + uint16_t error_code{0}; +}; + using namespace std::chrono_literals; //NOLINT /** @@ -73,7 +82,7 @@ class TimedBehavior : public nav2_core::Behavior // Derived classes can override this method to catch the command and perform some checks // before getting into the main loop. The method will only be called // once and should return SUCCEEDED otherwise behavior will return FAILED. - virtual Status onRun(const std::shared_ptr command) = 0; + virtual ResultStatus onRun(const std::shared_ptr command) = 0; // This is the method derived classes should mainly implement @@ -81,7 +90,7 @@ class TimedBehavior : public nav2_core::Behavior // Implement the behavior such that it runs some unit of work on each call // and provides a status. The Behavior will finish once SUCCEEDED is returned // It's up to the derived class to define the final commanded velocity. - virtual Status onCycleUpdate() = 0; + virtual ResultStatus onCycleUpdate() = 0; // an opportunity for derived classes to do something on configuration // if they chose @@ -193,19 +202,20 @@ class TimedBehavior : public nav2_core::Behavior return; } - if (onRun(action_server_->get_current_goal()) != Status::SUCCEEDED) { + // Initialize the ActionT result + auto result = std::make_shared(); + + ResultStatus on_run_result = onRun(action_server_->get_current_goal()); + if (on_run_result.status != Status::SUCCEEDED) { RCLCPP_INFO( logger_, "Initial checks failed for %s", behavior_name_.c_str()); - action_server_->terminate_current(); + result->error_code = on_run_result.error_code; + action_server_->terminate_current(result); return; } auto start_time = steady_clock_.now(); - - // Initialize the ActionT result - auto result = std::make_shared(); - rclcpp::WallRate loop_rate(cycle_frequency_); while (rclcpp::ok()) { @@ -232,7 +242,8 @@ class TimedBehavior : public nav2_core::Behavior return; } - switch (onCycleUpdate()) { + ResultStatus on_cycle_update_result = onCycleUpdate(); + switch (on_cycle_update_result.status) { case Status::SUCCEEDED: RCLCPP_INFO( logger_, @@ -245,6 +256,7 @@ class TimedBehavior : public nav2_core::Behavior 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; action_server_->terminate_current(result); onActionCompletion(); return; diff --git a/nav2_behaviors/plugins/assisted_teleop.cpp b/nav2_behaviors/plugins/assisted_teleop.cpp index defdfaf5a70..0ca8412abaf 100644 --- a/nav2_behaviors/plugins/assisted_teleop.cpp +++ b/nav2_behaviors/plugins/assisted_teleop.cpp @@ -63,12 +63,12 @@ void AssistedTeleop::onConfigure() this, std::placeholders::_1)); } -Status AssistedTeleop::onRun(const std::shared_ptr command) +ResultStatus AssistedTeleop::onRun(const std::shared_ptr command) { preempt_teleop_ = false; command_time_allowance_ = command->time_allowance; end_time_ = steady_clock_.now() + command_time_allowance_; - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED, AssistedTeleopActionGoal::NONE}; } void AssistedTeleop::onActionCompletion() @@ -77,7 +77,7 @@ void AssistedTeleop::onActionCompletion() preempt_teleop_ = false; } -Status AssistedTeleop::onCycleUpdate() +ResultStatus AssistedTeleop::onCycleUpdate() { feedback_->current_teleop_duration = elasped_time_; action_server_->publish_feedback(feedback_); @@ -89,13 +89,13 @@ Status AssistedTeleop::onCycleUpdate() logger_, "Exceeded time allowance before reaching the " << behavior_name_.c_str() << "goal - Exiting " << behavior_name_.c_str()); - return Status::FAILED; + return ResultStatus{Status::FAILED, AssistedTeleopActionGoal::TIMEOUT}; } // user states that teleop was successful if (preempt_teleop_) { stopRobot(); - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED, AssistedTeleopActionGoal::NONE}; } geometry_msgs::msg::PoseStamped current_pose; @@ -107,8 +107,9 @@ Status AssistedTeleop::onCycleUpdate() logger_, "Current robot pose is not available for " << behavior_name_.c_str()); - return Status::FAILED; + return ResultStatus{Status::FAILED, AssistedTeleopActionGoal::TF_ERROR}; } + geometry_msgs::msg::Pose2D projected_pose; projected_pose.x = current_pose.pose.position.x; projected_pose.y = current_pose.pose.position.y; @@ -147,7 +148,7 @@ Status AssistedTeleop::onCycleUpdate() } vel_pub_->publish(std::move(scaled_twist)); - return Status::RUNNING; + return ResultStatus{Status::RUNNING, AssistedTeleopActionGoal::NONE}; } geometry_msgs::msg::Pose2D AssistedTeleop::projectPose( diff --git a/nav2_behaviors/plugins/assisted_teleop.hpp b/nav2_behaviors/plugins/assisted_teleop.hpp index 12a85f327c4..8f45e43bd5a 100644 --- a/nav2_behaviors/plugins/assisted_teleop.hpp +++ b/nav2_behaviors/plugins/assisted_teleop.hpp @@ -35,6 +35,7 @@ using AssistedTeleopAction = nav2_msgs::action::AssistedTeleop; class AssistedTeleop : public TimedBehavior { public: + using AssistedTeleopActionGoal = AssistedTeleopAction::Goal; AssistedTeleop(); /** @@ -42,7 +43,7 @@ class AssistedTeleop : public TimedBehavior * @param command Goal to execute * @return Status of behavior */ - Status onRun(const std::shared_ptr command) override; + ResultStatus onRun(const std::shared_ptr command) override; /** * @brief func to run at the completion of the action @@ -53,7 +54,7 @@ class AssistedTeleop : public TimedBehavior * @brief Loop function to run behavior * @return Status of behavior */ - Status onCycleUpdate() override; + ResultStatus onCycleUpdate() override; protected: /** diff --git a/nav2_behaviors/plugins/back_up.cpp b/nav2_behaviors/plugins/back_up.cpp index 90a69a686ed..3e34bc86fc3 100644 --- a/nav2_behaviors/plugins/back_up.cpp +++ b/nav2_behaviors/plugins/back_up.cpp @@ -17,13 +17,13 @@ namespace nav2_behaviors { -Status BackUp::onRun(const std::shared_ptr command) +ResultStatus BackUp::onRun(const std::shared_ptr command) { if (command->target.y != 0.0 || command->target.z != 0.0) { RCLCPP_INFO( logger_, "Backing up in Y and Z not supported, will only move in X."); - return Status::FAILED; + return ResultStatus{Status::FAILED, BackUpActionGoal::INVALID_INPUT}; } // Silently ensure that both the speed and direction are negative. @@ -38,10 +38,10 @@ Status BackUp::onRun(const std::shared_ptr command) transform_tolerance_)) { RCLCPP_ERROR(logger_, "Initial robot pose is not available."); - return Status::FAILED; + return ResultStatus{Status::FAILED, BackUpActionGoal::TF_ERROR}; } - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED, BackUpActionGoal::NONE}; } } // namespace nav2_behaviors diff --git a/nav2_behaviors/plugins/back_up.hpp b/nav2_behaviors/plugins/back_up.hpp index f892c5b0e2d..3715297554d 100644 --- a/nav2_behaviors/plugins/back_up.hpp +++ b/nav2_behaviors/plugins/back_up.hpp @@ -28,7 +28,9 @@ namespace nav2_behaviors class BackUp : public DriveOnHeading { public: - Status onRun(const std::shared_ptr command) override; + using BackUpActionGoal = BackUpAction::Goal; + + ResultStatus onRun(const std::shared_ptr command) override; }; } diff --git a/nav2_behaviors/plugins/drive_on_heading.hpp b/nav2_behaviors/plugins/drive_on_heading.hpp index 79c8d81c719..d430803d300 100644 --- a/nav2_behaviors/plugins/drive_on_heading.hpp +++ b/nav2_behaviors/plugins/drive_on_heading.hpp @@ -55,19 +55,19 @@ class DriveOnHeading : public TimedBehavior * @param command Goal to execute * @return Status of behavior */ - Status onRun(const std::shared_ptr command) override + ResultStatus onRun(const std::shared_ptr command) override { if (command->target.y != 0.0 || command->target.z != 0.0) { RCLCPP_INFO( this->logger_, "DrivingOnHeading in Y and Z not supported, will only move in X."); - return Status::FAILED; + return ResultStatus{Status::FAILED, ActionT::Goal::INVALID_INPUT}; } // Ensure that both the speed and direction have the same sign if (!((command->target.x > 0.0) == (command->speed > 0.0)) ) { RCLCPP_ERROR(this->logger_, "Speed and command sign did not match"); - return Status::FAILED; + return ResultStatus{Status::FAILED, ActionT::Goal::INVALID_INPUT}; } command_x_ = command->target.x; @@ -81,17 +81,17 @@ class DriveOnHeading : public TimedBehavior this->transform_tolerance_)) { RCLCPP_ERROR(this->logger_, "Initial robot pose is not available."); - return Status::FAILED; + return ResultStatus{Status::FAILED, ActionT::Goal::TF_ERROR}; } - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED, ActionT::Goal::NONE}; } /** * @brief Loop function to run behavior * @return Status of behavior */ - Status onCycleUpdate() + ResultStatus onCycleUpdate() { rclcpp::Duration time_remaining = end_time_ - this->steady_clock_.now(); if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) { @@ -99,7 +99,7 @@ class DriveOnHeading : public TimedBehavior RCLCPP_WARN( this->logger_, "Exceeded time allowance before reaching the DriveOnHeading goal - Exiting DriveOnHeading"); - return Status::FAILED; + return ResultStatus{Status::FAILED, ActionT::Goal::NONE}; } geometry_msgs::msg::PoseStamped current_pose; @@ -108,7 +108,7 @@ class DriveOnHeading : public TimedBehavior this->transform_tolerance_)) { RCLCPP_ERROR(this->logger_, "Current robot pose is not available."); - return Status::FAILED; + return ResultStatus{Status::FAILED, ActionT::Goal::TF_ERROR}; } double diff_x = initial_pose_.pose.position.x - current_pose.pose.position.x; @@ -120,7 +120,7 @@ class DriveOnHeading : public TimedBehavior if (distance >= std::fabs(command_x_)) { this->stopRobot(); - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED, ActionT::Goal::NONE}; } auto cmd_vel = std::make_unique(); @@ -136,12 +136,12 @@ class DriveOnHeading : public TimedBehavior if (!isCollisionFree(distance, cmd_vel.get(), pose2d)) { this->stopRobot(); RCLCPP_WARN(this->logger_, "Collision Ahead - Exiting DriveOnHeading"); - return Status::FAILED; + return ResultStatus{Status::FAILED, ActionT::Goal::COLLISION_AHEAD}; } this->vel_pub_->publish(std::move(cmd_vel)); - return Status::RUNNING; + return ResultStatus{Status::RUNNING, ActionT::Goal::NONE}; } protected: diff --git a/nav2_behaviors/plugins/spin.cpp b/nav2_behaviors/plugins/spin.cpp index a76fe38f525..38255e69478 100644 --- a/nav2_behaviors/plugins/spin.cpp +++ b/nav2_behaviors/plugins/spin.cpp @@ -71,7 +71,7 @@ void Spin::onConfigure() node->get_parameter("rotational_acc_lim", rotational_acc_lim_); } -Status Spin::onRun(const std::shared_ptr command) +ResultStatus Spin::onRun(const std::shared_ptr command) { geometry_msgs::msg::PoseStamped current_pose; if (!nav2_util::getCurrentPose( @@ -79,7 +79,7 @@ Status Spin::onRun(const std::shared_ptr command) transform_tolerance_)) { RCLCPP_ERROR(logger_, "Current robot pose is not available."); - return Status::FAILED; + return ResultStatus{Status::FAILED, SpinActionGoal::TF_ERROR}; } prev_yaw_ = tf2::getYaw(current_pose.pose.orientation); @@ -93,10 +93,10 @@ Status Spin::onRun(const std::shared_ptr command) command_time_allowance_ = command->time_allowance; end_time_ = steady_clock_.now() + command_time_allowance_; - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED, SpinActionGoal::NONE}; } -Status Spin::onCycleUpdate() +ResultStatus Spin::onCycleUpdate() { rclcpp::Duration time_remaining = end_time_ - steady_clock_.now(); if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) { @@ -104,7 +104,7 @@ Status Spin::onCycleUpdate() RCLCPP_WARN( logger_, "Exceeded time allowance before reaching the Spin goal - Exiting Spin"); - return Status::FAILED; + return ResultStatus{Status::FAILED, SpinActionGoal::TIMEOUT}; } geometry_msgs::msg::PoseStamped current_pose; @@ -113,7 +113,7 @@ Status Spin::onCycleUpdate() transform_tolerance_)) { RCLCPP_ERROR(logger_, "Current robot pose is not available."); - return Status::FAILED; + return ResultStatus{Status::FAILED, SpinActionGoal::TF_ERROR}; } const double current_yaw = tf2::getYaw(current_pose.pose.orientation); @@ -132,7 +132,7 @@ Status Spin::onCycleUpdate() double remaining_yaw = abs(cmd_yaw_) - abs(relative_yaw_); if (remaining_yaw < 1e-6) { stopRobot(); - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED, SpinActionGoal::NONE}; } double vel = sqrt(2 * rotational_acc_lim_ * remaining_yaw); @@ -149,12 +149,12 @@ Status Spin::onCycleUpdate() if (!isCollisionFree(relative_yaw_, cmd_vel.get(), pose2d)) { stopRobot(); RCLCPP_WARN(logger_, "Collision Ahead - Exiting Spin"); - return Status::FAILED; + return ResultStatus{Status::FAILED, SpinActionGoal::COLLISION_AHEAD}; } vel_pub_->publish(std::move(cmd_vel)); - return Status::RUNNING; + return ResultStatus{Status::RUNNING, SpinActionGoal::NONE}; } bool Spin::isCollisionFree( diff --git a/nav2_behaviors/plugins/spin.hpp b/nav2_behaviors/plugins/spin.hpp index 7174c91f467..e22ddcd8f8f 100644 --- a/nav2_behaviors/plugins/spin.hpp +++ b/nav2_behaviors/plugins/spin.hpp @@ -34,6 +34,8 @@ using SpinAction = nav2_msgs::action::Spin; class Spin : public TimedBehavior { public: + using SpinActionGoal = SpinAction::Goal; + /** * @brief A constructor for nav2_behaviors::Spin */ @@ -45,7 +47,7 @@ class Spin : public TimedBehavior * @param command Goal to execute * @return Status of behavior */ - Status onRun(const std::shared_ptr command) override; + ResultStatus onRun(const std::shared_ptr command) override; /** * @brief Configuration of behavior action @@ -56,7 +58,7 @@ class Spin : public TimedBehavior * @brief Loop function to run behavior * @return Status of behavior */ - Status onCycleUpdate() override; + ResultStatus onCycleUpdate() override; protected: /** diff --git a/nav2_behaviors/plugins/wait.cpp b/nav2_behaviors/plugins/wait.cpp index 236f7122018..9b006196d99 100644 --- a/nav2_behaviors/plugins/wait.cpp +++ b/nav2_behaviors/plugins/wait.cpp @@ -28,14 +28,14 @@ Wait::Wait() Wait::~Wait() = default; -Status Wait::onRun(const std::shared_ptr command) +ResultStatus Wait::onRun(const std::shared_ptr command) { wait_end_ = std::chrono::steady_clock::now() + rclcpp::Duration(command->time).to_chrono(); - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED}; } -Status Wait::onCycleUpdate() +ResultStatus Wait::onCycleUpdate() { auto current_point = std::chrono::steady_clock::now(); auto time_left = @@ -45,9 +45,9 @@ Status Wait::onCycleUpdate() action_server_->publish_feedback(feedback_); if (time_left > 0) { - return Status::RUNNING; + return ResultStatus{Status::RUNNING}; } else { - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED}; } } diff --git a/nav2_behaviors/plugins/wait.hpp b/nav2_behaviors/plugins/wait.hpp index 38e85fd14aa..32c9aa7f1da 100644 --- a/nav2_behaviors/plugins/wait.hpp +++ b/nav2_behaviors/plugins/wait.hpp @@ -33,6 +33,8 @@ using WaitAction = nav2_msgs::action::Wait; class Wait : public TimedBehavior { public: + using WaitActionGoal = WaitAction::Goal; + /** * @brief A constructor for nav2_behaviors::Wait */ @@ -44,13 +46,13 @@ class Wait : public TimedBehavior * @param command Goal to execute * @return Status of behavior */ - Status onRun(const std::shared_ptr command) override; + ResultStatus onRun(const std::shared_ptr command) override; /** * @brief Loop function to run behavior * @return Status of behavior */ - Status onCycleUpdate() override; + ResultStatus onCycleUpdate() override; protected: std::chrono::time_point wait_end_; diff --git a/nav2_behaviors/test/test_behaviors.cpp b/nav2_behaviors/test/test_behaviors.cpp index 4cd7527fbcf..7b99289dbda 100644 --- a/nav2_behaviors/test/test_behaviors.cpp +++ b/nav2_behaviors/test/test_behaviors.cpp @@ -27,6 +27,7 @@ using nav2_behaviors::TimedBehavior; using nav2_behaviors::Status; +using nav2_behaviors::ResultStatus; using BehaviorAction = nav2_msgs::action::DummyBehavior; using ClientGoalHandle = rclcpp_action::ClientGoalHandle; @@ -43,7 +44,7 @@ class DummyBehavior : public TimedBehavior ~DummyBehavior() = default; - Status onRun(const std::shared_ptr goal) override + ResultStatus onRun(const std::shared_ptr goal) override { // A normal behavior would catch the command and initialize initialized_ = false; @@ -54,20 +55,20 @@ class DummyBehavior : public TimedBehavior // The output is defined by the tester class on the command string. if (command_ == "Testing success" || command_ == "Testing failure on run") { initialized_ = true; - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED, 0}; } - return Status::FAILED; + return ResultStatus{Status::FAILED, 0}; } - Status onCycleUpdate() override + ResultStatus onCycleUpdate() override { // A normal behavior would set the robot in motion in the first call // and check for robot states on subsequent calls to check if the movement // was completed. if (command_ != "Testing success" || !initialized_) { - return Status::FAILED; + return ResultStatus{Status::FAILED, 0}; } // For testing, pretend the robot takes some fixed @@ -77,10 +78,10 @@ class DummyBehavior : public TimedBehavior if (current_time - start_time_ >= motion_duration) { // Movement was completed - return Status::SUCCEEDED; + return ResultStatus{Status::SUCCEEDED, 0}; } - return Status::RUNNING; + return ResultStatus{Status::RUNNING, 0}; } private: @@ -94,7 +95,7 @@ class DummyBehavior : public TimedBehavior class BehaviorTest : public ::testing::Test { protected: - BehaviorTest() {SetUp();} + BehaviorTest() = default; ~BehaviorTest() = default; void SetUp() override diff --git a/nav2_bt_navigator/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml b/nav2_bt_navigator/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml index 3dc5a765031..c5056c1c199 100644 --- a/nav2_bt_navigator/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml +++ b/nav2_bt_navigator/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml @@ -28,9 +28,9 @@ - + - + diff --git a/nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml b/nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml index 07d3a363989..6843f3d8592 100644 --- a/nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml +++ b/nav2_bt_navigator/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml @@ -37,9 +37,9 @@ - + - + diff --git a/nav2_msgs/action/AssistedTeleop.action b/nav2_msgs/action/AssistedTeleop.action index ba830ebc121..7507c46cf5a 100644 --- a/nav2_msgs/action/AssistedTeleop.action +++ b/nav2_msgs/action/AssistedTeleop.action @@ -1,8 +1,16 @@ +# Error codes +# Note: The expected priority order of the error should match the message order +uint16 NONE=0 +uint16 UNKNOWN=730 +uint16 TIMEOUT=731 +uint16 TF_ERROR=732 + #goal definition builtin_interfaces/Duration time_allowance --- #result definition builtin_interfaces/Duration total_elapsed_time +uint16 error_code --- #feedback builtin_interfaces/Duration current_teleop_duration diff --git a/nav2_msgs/action/BackUp.action b/nav2_msgs/action/BackUp.action index 9937302578a..298e8c56ba1 100644 --- a/nav2_msgs/action/BackUp.action +++ b/nav2_msgs/action/BackUp.action @@ -1,3 +1,12 @@ +# Error codes +# Note: The expected priority order of the error should match the message order +uint16 NONE=0 +uint16 UNKNOWN=710 +uint16 TIMEOUT=711 +uint16 TF_ERROR=712 +uint16 INVALID_INPUT=713 +uint16 COLLISION_AHEAD=714 + #goal definition geometry_msgs/Point target float32 speed @@ -5,6 +14,7 @@ builtin_interfaces/Duration time_allowance --- #result definition builtin_interfaces/Duration total_elapsed_time +uint16 error_code --- #feedback definition float32 distance_traveled diff --git a/nav2_msgs/action/DriveOnHeading.action b/nav2_msgs/action/DriveOnHeading.action index 9937302578a..529d88d61b6 100644 --- a/nav2_msgs/action/DriveOnHeading.action +++ b/nav2_msgs/action/DriveOnHeading.action @@ -1,3 +1,12 @@ +# Error codes +# Note: The expected priority order of the error should match the message order +uint16 NONE=0 +uint16 UNKNOWN=720 +uint16 TIMEOUT=721 +uint16 TF_ERROR=722 +uint16 COLLISION_AHEAD=723 +uint16 INVALID_INPUT=724 + #goal definition geometry_msgs/Point target float32 speed @@ -5,6 +14,7 @@ builtin_interfaces/Duration time_allowance --- #result definition builtin_interfaces/Duration total_elapsed_time +uint16 error_code --- #feedback definition float32 distance_traveled diff --git a/nav2_msgs/action/DummyBehavior.action b/nav2_msgs/action/DummyBehavior.action index 4b8db815d2b..2b90ea781a7 100644 --- a/nav2_msgs/action/DummyBehavior.action +++ b/nav2_msgs/action/DummyBehavior.action @@ -3,5 +3,6 @@ std_msgs/String command --- #result definition builtin_interfaces/Duration total_elapsed_time +uint16 error_code --- #feedback definition diff --git a/nav2_msgs/action/Spin.action b/nav2_msgs/action/Spin.action index 3e1c0aadef0..036cd1b8f50 100644 --- a/nav2_msgs/action/Spin.action +++ b/nav2_msgs/action/Spin.action @@ -1,9 +1,18 @@ +# Error codes +# Note: The expected priority order of the error should match the message order +uint16 NONE=0 +uint16 UNKNOWN=700 +uint16 TIMEOUT=701 +uint16 TF_ERROR=702 +uint16 COLLISION_AHEAD=703 + #goal definition float32 target_yaw builtin_interfaces/Duration time_allowance --- #result definition builtin_interfaces/Duration total_elapsed_time +uint16 error_code --- #feedback definition float32 angular_distance_traveled diff --git a/nav2_msgs/action/Wait.action b/nav2_msgs/action/Wait.action index 8cf7119431d..4657a7daa20 100644 --- a/nav2_msgs/action/Wait.action +++ b/nav2_msgs/action/Wait.action @@ -3,6 +3,7 @@ builtin_interfaces/Duration time --- #result definition builtin_interfaces/Duration total_elapsed_time +uint16 error_code --- #feedback definition builtin_interfaces/Duration time_left