diff --git a/rmf_task/include/rmf_task/Request.hpp b/rmf_task/include/rmf_task/Request.hpp index 19a389176..e31cf5209 100644 --- a/rmf_task/include/rmf_task/Request.hpp +++ b/rmf_task/include/rmf_task/Request.hpp @@ -37,7 +37,7 @@ class Request using SharedPtr = std::shared_ptr; /// Get the id of the task - virtual std::size_t id() const = 0; + virtual std::string id() const = 0; /// Estimate the state of the robot when the task is finished along with the /// time the robot has to wait before commencing the task diff --git a/rmf_task/include/rmf_task/agv/TaskPlanner.hpp b/rmf_task/include/rmf_task/agv/TaskPlanner.hpp index 965727f37..f564ea259 100644 --- a/rmf_task/include/rmf_task/agv/TaskPlanner.hpp +++ b/rmf_task/include/rmf_task/agv/TaskPlanner.hpp @@ -125,7 +125,7 @@ class TaskPlanner rmf_task::RequestPtr request, State state, rmf_traffic::Time deployment_time); - + // Get the request of this task rmf_task::RequestPtr request() const; diff --git a/rmf_task/include/rmf_task/requests/ChargeBattery.hpp b/rmf_task/include/rmf_task/requests/ChargeBattery.hpp index 959cae7f6..0031e09c2 100644 --- a/rmf_task/include/rmf_task/requests/ChargeBattery.hpp +++ b/rmf_task/include/rmf_task/requests/ChargeBattery.hpp @@ -18,6 +18,8 @@ #ifndef INCLUDE__RMF_TASK__REQUESTS__CHARGEBATTERY_HPP #define INCLUDE__RMF_TASK__REQUESTS__CHARGEBATTERY_HPP +#include + #include #include @@ -46,7 +48,7 @@ class ChargeBattery : public rmf_task::Request rmf_traffic::Time start_time, bool drain_battery = true); - std::size_t id() const final; + std::string id() const final; rmf_utils::optional estimate_finish( const agv::State& initial_state, diff --git a/rmf_task/include/rmf_task/requests/Clean.hpp b/rmf_task/include/rmf_task/requests/Clean.hpp index 98d148e25..e8aa02c58 100644 --- a/rmf_task/include/rmf_task/requests/Clean.hpp +++ b/rmf_task/include/rmf_task/requests/Clean.hpp @@ -19,6 +19,7 @@ #define INCLUDE__RMF_TASK__REQUESTS__CLEAN_HPP #include +#include #include #include @@ -41,7 +42,7 @@ class Clean : public rmf_task::Request public: static rmf_task::Request::SharedPtr make( - std::size_t id, + std::string id, std::size_t start_waypoint, std::size_t end_waypoint, rmf_traffic::Trajectory& cleaning_path, @@ -52,7 +53,7 @@ class Clean : public rmf_task::Request rmf_traffic::Time start_time, bool drain_battery = true); - std::size_t id() const final; + std::string id() const final; rmf_utils::optional estimate_finish( const agv::State& initial_state, diff --git a/rmf_task/include/rmf_task/requests/Delivery.hpp b/rmf_task/include/rmf_task/requests/Delivery.hpp index 062840ed0..9a37702a5 100644 --- a/rmf_task/include/rmf_task/requests/Delivery.hpp +++ b/rmf_task/include/rmf_task/requests/Delivery.hpp @@ -19,6 +19,7 @@ #define INCLUDE__RMF_TASK__REQUESTS__DELIVERY_HPP #include +#include #include #include @@ -40,7 +41,7 @@ class Delivery : public rmf_task::Request public: static rmf_task::Request::SharedPtr make( - std::size_t id, + std::string id, std::size_t pickup_waypoint, std::size_t dropoff_waypoint, std::shared_ptr motion_sink, @@ -49,7 +50,7 @@ class Delivery : public rmf_task::Request rmf_traffic::Time start_time, bool drain_battery = true); - std::size_t id() const final; + std::string id() const final; rmf_utils::optional estimate_finish( const agv::State& initial_state, diff --git a/rmf_task/src/rmf_task/agv/TaskPlanner.cpp b/rmf_task/src/rmf_task/agv/TaskPlanner.cpp index b937ca52f..bb2964fa3 100644 --- a/rmf_task/src/rmf_task/agv/TaskPlanner.cpp +++ b/rmf_task/src/rmf_task/agv/TaskPlanner.cpp @@ -138,7 +138,7 @@ TaskPlanner::Assignment::Assignment( } //============================================================================== -rmf_task::RequestPtr TaskPlanner::Assignment::request() const +rmf_task::RequestPtr TaskPlanner::Assignment::request() const { return _pimpl->request; } @@ -194,10 +194,10 @@ class Candidates using Map = std::multimap; static Candidates make( - const std::vector& initial_states, - const std::vector& state_configs, - const rmf_task::Request& request, - const rmf_task::Request& charge_battery_request); + const std::vector& initial_states, + const std::vector& state_configs, + const rmf_task::Request& request, + const rmf_task::Request& charge_battery_request); Candidates(const Candidates& other) { @@ -283,10 +283,10 @@ class Candidates }; Candidates Candidates::make( - const std::vector& initial_states, - const std::vector& state_configs, - const rmf_task::Request& request, - const rmf_task::Request& charge_battery_request) + const std::vector& initial_states, + const std::vector& state_configs, + const rmf_task::Request& request, + const rmf_task::Request& charge_battery_request) { Map initial_map; for (std::size_t i = 0; i < initial_states.size(); ++i) @@ -329,7 +329,7 @@ Candidates Candidates::make( << "] and request [" << request.id() << " ]" << std::endl; assert(false); } - } + } } @@ -360,7 +360,13 @@ struct PendingTask // ============================================================================ struct Node { - using AssignedTasks = TaskPlanner::Assignments; + struct AssignmentWrapper + { + std::size_t internal_id; + TaskPlanner::Assignment assignment; + }; + + using AssignedTasks = std::vector>; using UnassignedTasks = std::unordered_map; using InvariantSet = std::multiset; @@ -370,6 +376,13 @@ struct Node double cost_estimate; rmf_traffic::Time latest_time; InvariantSet unassigned_invariants; + std::size_t next_available_internal_id = 1; + + // ID 0 is reserved for charging tasks + std::size_t get_available_internal_id(bool charging_task = false) + { + return charging_task ? 0 : next_available_internal_id++; + } void sort_invariants() { @@ -397,7 +410,7 @@ struct Node bool popped_invariant = false; InvariantSet::iterator erase_it; for (auto it = unassigned_invariants.begin(); - it != unassigned_invariants.end(); ++it) + it != unassigned_invariants.end(); ++it) { if (it->task_id == task_id) { @@ -535,7 +548,7 @@ class Filter { // We add 1 to the task_id to differentiate between task_id == 0 and // a task being unassigned. - const std::size_t id = s.request()->id() + 1; + const std::size_t id = s.internal_id + 1; output += id << (_shift * (count++)); } } @@ -564,8 +577,10 @@ class Filter for (std::size_t j=0; j < a.size(); ++j) { - if (a[j].request()->id() != b[j].request()->id()) + if (a[j].internal_id != b[j].internal_id) + { return false; + } } } @@ -601,7 +616,7 @@ bool Filter::ignore(const Node& node) if (t < current_agent.size()) { - const auto& task_id = current_agent[t].request()->id(); + const auto& task_id = current_agent[t].internal_id; const auto agent_insertion = agent_table->agent.insert({a, nullptr}); if (agent_insertion.second) agent_insertion.first->second = std::make_unique(); @@ -631,8 +646,19 @@ bool Filter::ignore(const Node& node) const rmf_traffic::Duration segmentation_threshold = rmf_traffic::time::from_seconds(1.0); -} // anonymous namespace +inline double compute_g_assignment(const TaskPlanner::Assignment& assignment) +{ + if (std::dynamic_pointer_cast( + assignment.request())) + { + return 0.0; // Ignore charging tasks in cost + } + return rmf_traffic::time::to_seconds(assignment.state().finish_time() + - assignment.request()->earliest_start_time()); +} + +} // anonymous namespace class TaskPlanner::Implementation { @@ -658,22 +684,15 @@ class TaskPlanner::Implementation { for (const auto& assignment : agent) { - if (std::dynamic_pointer_cast( - assignment.request())) - { - continue; // Ignore charging tasks in cost - } - - cost += - rmf_traffic::time::to_seconds( - assignment.state().finish_time() - assignment.request()->earliest_start_time()); + cost += compute_g_assignment(assignment); } } return cost; } - Assignments prune_assignments(Assignments& assignments) + TaskPlanner::Assignments prune_assignments( + TaskPlanner::Assignments& assignments) { for (std::size_t a = 0; a < assignments.size(); ++a) { @@ -684,7 +703,7 @@ class TaskPlanner::Implementation // TODO(YV): Remove this after fixing the planner if (std::dynamic_pointer_cast( assignments[a].back().request())) - assignments[a].pop_back(); + assignments[a].pop_back(); } return assignments; @@ -702,7 +721,7 @@ class TaskPlanner::Implementation auto node = make_initial_node(initial_states, state_configs, requests, time_now); - Node::AssignedTasks complete_assignments; + TaskPlanner::Assignments complete_assignments; complete_assignments.resize(node->assigned_tasks.size()); while (node) @@ -722,13 +741,14 @@ class TaskPlanner::Implementation const auto& new_assignments = node->assigned_tasks[i]; for (const auto& a : new_assignments) { - all_assignments.push_back(a); - // all_assignments.back().task_id = task_id_map.at(a.task_id); + all_assignments.push_back(a.assignment); } } if (node->unassigned_tasks.empty()) + { return prune_assignments(complete_assignments); + } std::vector new_tasks; for (const auto& u : node->unassigned_tasks) @@ -747,7 +767,7 @@ class TaskPlanner::Implementation if (assignments.empty()) estimates[i] = initial_states[i]; else - estimates[i] = assignments.back().state(); + estimates[i] = assignments.back().assignment.state(); } node = make_initial_node(estimates, state_configs, new_tasks, time_now); @@ -759,7 +779,15 @@ class TaskPlanner::Implementation double compute_g(const Node& node) { - return compute_g(node.assigned_tasks); + double cost = 0.0; + for (const auto& agent : node.assigned_tasks) + { + for (const auto& assignment : agent) + { + cost += compute_g_assignment(assignment.assignment); + } + } + return cost; } double compute_h(const Node& node, const rmf_traffic::Time time_now) @@ -799,7 +827,7 @@ class TaskPlanner::Implementation value = rmf_traffic::time::to_seconds(time_now.time_since_epoch()); else value = rmf_traffic::time::to_seconds( - assignments.back().state().finish_time().time_since_epoch()); + assignments.back().assignment.state().finish_time().time_since_epoch()); } } @@ -833,11 +861,16 @@ class TaskPlanner::Implementation // TODO(YV): Come up with a better solution for charge_battery_request auto charge_battery = make_charging_request(time_now); for (const auto& request : requests) + { + // Generate a unique internal id for the request. Currently, multiple + // requests with the same string id will be assigned different internal ids + std::size_t internal_id = initial_node->get_available_internal_id(); initial_node->unassigned_tasks.insert( { - request->id(), + internal_id, PendingTask(initial_states, state_configs, request, charge_battery) }); + } initial_node->cost_estimate = compute_f(*initial_node, time_now); @@ -881,7 +914,7 @@ class TaskPlanner::Implementation if (a.empty()) continue; - const auto finish_time = a.back().state().finish_time(); + const auto finish_time = a.back().assignment.state().finish_time(); if (latest < finish_time) latest = finish_time; } @@ -917,24 +950,29 @@ class TaskPlanner::Implementation // Check if a battery task already precedes the latest assignment auto& assignments = new_node->assigned_tasks[entry.candidate]; if (assignments.empty() || !std::dynamic_pointer_cast( - assignments.back().request())) + assignments.back().assignment.request())) { auto charge_battery = make_charging_request(entry.previous_state.finish_time()); auto battery_estimate = charge_battery->estimate_finish(entry.previous_state, state_config); if (battery_estimate.has_value()) { assignments.push_back( - Assignment - { - charge_battery, - battery_estimate.value().finish_state(), - battery_estimate.value().wait_until() - }); - } + Node::AssignmentWrapper + { u.first, + Assignment + { + charge_battery, + battery_estimate.value().finish_state(), + battery_estimate.value().wait_until() + } + } + ); + } } } new_node->assigned_tasks[entry.candidate].push_back( - Assignment{u.second.request, entry.state, entry.wait_until}); + Node::AssignmentWrapper{u.first, + Assignment{u.second.request, entry.state, entry.wait_until}}); // Erase the assigned task from unassigned tasks new_node->pop_unassigned(u.first); @@ -991,12 +1029,13 @@ class TaskPlanner::Implementation if (battery_estimate.has_value()) { new_node->assigned_tasks[entry.candidate].push_back( - Assignment - { - charge_battery, - battery_estimate.value().finish_state(), - battery_estimate.value().wait_until() - }); + { new_node->get_available_internal_id(true), + Assignment + { + charge_battery, + battery_estimate.value().finish_state(), + battery_estimate.value().wait_until() + }}); for (auto& new_u : new_node->unassigned_tasks) { const auto finish = @@ -1050,9 +1089,9 @@ class TaskPlanner::Implementation if (!assignments.empty()) { if (std::dynamic_pointer_cast( - assignments.back().request())) + assignments.back().assignment.request())) return nullptr; - state = assignments.back().state(); + state = assignments.back().assignment.state(); } auto charge_battery = make_charging_request(state.finish_time()); @@ -1061,11 +1100,16 @@ class TaskPlanner::Implementation if (estimate.has_value()) { new_node->assigned_tasks[agent].push_back( - Assignment{ - charge_battery, - estimate.value().finish_state(), - estimate.value().wait_until()}); - + Node::AssignmentWrapper + { + new_node->get_available_internal_id(true), + Assignment + { + charge_battery, + estimate.value().finish_state(), + estimate.value().wait_until() + } + }); for (auto& new_u : new_node->unassigned_tasks) { const auto finish = diff --git a/rmf_task/src/rmf_task/requests/ChargeBattery.cpp b/rmf_task/src/rmf_task/requests/ChargeBattery.cpp index fa8fdb680..0df6dac0d 100644 --- a/rmf_task/src/rmf_task/requests/ChargeBattery.cpp +++ b/rmf_task/src/rmf_task/requests/ChargeBattery.cpp @@ -15,6 +15,7 @@ * */ +#include #include namespace rmf_task { @@ -29,7 +30,7 @@ class ChargeBattery::Implementation {} // fixed id for now - std::size_t _id = 1001; + std::string _id = "Charge"; rmf_battery::agv::BatterySystemPtr _battery_system; std::shared_ptr _motion_sink; std::shared_ptr _device_sink; @@ -75,7 +76,7 @@ ChargeBattery::ChargeBattery() {} //============================================================================== -std::size_t ChargeBattery::id() const +std::string ChargeBattery::id() const { return _pimpl->_id; } diff --git a/rmf_task/src/rmf_task/requests/Clean.cpp b/rmf_task/src/rmf_task/requests/Clean.cpp index 931e53f49..d4e27fe3b 100644 --- a/rmf_task/src/rmf_task/requests/Clean.cpp +++ b/rmf_task/src/rmf_task/requests/Clean.cpp @@ -30,7 +30,7 @@ class Clean::Implementation Implementation() {} - std::size_t id; + std::string id; std::size_t start_waypoint; std::size_t end_waypoint; rmf_traffic::Trajectory cleaning_path; @@ -47,7 +47,7 @@ class Clean::Implementation //============================================================================== rmf_task::Request::SharedPtr Clean::make( - std::size_t id, + std::string id, std::size_t start_waypoint, std::size_t end_waypoint, rmf_traffic::Trajectory& cleaning_path, @@ -102,7 +102,7 @@ Clean::Clean() {} //============================================================================== -std::size_t Clean::id() const +std::string Clean::id() const { return _pimpl->id; } diff --git a/rmf_task/src/rmf_task/requests/Delivery.cpp b/rmf_task/src/rmf_task/requests/Delivery.cpp index 980b3160e..6c525ed1f 100644 --- a/rmf_task/src/rmf_task/requests/Delivery.cpp +++ b/rmf_task/src/rmf_task/requests/Delivery.cpp @@ -30,7 +30,7 @@ class Delivery::Implementation Implementation() {} - std::size_t _id; + std::string _id; std::size_t _pickup_waypoint; std::size_t _dropoff_waypoint; std::shared_ptr _motion_sink; @@ -45,7 +45,7 @@ class Delivery::Implementation //============================================================================== rmf_task::Request::SharedPtr Delivery::make( - std::size_t id, + std::string id, std::size_t pickup_waypoint, std::size_t dropoff_waypoint, std::shared_ptr motion_sink, @@ -100,7 +100,7 @@ Delivery::Delivery() {} //============================================================================== -std::size_t Delivery::id() const +std::string Delivery::id() const { return _pimpl->_id; } diff --git a/rmf_task/test/unit/agv/test_TaskPlanner.cpp b/rmf_task/test/unit/agv/test_TaskPlanner.cpp index 1ff21bd7b..d00b5bc65 100644 --- a/rmf_task/test/unit/agv/test_TaskPlanner.cpp +++ b/rmf_task/test/unit/agv/test_TaskPlanner.cpp @@ -185,7 +185,7 @@ SCENARIO("Grid World") std::vector requests = { rmf_task::requests::Delivery::make( - 1, + "1", 0, 3, motion_sink, @@ -195,7 +195,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 2, + "2", 15, 2, motion_sink, @@ -205,7 +205,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 3, + "3", 7, 9, motion_sink, @@ -260,7 +260,7 @@ SCENARIO("Grid World") std::vector requests = { rmf_task::requests::Delivery::make( - 1, + "1", 0, 3, motion_sink, @@ -270,7 +270,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 2, + "2", 15, 2, motion_sink, @@ -280,7 +280,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 3, + "3", 7, 9, motion_sink, @@ -290,7 +290,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 4, + "4", 8, 11, motion_sink, @@ -300,7 +300,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 5, + "5", 10, 0, motion_sink, @@ -310,7 +310,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 6, + "6", 4, 8, motion_sink, @@ -320,7 +320,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 7, + "7", 8, 14, motion_sink, @@ -330,7 +330,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 8, + "8", 5, 11, motion_sink, @@ -340,7 +340,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 9, + "9", 9, 0, motion_sink, @@ -350,7 +350,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 10, + "10", 1, 3, motion_sink, @@ -360,7 +360,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 11, + "11", 0, 12, motion_sink, @@ -416,7 +416,7 @@ SCENARIO("Grid World") std::vector requests = { rmf_task::requests::Delivery::make( - 1, + "1", 0, 3, motion_sink, @@ -426,7 +426,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 2, + "2", 15, 2, motion_sink, @@ -436,7 +436,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 3, + "3", 9, 4, motion_sink, @@ -446,7 +446,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 4, + "4", 8, 11, motion_sink, @@ -511,7 +511,7 @@ SCENARIO("Grid World") std::vector requests = { rmf_task::requests::Delivery::make( - 1, + "1", 6, 3, motion_sink, @@ -521,7 +521,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 2, + "2", 10, 7, motion_sink, @@ -531,7 +531,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 3, + "3", 2, 12, motion_sink, @@ -541,7 +541,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 4, + "4", 8, 11, motion_sink, @@ -551,7 +551,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 5, + "5", 10, 6, motion_sink, @@ -561,7 +561,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 6, + "6", 2, 9, motion_sink, @@ -571,7 +571,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 7, + "7", 3, 4, motion_sink, @@ -581,7 +581,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 8, + "8", 5, 11, motion_sink, @@ -591,7 +591,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 9, + "9", 9, 1, motion_sink, @@ -601,7 +601,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 10, + "10", 1, 5, motion_sink, @@ -611,7 +611,7 @@ SCENARIO("Grid World") drain_battery), rmf_task::requests::Delivery::make( - 11, + "11", 13, 10, motion_sink,