diff --git a/nexus_capabilities/CMakeLists.txt b/nexus_capabilities/CMakeLists.txt index 6f9d4a3..c9e590e 100644 --- a/nexus_capabilities/CMakeLists.txt +++ b/nexus_capabilities/CMakeLists.txt @@ -56,6 +56,7 @@ include(GNUInstallDirs) # nexus_capabilities library add_library(${PROJECT_NAME} SHARED + src/context.cpp src/conversions/pose_stamped.cpp ) diff --git a/nexus_capabilities/include/nexus_capabilities/capability.hpp b/nexus_capabilities/include/nexus_capabilities/capability.hpp index 830febf..5469dc4 100644 --- a/nexus_capabilities/include/nexus_capabilities/capability.hpp +++ b/nexus_capabilities/include/nexus_capabilities/capability.hpp @@ -22,6 +22,7 @@ #include "task.hpp" #include +#include #include #include @@ -54,7 +55,7 @@ class Capability * @param bt_factory Must be valid for the lifetime of the capability. * @throws StateTransitionError if transition fails. */ - virtual void configure( + [[nodiscard]] virtual common::Result configure( rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr ctx_mgr, BT::BehaviorTreeFactory& bt_factory) = 0; diff --git a/nexus_capabilities/include/nexus_capabilities/context.hpp b/nexus_capabilities/include/nexus_capabilities/context.hpp index 75d5cfa..a8c1011 100644 --- a/nexus_capabilities/include/nexus_capabilities/context.hpp +++ b/nexus_capabilities/include/nexus_capabilities/context.hpp @@ -20,6 +20,11 @@ #include "task.hpp" +#include +#include +#include + +#include #include #include @@ -32,6 +37,9 @@ namespace nexus { class Context { +public: using GoalHandlePtr = + std::shared_ptr>; + /** * There are several choices we can use here, each having their own pros and cons. * @@ -65,8 +73,15 @@ public: Task task; public: std::vector errors; public: std::unordered_set signals; -public: Context(std::shared_ptr node) - : node(std::move(node)) {} +public: Context(std::shared_ptr node, + GoalHandlePtr goal_handle) + : node(std::move(node)), _goal_handle(std::move(goal_handle)) {} + +public: common::Result publish_feedback( + const nexus_orchestrator_msgs::msg::TaskProgress& progress, + const std::string& msg = ""); + +private: GoalHandlePtr _goal_handle; }; } // namespace nexus diff --git a/nexus_capabilities/include/nexus_capabilities/exceptions.hpp b/nexus_capabilities/include/nexus_capabilities/exceptions.hpp deleted file mode 100644 index 64100f6..0000000 --- a/nexus_capabilities/include/nexus_capabilities/exceptions.hpp +++ /dev/null @@ -1,37 +0,0 @@ -/* - * Copyright (C) 2022 Johnson & Johnson - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - */ - -#ifndef NEXUS_CAPABILITIES__EXCEPTIONS_HPP -#define NEXUS_CAPABILITIES__EXCEPTIONS_HPP - -#include -#include - -namespace nexus { - -/** - * Base class for all errors from capabilities. - */ -class CapabilityError : public std::runtime_error -{ -public: CapabilityError(const std::string& msg) - : std::runtime_error(msg) {} -}; - -} - -#endif // NEXUS_CAPABILITIES__EXCEPTIONS_HPP diff --git a/nexus_capabilities/src/capabilities/detection_capability.cpp b/nexus_capabilities/src/capabilities/detection_capability.cpp index c546411..05975f3 100644 --- a/nexus_capabilities/src/capabilities/detection_capability.cpp +++ b/nexus_capabilities/src/capabilities/detection_capability.cpp @@ -37,7 +37,7 @@ void DetectionCapability::declare_params( } //============================================================================== -void DetectionCapability::configure( +common::Result DetectionCapability::configure( rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr ctx_mgr, BT::BehaviorTreeFactory& bt_factory) @@ -57,18 +57,11 @@ void DetectionCapability::configure( bt_factory.registerBuilder( "detection.DetectOffset", - [this, ctx_mgr, w_node = std::weak_ptr{node}](const std::string& name, + [this, ctx_mgr, node](const std::string& name, const BT::NodeConfiguration& config) { - auto node = w_node.lock(); - if (!node) - { - std::cerr << "FATAL ERROR!!! NODE IS DESTROYED WHILE THERE ARE STILL REFERENCES!!!" << std::endl; - std::terminate(); - } - return std::make_unique(name, config, - node->get_logger(), ctx_mgr, [this, node](const std::string& detector) + node->get_logger(), ctx_mgr, [this](const std::string& detector) { return this->_clients.at(detector); }); @@ -76,16 +69,9 @@ void DetectionCapability::configure( bt_factory.registerBuilder( "detection.DetectAllItems", - [this, ctx_mgr, w_node = std::weak_ptr{node}](const std::string& name, + [this, ctx_mgr, node](const std::string& name, const BT::NodeConfiguration& config) { - auto node = w_node.lock(); - if (!node) - { - std::cerr << "FATAL ERROR!!! NODE IS DESTROYED WHILE THERE ARE STILL REFERENCES!!!" << std::endl; - std::terminate(); - } - return std::make_unique(name, config, node, ctx_mgr, [this](const std::string& detector) { @@ -106,6 +92,8 @@ void DetectionCapability::configure( { return std::make_unique(name, config, ctx_mgr); }); + + return common::Result(); } //============================================================================== diff --git a/nexus_capabilities/src/capabilities/detection_capability.hpp b/nexus_capabilities/src/capabilities/detection_capability.hpp index ced80a5..81c72c1 100644 --- a/nexus_capabilities/src/capabilities/detection_capability.hpp +++ b/nexus_capabilities/src/capabilities/detection_capability.hpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -45,7 +46,7 @@ public: void declare_params(rclcpp_lifecycle::LifecycleNode& node) final; /** * @copydoc Capability::configure */ -public: void configure( +public: common::Result configure( rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr ctx_mgr, BT::BehaviorTreeFactory& bt_factory) final; diff --git a/nexus_capabilities/src/capabilities/dispense_item_capability.cpp b/nexus_capabilities/src/capabilities/dispense_item_capability.cpp index 1277d8c..9288d3c 100644 --- a/nexus_capabilities/src/capabilities/dispense_item_capability.cpp +++ b/nexus_capabilities/src/capabilities/dispense_item_capability.cpp @@ -19,8 +19,6 @@ #include "dispense_item_task_data.hpp" -#include - #include namespace nexus::capabilities { @@ -47,7 +45,7 @@ void DispenseItemCapability::declare_params( } //============================================================================== -void DispenseItemCapability::configure( +common::Result DispenseItemCapability::configure( rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr /* ctx_mgr */, BT::BehaviorTreeFactory& bt_factory) @@ -76,6 +74,8 @@ void DispenseItemCapability::configure( return std::make_unique(name, config, node, this->_dispensers, std::chrono::milliseconds{dispenser_timeout}); }); + + return common::Result(); } } diff --git a/nexus_capabilities/src/capabilities/dispense_item_capability.hpp b/nexus_capabilities/src/capabilities/dispense_item_capability.hpp index 15b5923..b01faaf 100644 --- a/nexus_capabilities/src/capabilities/dispense_item_capability.hpp +++ b/nexus_capabilities/src/capabilities/dispense_item_capability.hpp @@ -22,6 +22,7 @@ #include #include +#include #include #include @@ -48,7 +49,8 @@ public: void declare_params(rclcpp_lifecycle::LifecycleNode& node) final; /** * @copydoc Capability::configure */ -public: void configure(rclcpp_lifecycle::LifecycleNode::SharedPtr node, +public: common::Result configure( + rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr ctx_mgr, BT::BehaviorTreeFactory& bt_factory) final; diff --git a/nexus_capabilities/src/capabilities/execute_trajectory.hpp b/nexus_capabilities/src/capabilities/execute_trajectory.hpp index 768717e..3210187 100644 --- a/nexus_capabilities/src/capabilities/execute_trajectory.hpp +++ b/nexus_capabilities/src/capabilities/execute_trajectory.hpp @@ -35,7 +35,7 @@ namespace nexus::capabilities { * trajectory |moveit_msgs::msg::RobotTrajectory| The trajectory to execute. */ class ExecuteTrajectory : public common - ::ActionClientBtNode { public: using ActionType = @@ -54,9 +54,10 @@ public: static BT::PortsList providedPorts(); */ public: inline ExecuteTrajectory(const std::string& name, const BT::NodeConfiguration& config, - rclcpp_lifecycle::LifecycleNode& node) - : common::ActionClientBtNode( - name, config, &node) {} + rclcpp_lifecycle::LifecycleNode::SharedPtr node) + : common::ActionClientBtNode( + name, config, std::move(node)) {} protected: std::string get_action_name() const override diff --git a/nexus_capabilities/src/capabilities/execute_trajectory_capability.cpp b/nexus_capabilities/src/capabilities/execute_trajectory_capability.cpp index 8d66b25..d04e0ec 100644 --- a/nexus_capabilities/src/capabilities/execute_trajectory_capability.cpp +++ b/nexus_capabilities/src/capabilities/execute_trajectory_capability.cpp @@ -25,25 +25,19 @@ namespace nexus::capabilities { -void ExecuteTrajectoryCapability::configure( +common::Result ExecuteTrajectoryCapability::configure( rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr /* ctx_mgr */, BT::BehaviorTreeFactory& bt_factory) { bt_factory.registerBuilder( "execute_trajectory.ExecuteTrajectory", - [w_node = std::weak_ptr{node}](const std::string& name, + [node](const std::string& name, const BT::NodeConfiguration& config) { - auto node = w_node.lock(); - if (!node) - { - std::cerr << "FATAL ERROR!!! NODE IS DESTROYED WHILE THERE ARE STILL REFERENCES!!!" << std::endl; - std::terminate(); - } - - return std::make_unique(name, config, *node); + return std::make_unique(name, config, node); }); + return common::Result(); } } diff --git a/nexus_capabilities/src/capabilities/execute_trajectory_capability.hpp b/nexus_capabilities/src/capabilities/execute_trajectory_capability.hpp index d544f5e..d818712 100644 --- a/nexus_capabilities/src/capabilities/execute_trajectory_capability.hpp +++ b/nexus_capabilities/src/capabilities/execute_trajectory_capability.hpp @@ -22,6 +22,7 @@ #include #include +#include #include #include @@ -48,7 +49,8 @@ public: void declare_params(rclcpp_lifecycle::LifecycleNode& /* node */) final /** * @copydoc Capability::configure */ -public: void configure(rclcpp_lifecycle::LifecycleNode::SharedPtr node, +public: common::Result configure( + rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr ctx_mgr, BT::BehaviorTreeFactory& bt_factory) final; diff --git a/nexus_capabilities/src/capabilities/gripper_capability.cpp b/nexus_capabilities/src/capabilities/gripper_capability.cpp index b4ae30d..3a55abf 100644 --- a/nexus_capabilities/src/capabilities/gripper_capability.cpp +++ b/nexus_capabilities/src/capabilities/gripper_capability.cpp @@ -31,7 +31,7 @@ void GripperCapability::declare_params(rclcpp_lifecycle::LifecycleNode& node) node.declare_parameter("grippers", std::vector{}, desc); } -void GripperCapability::configure( +common::Result GripperCapability::configure( rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr /* ctx_mgr */, BT::BehaviorTreeFactory& bt_factory) @@ -48,6 +48,8 @@ void GripperCapability::configure( { return std::make_unique(name, config, *node); }); + + return common::Result(); } } diff --git a/nexus_capabilities/src/capabilities/gripper_capability.hpp b/nexus_capabilities/src/capabilities/gripper_capability.hpp index 82e541a..09b901e 100644 --- a/nexus_capabilities/src/capabilities/gripper_capability.hpp +++ b/nexus_capabilities/src/capabilities/gripper_capability.hpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -45,7 +46,7 @@ public: void declare_params(rclcpp_lifecycle::LifecycleNode& node) final; /** * @copydoc Capability::configure */ -public: void configure(rclcpp_lifecycle::LifecycleNode::SharedPtr node, +public: common::Result configure(rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr ctx_mgr, BT::BehaviorTreeFactory& bt_factory) final; diff --git a/nexus_capabilities/src/capabilities/plan_motion_capability.cpp b/nexus_capabilities/src/capabilities/plan_motion_capability.cpp index 7745047..da3e1e1 100644 --- a/nexus_capabilities/src/capabilities/plan_motion_capability.cpp +++ b/nexus_capabilities/src/capabilities/plan_motion_capability.cpp @@ -19,15 +19,13 @@ #include "plan_motion.hpp" -#include - #include #include namespace nexus::capabilities { -void PlanMotionCapability::configure( +common::Result PlanMotionCapability::configure( rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr /* ctx_mgr */, BT::BehaviorTreeFactory& bt_factory) @@ -43,6 +41,7 @@ void PlanMotionCapability::configure( return std::make_unique(name, config, *node, this->_client, tf_broadcaster); }); + return common::Result(); } } diff --git a/nexus_capabilities/src/capabilities/plan_motion_capability.hpp b/nexus_capabilities/src/capabilities/plan_motion_capability.hpp index 2622965..f2c7a2b 100644 --- a/nexus_capabilities/src/capabilities/plan_motion_capability.hpp +++ b/nexus_capabilities/src/capabilities/plan_motion_capability.hpp @@ -20,6 +20,7 @@ #include #include +#include #include #include @@ -45,7 +46,8 @@ public: void declare_params(rclcpp_lifecycle::LifecycleNode& /* node */) final /** * @copydoc Capability::configure */ -public: void configure(rclcpp_lifecycle::LifecycleNode::SharedPtr node, +public: common::Result configure( + rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr ctx_mgr, BT::BehaviorTreeFactory& bt_factory) final; diff --git a/nexus_capabilities/src/context.cpp b/nexus_capabilities/src/context.cpp new file mode 100644 index 0000000..d2d5f36 --- /dev/null +++ b/nexus_capabilities/src/context.cpp @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2023 Johnson & Johnson + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include "nexus_capabilities/context.hpp" + +#include + +namespace nexus { + +common::Result Context::publish_feedback( + const nexus_orchestrator_msgs::msg::TaskProgress& progress, + const std::string& msg) +{ + endpoints::WorkcellRequestAction::ActionType::Feedback::SharedPtr feedback_msg; + feedback_msg->state.task_id = this->task.id; + feedback_msg->state.workcell_id = this->node->get_name(); + feedback_msg->state.status = + nexus_orchestrator_msgs::msg::TaskState::STATUS_RUNNING; + feedback_msg->state.progress = progress; + feedback_msg->state.message = msg; + try + { + this->_goal_handle->publish_feedback(std::move(feedback_msg)); + return common::Result(); + } + catch (const std::runtime_error& e) + { + return e; + } +} + +} diff --git a/nexus_workcell_orchestrator/src/job_manager_test.cpp b/nexus_workcell_orchestrator/src/job_manager_test.cpp index 0cf8bd9..04179a1 100644 --- a/nexus_workcell_orchestrator/src/job_manager_test.cpp +++ b/nexus_workcell_orchestrator/src/job_manager_test.cpp @@ -109,7 +109,7 @@ TEST_CASE("JobManager") { SECTION("can queue an assigned task") { handle_accepted = [&](const JobManager::GoalHandlePtr& goal_handle) { - auto ctx = std::make_shared(fixture.node); + auto ctx = std::make_shared(fixture.node, goal_handle); CHECK(job_mgr.queue_task(goal_handle, ctx, bt_factory.createTreeFromText(bt)).value() == job); CHECK(job->bt.has_value()); @@ -148,7 +148,7 @@ TEST_CASE("JobManager") { size_t queued = 0; handle_accepted = [&](const JobManager::GoalHandlePtr& goal_handle) { - auto ctx = std::make_shared(fixture.node); + auto ctx = std::make_shared(fixture.node, goal_handle); REQUIRE(job_mgr.queue_task(goal_handle, ctx, bt_factory.createTreeFromText(bt)).value()); if (++queued == task_ids.size()) diff --git a/nexus_workcell_orchestrator/src/task_results_test.cpp b/nexus_workcell_orchestrator/src/task_results_test.cpp index 21b2b37..51503a8 100644 --- a/nexus_workcell_orchestrator/src/task_results_test.cpp +++ b/nexus_workcell_orchestrator/src/task_results_test.cpp @@ -34,7 +34,7 @@ namespace nexus::workcell_orchestrator::test { TEST_CASE("get and set results") { auto fixture = common::test::RosFixture{}; auto ctx_mgr = std::make_shared(); - auto ctx = std::make_shared(fixture.node); + auto ctx = std::make_shared(fixture.node, nullptr); ctx_mgr->set_active_context(ctx); BT::BehaviorTreeFactory bt_factory; diff --git a/nexus_workcell_orchestrator/src/workcell_orchestrator.cpp b/nexus_workcell_orchestrator/src/workcell_orchestrator.cpp index 5a97ee4..f664ff2 100644 --- a/nexus_workcell_orchestrator/src/workcell_orchestrator.cpp +++ b/nexus_workcell_orchestrator/src/workcell_orchestrator.cpp @@ -317,7 +317,7 @@ auto WorkcellOrchestrator::_configure( return; } - auto ctx = std::make_shared(this->shared_from_this()); + auto ctx = std::make_shared(this->shared_from_this(), goal_handle); auto task_result = this->_task_parser.parse_task(goal_handle->get_goal()->task); if (task_result.error()) @@ -564,30 +564,28 @@ auto WorkcellOrchestrator::_configure( } // configure capabilities - try + RCLCPP_INFO( + this->get_logger(), + "Configuring generic capabilities..." + ); + for (auto& [cap_id, cap] : this->_capabilities) { RCLCPP_INFO( this->get_logger(), - "Configuring generic capabilities..." + "configuring capability [%s]", + cap_id.c_str() ); - for (auto& [cap_id, cap] : this->_capabilities) + const auto r = cap->configure( + this->shared_from_this(), this->_job_mgr->context_manager(), + *_bt_factory); + if (r.error()) { - RCLCPP_INFO( - this->get_logger(), - "configuring capability [%s]", - cap_id.c_str() - ); - cap->configure( - this->shared_from_this(), this->_job_mgr->context_manager(), - *_bt_factory); + RCLCPP_ERROR( + this->get_logger(), "Failed to configure capability (%s)", + r.error()->what()); + return CallbackReturn::FAILURE; } } - catch (const CapabilityError& e) - { - RCLCPP_ERROR( - this->get_logger(), "Failed to configure capability (%s)", e.what()); - return CallbackReturn::FAILURE; - } // Create map for remapping capabilities auto remap_caps = this->get_parameter("remap_task_types").as_string();