Skip to content

Commit

Permalink
AmrDestination -> Destination
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 ead8808 commit 18070e6
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 14 deletions.
12 changes: 6 additions & 6 deletions nexus_capabilities/src/capabilities/rmf_request.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ namespace rmf {

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

void DispatchRequest::submit_itinerary(const std::deque<AmrDestination>& destinations)
void DispatchRequest::submit_itinerary(const std::deque<Destination>& destinations)
{
nlohmann::json j;
j["type"] = "dispatch_task_request";
Expand Down Expand Up @@ -135,14 +135,14 @@ BT::NodeStatus ExtractDestinations::tick()
{
const auto ctx = this->_ctx_mgr->current_context();
const auto& task = ctx->task;
std::deque<AmrDestination> destinations;
std::deque<Destination> destinations;
for (const auto& node : task.data)
{
if (node["type"] && node["destination"])
{
auto type = node["type"].as<std::string>();
auto destination = node["destination"].as<std::string>();
destinations.push_back(AmrDestination {type, destination});
destinations.push_back(Destination {type, destination});
}
else
{
Expand All @@ -158,7 +158,7 @@ BT::NodeStatus ExtractDestinations::tick()

BT::NodeStatus UnpackDestinationData::tick()
{
const auto destination = this->getInput<AmrDestination>("destination");
const auto destination = this->getInput<Destination>("destination");
if (!destination)
{
RCLCPP_ERROR(
Expand Down Expand Up @@ -203,7 +203,7 @@ BT::NodeStatus LoopDestinations::tick()
{
if (!this->_initialized)
{
auto queue = this->getInput<std::deque<AmrDestination>>("queue");
auto queue = this->getInput<std::deque<Destination>>("queue");
if (!queue)
{
RCLCPP_ERROR(
Expand Down
16 changes: 8 additions & 8 deletions nexus_capabilities/src/capabilities/rmf_request.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ namespace nexus::capabilities {

namespace rmf {

struct AmrDestination {
struct Destination {
// Either "pickup" or "dropoff"
std::string action;
std::string workcell;
Expand All @@ -58,7 +58,7 @@ public: using ApiResponse = rmf_task_msgs::msg::ApiResponse;

public: static BT::PortsList providedPorts()
{
return { BT::InputPort<std::deque<AmrDestination>>("destinations", "Destinations to visit"),
return { BT::InputPort<std::deque<Destination>>("destinations", "Destinations to visit"),
BT::OutputPort<std::string>("rmf_task_id", "The resulting RMF task id")
};
}
Expand All @@ -74,7 +74,7 @@ public: BT::NodeStatus onRunning() override;

public: void onHalted() override {}

private: void submit_itinerary(const std::deque<AmrDestination>& destinations);
private: void submit_itinerary(const std::deque<Destination>& destinations);

private: void api_response_cb(const ApiResponse& msg);

Expand All @@ -94,7 +94,7 @@ class ExtractDestinations : public BT::SyncActionNode
public: static BT::PortsList providedPorts()
{
return {
BT::OutputPort<std::deque<AmrDestination>>("destinations"),
BT::OutputPort<std::deque<Destination>>("destinations"),
};
}

Expand All @@ -115,7 +115,7 @@ class UnpackDestinationData : public BT::SyncActionNode
public: static BT::PortsList providedPorts()
{
return {
BT::InputPort<AmrDestination>("destination"),
BT::InputPort<Destination>("destination"),
BT::OutputPort<std::string>("workcell"),
BT::OutputPort<std::string>("type"),
};
Expand Down Expand Up @@ -165,8 +165,8 @@ class LoopDestinations : public BT::DecoratorNode
public: static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::deque<AmrDestination>>("queue"),
BT::OutputPort<AmrDestination>("value"),
BT::InputPort<std::deque<Destination>>("queue"),
BT::OutputPort<Destination>("value"),
};
}

Expand All @@ -183,7 +183,7 @@ public: BT::NodeStatus tick() override;

private: rclcpp_lifecycle::LifecycleNode::SharedPtr _node;
private: bool _initialized = false;
private: std::deque<AmrDestination> _queue;
private: std::deque<Destination> _queue;
};

class WaitForAmr: public BT::StatefulActionNode
Expand Down

0 comments on commit 18070e6

Please sign in to comment.