Skip to content

Commit

Permalink
Rename capability and add rmf namespace
Browse files Browse the repository at this point in the history
Signed-off-by: Luca Della Vedova <lucadv@intrinsic.ai>
  • Loading branch information
luca-della-vedova committed Jan 3, 2025
1 parent c96fdbf commit ead8808
Show file tree
Hide file tree
Showing 9 changed files with 46 additions and 40 deletions.
4 changes: 2 additions & 2 deletions nexus_capabilities/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -130,8 +130,8 @@ add_library(nexus_builtin_capabilities SHARED
src/capabilities/gripper_control.cpp
src/capabilities/plan_motion_capability.cpp
src/capabilities/plan_motion.cpp
src/capabilities/transport_amr.cpp
src/capabilities/transport_amr_capability.cpp
src/capabilities/rmf_request.cpp
src/capabilities/rmf_request_capability.cpp
)

target_compile_options(nexus_builtin_capabilities PUBLIC INTERFACE cxx_std_17)
Expand Down
4 changes: 2 additions & 2 deletions nexus_capabilities/src/capabilities/plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
<description>PlanMotion capability.</description>
</class>

<class type="nexus::capabilities::TransportAmrCapability" base_class_type="nexus::Capability">
<description>TransportAmr capability.</description>
<class type="nexus::capabilities::RMFRequestCapability" base_class_type="nexus::Capability">
<description>RMFRequest capability.</description>
</class>
</library>
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,16 @@
*
*/

#include "transport_amr.hpp"
#include "rmf_request.hpp"

#include <nlohmann/json.hpp>
#include <yaml-cpp/yaml.h>

namespace nexus::capabilities {

BT::NodeStatus DispatchRmfRequest::onStart()
namespace rmf {

BT::NodeStatus DispatchRequest::onStart()
{
const auto destinations = this->getInput<std::deque<AmrDestination>>("destinations");
if (!destinations)
Expand All @@ -46,7 +48,7 @@ BT::NodeStatus DispatchRmfRequest::onStart()
return BT::NodeStatus::RUNNING;
}

void DispatchRmfRequest::submit_itinerary(const std::deque<AmrDestination>& destinations)
void DispatchRequest::submit_itinerary(const std::deque<AmrDestination>& destinations)
{
nlohmann::json j;
j["type"] = "dispatch_task_request";
Expand Down Expand Up @@ -89,7 +91,7 @@ void DispatchRmfRequest::submit_itinerary(const std::deque<AmrDestination>& dest
this->_api_request_pub->publish(msg);
}

void DispatchRmfRequest::api_response_cb(const ApiResponse& msg)
void DispatchRequest::api_response_cb(const ApiResponse& msg)
{
// Receive response, populate hashmaps
if (msg.type != msg.TYPE_RESPONDING)
Expand Down Expand Up @@ -119,7 +121,7 @@ void DispatchRmfRequest::api_response_cb(const ApiResponse& msg)
this->rmf_task_id = j["state"]["booking"]["id"];
}

BT::NodeStatus DispatchRmfRequest::onRunning()
BT::NodeStatus DispatchRequest::onRunning()
{
if (rmf_task_id.has_value())
{
Expand Down Expand Up @@ -328,3 +330,4 @@ BT::NodeStatus SendSignal::tick()
}

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
*
*/

#ifndef NEXUS_WORKCELL_ORCHESTRATOR__TRANSPORT_AMR_HPP
#define NEXUS_WORKCELL_ORCHESTRATOR__TRANSPORT_AMR_HPP
#ifndef NEXUS_WORKCELL_ORCHESTRATOR__RMF_REQUEST_HPP
#define NEXUS_WORKCELL_ORCHESTRATOR__RMF_REQUEST_HPP

#include <nexus_capabilities/context_manager.hpp>
#include <nexus_common/sync_service_client.hpp>
Expand All @@ -35,6 +35,8 @@

namespace nexus::capabilities {

namespace rmf {

struct AmrDestination {
// Either "pickup" or "dropoff"
std::string action;
Expand All @@ -48,7 +50,7 @@ struct AmrDestination {
* signal |std::string| Signal to wait for.
* clear |bool| Set this to true to clear the signal when this node is finished.
*/
class DispatchRmfRequest : public BT::StatefulActionNode
class DispatchRequest : public BT::StatefulActionNode
{
// RMF interfaces
public: using ApiRequest = rmf_task_msgs::msg::ApiRequest;
Expand All @@ -61,7 +63,7 @@ public: static BT::PortsList providedPorts()
};
}

public: DispatchRmfRequest(const std::string& name,
public: DispatchRequest(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp_lifecycle::LifecycleNode::SharedPtr node)
: BT::StatefulActionNode(name, config), _node(std::move(node)) {}
Expand Down Expand Up @@ -247,6 +249,7 @@ private: rclcpp_lifecycle::LifecycleNode::SharedPtr _node;
private: std::shared_ptr<const ContextManager> _ctx_mgr;
};

}
}

#endif
Original file line number Diff line number Diff line change
Expand Up @@ -17,59 +17,61 @@

// #include <behaviortree_cpp/decorators/loop_node.h>

#include "transport_amr.hpp"
#include "transport_amr_capability.hpp"
#include "rmf_request.hpp"
#include "rmf_request_capability.hpp"

namespace nexus::capabilities {

void TransportAmrCapability::configure(
using namespace rmf;

void RMFRequestCapability::configure(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
std::shared_ptr<const ContextManager> ctx_mgr,
BT::BehaviorTreeFactory& bt_factory)
{
bt_factory.registerBuilder<DispatchRmfRequest>("transport_amr.DispatchRmfRequest",
bt_factory.registerBuilder<DispatchRequest>("rmf_request.DispatchRequest",
[this, node](const std::string& name,
const BT::NodeConfiguration& config)
{
return std::make_unique<DispatchRmfRequest>(name, config, node);
return std::make_unique<DispatchRequest>(name, config, node);
});

bt_factory.registerBuilder<ExtractDestinations>("transport_amr.ExtractDestinations",
bt_factory.registerBuilder<ExtractDestinations>("rmf_request.ExtractDestinations",
[this, node, ctx_mgr](const std::string& name,
const BT::NodeConfiguration& config)
{
return std::make_unique<ExtractDestinations>(name, config, ctx_mgr, node);
});

bt_factory.registerBuilder<UnpackDestinationData>("transport_amr.UnpackDestinationData",
bt_factory.registerBuilder<UnpackDestinationData>("rmf_request.UnpackDestinationData",
[this, node](const std::string& name,
const BT::NodeConfiguration& config)
{
return std::make_unique<UnpackDestinationData>(name, config, node);
});

bt_factory.registerBuilder<SignalAmr>("transport_amr.SignalAmr",
bt_factory.registerBuilder<SignalAmr>("rmf_request.SignalAmr",
[this, node](const std::string& name,
const BT::NodeConfiguration& config)
{
return std::make_unique<SignalAmr>(name, config, node);
});

bt_factory.registerBuilder<LoopDestinations>("transport_amr.LoopDestinations",
bt_factory.registerBuilder<LoopDestinations>("rmf_request.LoopDestinations",
[this, node](const std::string& name,
const BT::NodeConfiguration& config)
{
return std::make_unique<LoopDestinations>(name, config, node);
});

bt_factory.registerBuilder<WaitForAmr>("transport_amr.WaitForAmr",
bt_factory.registerBuilder<WaitForAmr>("rmf_request.WaitForAmr",
[this, node](const std::string& name,
const BT::NodeConfiguration& config)
{
return std::make_unique<WaitForAmr>(name, config, node);
});

bt_factory.registerBuilder<SendSignal>("transport_amr.SendSignal",
bt_factory.registerBuilder<SendSignal>("rmf_request.SendSignal",
[this, node, ctx_mgr](const std::string& name,
const BT::NodeConfiguration& config)
{
Expand All @@ -82,6 +84,6 @@ void TransportAmrCapability::configure(
#include <pluginlib/class_list_macros.hpp>

PLUGINLIB_EXPORT_CLASS(
nexus::capabilities::TransportAmrCapability,
nexus::capabilities::RMFRequestCapability,
nexus::Capability
)
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
*
*/

#ifndef NEXUS_CAPABILITIES__CAPABILITIES__PLAN_MOTION_CAPABILITY_HPP
#define NEXUS_CAPABILITIES__CAPABILITIES__PLAN_MOTION_CAPABILITY_HPP
#ifndef NEXUS_CAPABILITIES__CAPABILITIES__RMF_REQUEST_CAPABILITY_HPP
#define NEXUS_CAPABILITIES__CAPABILITIES__RMF_REQUEST_CAPABILITY_HPP

#include <nexus_capabilities/capability.hpp>
#include <nexus_capabilities/context_manager.hpp>
Expand All @@ -33,7 +33,7 @@ namespace nexus::capabilities {
/**
* Capability to plan robot arm motions.
*/
class TransportAmrCapability : public Capability
class RMFRequestCapability : public Capability
{
/**
* @copydoc Capability::declare_params
Expand All @@ -58,9 +58,6 @@ public: void activate() final {}
* @copydoc Capability::deactivate
*/
public: void deactivate() final {}

private: rclcpp::Client<endpoints::GetMotionPlanService::ServiceType>::
SharedPtr _client;
};

}
Expand Down
16 changes: 8 additions & 8 deletions nexus_integration_tests/config/rmf_bts/transportation.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,23 +3,23 @@
<BehaviorTree ID="PickAndPlace">
<Sequence name="root_sequence">
<!-- Extract the destination information from the task payload -->
<transport_amr.ExtractDestinations destinations="{destinations}" />
<rmf_request.ExtractDestinations destinations="{destinations}" />
<!-- Sends the actual RMF task then returns -->
<transport_amr.DispatchRmfRequest destinations="{destinations}" rmf_task_id="{rmf_task_id}" />
<transport_amr.LoopDestinations queue="{destinations}" value="{destination}">
<rmf_request.DispatchRequest destinations="{destinations}" rmf_task_id="{rmf_task_id}" />
<rmf_request.LoopDestinations queue="{destinations}" value="{destination}">
<Sequence>
<!-- Utility node that unpacks the struct data into its fields -->
<transport_amr.UnpackDestinationData destination="{destination}" workcell="{workcell}" type="{type}" />
<rmf_request.UnpackDestinationData destination="{destination}" workcell="{workcell}" type="{type}" />
<!-- Wait for AMR to reach the workcell -->
<transport_amr.WaitForAmr rmf_task_id="{rmf_task_id}" workcell="{workcell}" />
<rmf_request.WaitForAmr rmf_task_id="{rmf_task_id}" workcell="{workcell}" />
<!-- Signal system orchestrator to start the workcell -->
<transport_amr.SendSignal signal="{workcell}" />
<rmf_request.SendSignal signal="{workcell}" />
<!-- Wait for workcell to be done with its task -->
<WaitForSignal signal="{workcell}" />
<!-- Signal RMF that we can move -->
<transport_amr.SignalAmr workcell="{workcell}" rmf_task_id="{rmf_task_id}" />
<rmf_request.SignalAmr workcell="{workcell}" rmf_task_id="{rmf_task_id}" />
</Sequence>
</transport_amr.LoopDestinations>
</rmf_request.LoopDestinations>
</Sequence>
</BehaviorTree>
</root>
2 changes: 1 addition & 1 deletion nexus_integration_tests/launch/control_center.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ def launch_setup(context, *args, **kwargs):
executable="nexus_workcell_orchestrator",
parameters=[
{
"capabilities": ["nexus::capabilities::TransportAmrCapability"],
"capabilities": ["nexus::capabilities::RMFRequestCapability"],
"bt_path": (FindPackageShare("nexus_integration_tests"), "/config/rmf_bts"),
}
],
Expand Down
1 change: 1 addition & 0 deletions nexus_integration_tests/launch/office.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
<!-- Simulator launch -->
<include if="$(var use_simulator)" file="$(find-pkg-share rmf_demos_gz)/simulation.launch.xml">
<arg name="headless" value="$(var headless)" />
<arg name="map_package" value="nexus_integration_tests" />
<arg name="map_name" value="office" />
<arg name="gazebo_version" value="8" />
<arg name="sim_update_rate" value="$(var sim_update_rate)"/>
Expand Down

0 comments on commit ead8808

Please sign in to comment.