Class Delivery

Nested Relationships

Nested Types

Class Documentation

class Delivery

A class that generates a Request which requires an AGV to pickup items from one location and deliver them to another

Public Static Functions

static ConstRequestPtr make(std::size_t pickup_waypoint, rmf_traffic::Duration pickup_wait, std::size_t dropoff_waypoint, rmf_traffic::Duration dropoff_wait, Payload payload, const std::string &id, rmf_traffic::Time earliest_start_time, ConstPriorityPtr priority = nullptr, bool automatic = false, std::string pickup_from_dispenser = "", std::string dropoff_to_ingestor = "")

Generate a delivery request

Parameters:
  • pickup_waypoint[in] The graph index for the pickup location

  • pickup_wait[in] The expected duration the AGV has to wait at the pickup location for the items to be loaded

  • dropoff_waypoint[in] The graph index for the dropoff location

  • dropoff_wait[in] The expected duration the AGV has to wait at the dropoff location for the items to be unloaded

  • id[in] A unique id for this request

  • earliest_start_time[in] The desired start time for this request

  • priority[in] The priority for this request

  • automatic[in] True if this request is auto-generated

static ConstRequestPtr make(std::size_t pickup_waypoint, rmf_traffic::Duration pickup_wait, std::size_t dropoff_waypoint, rmf_traffic::Duration dropoff_wait, Payload payload, const std::string &id, rmf_traffic::Time earliest_start_time, const std::string &requester, rmf_traffic::Time request_time, ConstPriorityPtr priority = nullptr, bool automatic = false, std::string pickup_from_dispenser = "", std::string dropoff_to_ingestor = "")

Generate a delivery request.

Parameters:
  • pickup_waypoint[in] The graph index for the pickup location.

  • pickup_wait[in] The expected duration the AGV has to wait at the pickup location for the items to be loaded.

  • dropoff_waypoint[in] The graph index for the dropoff location.

  • dropoff_wait[in] The expected duration the AGV has to wait at the dropoff location for the items to be unloaded.

  • id[in] A unique id for this request.

  • earliest_start_time[in] The desired start time for this request.

  • requester[in] The entity that issued this request.

  • request_time[in] The time this request was generated or submitted.

  • priority[in] The priority for this request.

  • automatic[in] True if this request is auto-generated, default value as false.

  • pickup_from_dispenser[in] The name of the dispenser to pick up the delivery item from, at the designated pickup waypoint. This field is optional.

  • dropoff_to_ingestor[in] The name of the ingestor to drop off the delivery item to, at the designated dropoff waypoint. This field is optional.

class Description : public rmf_task::Task::Description

Public Types

using Start = rmf_traffic::agv::Planner::Start

Public Functions

virtual Task::ConstModelPtr make_model(rmf_traffic::Time earliest_start_time, const Parameters &parameters) const final

Generate a Model for the task based on the unique traits of this description

Parameters:
  • earliest_start_time[in] The earliest time this task should begin execution. This is usually the requested start time for the task.

  • parameters[in] The parameters that describe this AGV

virtual Info generate_info(const State &initial_state, const Parameters &parameters) const final

Generate a plain text info description for the task, given the predicted initial state and the task planning parameters.

Parameters:
  • initial_state[in] The predicted initial state for the task

  • parameters[in] The task planning parameters

std::size_t pickup_waypoint() const

Get the pickup waypoint in this request.

std::string pickup_from_dispenser() const

Get the name of the dispenser that we’re picking up from.

rmf_traffic::Duration pickup_wait() const

Get the duration over which delivery items are loaded.

std::size_t dropoff_waypoint() const

Get the dropoff waypoint in this request.

std::string dropoff_to_ingestor() const

Get the name of the ingestor that we’re dropping off to.

rmf_traffic::Duration dropoff_wait() const

Get the duration over which delivery items are unloaded.

const Payload &payload() const

Get the payload that is being delivered.

Public Static Functions

static Task::ConstDescriptionPtr make(std::size_t pickup_waypoint, rmf_traffic::Duration pickup_duration, std::size_t dropoff_waypoint, rmf_traffic::Duration dropoff_duration, Payload payload, std::string pickup_from_dispenser = "", std::string dropoff_to_ingestor = "")

Generate the description for this request.