Skip to content
This repository was archived by the owner on Jul 22, 2021. It is now read-only.
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion rmf_task/include/rmf_task/Request.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class Request
using SharedPtr = std::shared_ptr<Request>;

/// 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
Expand Down
2 changes: 1 addition & 1 deletion rmf_task/include/rmf_task/agv/TaskPlanner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
4 changes: 3 additions & 1 deletion rmf_task/include/rmf_task/requests/ChargeBattery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#ifndef INCLUDE__RMF_TASK__REQUESTS__CHARGEBATTERY_HPP
#define INCLUDE__RMF_TASK__REQUESTS__CHARGEBATTERY_HPP

#include <string>

#include <rmf_traffic/Time.hpp>
#include <rmf_traffic/agv/Planner.hpp>

Expand Down Expand Up @@ -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<rmf_task::Estimate> estimate_finish(
const agv::State& initial_state,
Expand Down
5 changes: 3 additions & 2 deletions rmf_task/include/rmf_task/requests/Clean.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#define INCLUDE__RMF_TASK__REQUESTS__CLEAN_HPP

#include <chrono>
#include <string>

#include <rmf_traffic/Time.hpp>
#include <rmf_traffic/Trajectory.hpp>
Expand All @@ -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,
Expand All @@ -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<rmf_task::Estimate> estimate_finish(
const agv::State& initial_state,
Expand Down
5 changes: 3 additions & 2 deletions rmf_task/include/rmf_task/requests/Delivery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#define INCLUDE__RMF_TASK__REQUESTS__DELIVERY_HPP

#include <chrono>
#include <string>

#include <rmf_traffic/Time.hpp>
#include <rmf_traffic/agv/Planner.hpp>
Expand All @@ -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<rmf_battery::MotionPowerSink> motion_sink,
Expand All @@ -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<rmf_task::Estimate> estimate_finish(
const agv::State& initial_state,
Expand Down
Loading