diff --git a/nexus_capabilities/src/capabilities/gripper_capability.hpp b/nexus_capabilities/src/capabilities/gripper_capability.hpp index 09b901e..02fe6be 100644 --- a/nexus_capabilities/src/capabilities/gripper_capability.hpp +++ b/nexus_capabilities/src/capabilities/gripper_capability.hpp @@ -46,7 +46,8 @@ public: void declare_params(rclcpp_lifecycle::LifecycleNode& node) final; /** * @copydoc Capability::configure */ -public: common::Result 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_workcell_orchestrator/src/workcell_orchestrator.cpp b/nexus_workcell_orchestrator/src/workcell_orchestrator.cpp index 422f738..6917a42 100644 --- a/nexus_workcell_orchestrator/src/workcell_orchestrator.cpp +++ b/nexus_workcell_orchestrator/src/workcell_orchestrator.cpp @@ -316,7 +316,8 @@ auto WorkcellOrchestrator::_configure( return; } - auto ctx = std::make_shared(this->shared_from_this(), goal_handle); + 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())