Class LPScheduler

Nested Relationships

Nested Types

Class Documentation

class LPScheduler

Public Functions

LPScheduler(const MinimalState &s, list<FFEvent> &header, list<FFEvent> &now, const int &justAppliedStep, list<StartEvent> &seq, ParentData *parentData, map<int, list<list<StartEvent>::iterator>> &compulsaryEnds, const vector<double> *prevStateMin, const vector<double> *prevStateMax, list<int> *tilComesBefore, const bool &setObjectiveToMetric)
LPScheduler(const MinimalState &s, list<FFEvent> &plan)
~LPScheduler()
inline const bool &isSolved() const
void updateStateFluents(vector<double> &min, vector<double> &max)

Update the bounds on the task variables in the state reached by the plan so far.

Assuming the plan passed to the constructor led to an LP that could be solved (i.e. isSolved() = true), then this function can be used to calculate the upper and lower bounds of the task variables in a state after the actions in the plan so far. Note that only the bounds of time-dependent variables are actually updated, so it is important that for all other variables, the bounds passed as input to the function are correct.

Parameters:
  • min – The vector containing the lower bounds to be updated

  • max – The vector containing the upper bounds to be updated

bool addRelaxedPlan(list<FFEvent> &header, list<FFEvent> &now, list<pair<double, list<ActionSegment>>> &relaxedPlan)
bool isSolution(const MinimalState &state, list<FFEvent> &header, list<FFEvent> &now)

Public Static Functions

static inline bool isBoring(const int &a, const int &s, const bool &includeMetric)

Ascertain whether a given snap-action introduces time-dependent effects or preconditions.

Parameters:
  • a – The index of the action

  • s0 for the start of the action, 1 for the end

  • includeMetric – If true, then effects on metric-tracking variables are considered cause for a snap-action not to be boring.

Returns:

true if the specified snap-action introduces time-dependent effects or preconditions.

static ParentData *prime(list<FFEvent> &header, const TemporalConstraints *const cons, list<StartEvent> &open, const bool includeMetric = false)

Function to support the incremental Bellman Ford algorithm. It creates an object representing the the temporal constraints (both action sequencing constraints, and duration constraints) relevant to the current plan header, and the list of actions that have started but not yet finished. Functions on this object can then be used to incrementally check the consistency of these temporal constraints when a new action is applied.

See also

ParentData, ChildData

Parameters:
  • header – The plan header for which to create the temporal constraint data.

  • cons – The temporal separation constraints between the steps in the plan.

  • open – The list of actions that have started, but not yet finished, following the supplied plan.

  • includeMetric – If true, effects on metric-tracking variables are considered when determining whether the steps in header necessitate the the use of an LP.

Returns:

An object capturing all the temporal constraints on the plan header.

static void initialise()
static inline const double &getTILTimestamp(const int &i)

Public Static Attributes

static bool hybridBFLP
static bool optimiseOrdering
static int lpDebug

Protected Types

typedef set<const Constraint*, ConstraintPtrLT> ConstraintSet

Protected Functions

int generateEndDetails(const VAL::time_spec &currTS, const int &actID, const int &stepID, FFEvent &currEvent, const vector<FFEvent*> &planAsAVector, int &nextImaginaryEndVar, vector<EndDetails> &imaginaryMinMax)
void addConstraintsToGetValuesOfVariablesNow(InterestingMap &currInterest, const int &stepID, const int &currVar, map<int, int> &beforeStep)
void addConstraintsForTILMutexes(const int &timestampVar, const vector<double> &mutexTimestamps)

Add constraints to the LP to enforce that the given variable cannot take a value equal to any of the specified timestamps (excluding those that are known to be outwith the variables permissible bounds)

Parameters:
  • timestampVar – The timestamp variable in the LP to constrain

  • mutexTimestamps – A vector of times whose values the given variable cannot take

bool addAnyNumericConstraints(const list<pair<int, VAL::time_spec>> &numericConditions, const int &actStartAt, const int &actEndAt, list<int> &conditionVars)

Add constraints to the LP to determine whether a list of conditional effect conditions are satisfied.

Parameters:
  • numericConditions – The numeric conditions to satisfy, each a pair:

    • the first element is an index into RPGBuilder::getNumericPreTable()

    • the second element, a VAL::time_spec, dictates when it has to be satisfied: VAL::E_AT_START, VAL::E_OVER_ALL, or VAL::E_AT_END.

  • actStartAt – The LP variable denoting the start of the action from which the conditions are taken

  • actEndAt – The LP variable denoting the end of the action from which the conditions are taken (or -1 if the action is non-temporal)

  • conditionVars – The LP columns created (one for each entry in propositionConditions) are added to this list.

Returns:

true if the conditions can possibly be satisfied, false otherwise.

bool addAnyTimeWindowConstraints(const list<pair<Literal*, VAL::time_spec>> &propositionalConditions, const int &actStartAt, const int &actEndAt, list<int> &conditionVars)

Add constraints to the LP to determine whether a list of conditional effect conditions are satisfied by the TILs.

Parameters:
  • propositionalConditions – The propositional conditions to satisfy, each a pair:

    • the first element, a Literal*, dictates which proposition to satisfy

    • the second element, a VAL::time_spec, dictates when it has to be satisfied: VAL::E_AT_START, VAL::E_OVER_ALL, or VAL::E_AT_END.

  • actStartAt – The LP variable denoting the start of the action from which the conditions are taken

  • actEndAt – The LP variable denoting the end of the action from which the conditions are taken (or -1 if the action is non-temporal)

  • conditionVars – The LP columns created (one for each entry in propositionConditions) are added to this list.

Returns:

true if the conditions can possibly be satisfied, false otherwise.

bool scheduleToMetric()

Set the objective function of the LP to minimise the metric stated in the problem file.

Returns:

false if the new objective was quadratic and led to an unsolvable problem

void pushTimestampToMin()

Set the lower bound on the most recent timestamp in the plan to its current timestamp.

When a step is added to the plan, the LP is solved, minimising the timestamp of that step. Thus, the timestamp obtained is a lower bound on the timestamp it can have in any state reached from there onwards. Furthermore, if the step is the start/end of a durative action we can (potentially) refine the lower bound on the timestamp of the corresponding start/end.

Protected Attributes

int tsVarCount
ChildData *cd
MILPSolver *lp
int timestampToUpdateVar

The LP variable denoting the time of the most recent step in the plan.

int timestampToUpdateStep

The index, within the plan, of the most recent step.

FFEvent *timestampToUpdate

The FFEvent representing the most recent step in the plan.

int timestampToUpdatePartnerVar

The LP variable denoting the start/end action paired with the most recent step in the plan.

If no such action exists (i.e. the most recent step is for a non-temporal action or a timed initial literal), this variable takes the value -1.

int timestampToUpdatePartnerStep

The index, within the plan, of the step paired with the most recent step.

If no such action exists (i.e. the most recent step is for a non-temporal action or a timed initial literal), this variable takes the value -1.

FFEvent *timestampToUpdatePartner

The FFEvent representing the plan step paired with the most recent step.

If no such action exists (i.e. the most recent step is for a non-temporal action or a timed initial literal), this variable takes the value 0.

int previousObjectiveVar

The variable last used as the objective of the LP.

This variable is used to facilitate changing the objective function of the LP. As the objective only features a single variable, the prodedure for changing objectives is as follows:

  • Set the objective coefficient of this variable to 0

  • Set this variable to the new variable to optimise

  • Set the objective coefficient of this variable to 1

If no objective has yet been given to the LP, this variable takes the value -1.

vector<int> timestampVars

The LP variables containing the timestamps of the corresponding plan steps.

vector<FluentTracking> finalNumericVars

Information about how the task numeric variables are represented in the LP.

Each entry in the vector corresponds to a variable in RPGBuilder::pnes. As the LP is constructed, iterating through the plan steps, the entries in this vector are modified according to the effects of the actions.

list<int> endsOfThreads

LP variables for the timestamps of actions with no successors.

This list contains the variables in the LP representing the plan steps with no successors. When minimising the makespan of the solution, the objective is set to minimise a variable whose value must exceed each of these.

double makespanVarMinimum

Lower-bound on the makespan of the plan.

This is determined during LP construction, as the maximum timestamp lower bound across all steps in the plan.

vector<bool> stableVariable

A record of whether a variable has only ever been subject to non-time-dependent effects

Each entry in the vector corresponds to a variable in RPGBuilder::pnes. If the value corresponding to a given variable is false, then the value of the variable is not stable. This happens if either:

  • it has been subjected to continuous/duration-dependent change; or,

  • it has been subjected to discrete change, the value of which depended on a non-stable variable.

The distinction is made for efficiency: the bounds on variables’ values only needs to be computed for non-stable variables, as no other variables are time-dependent (and hence need the LP).

bool solved

Whether the LP representing the plan could be solved.

bool nameLPElements

Whether LP elements should be named.

This is an internal flag for debugging. If set to true, i.e. if LPScheduler::lpDebug is non-zero, the rows and columns of the LP are given meaningful names, rather than the defaults. As naming the elements carries a small overhead, and serves no purpose other than making the resulting LP easier for humans to comprehend, the variable takes a value of false unless LP debugging output is enabled.

bool includeMetricTrackingVariables

Whether to include metric tracking variables in the LP.

By default, this is set to false, i.e. metric tracking variables are excluded from the LP, leading to smaller models. However, if the plan is to be post-hoc scheduled to the metric, this is set to true, as the values of such variables need to be computed for subsequent optimisation.

bool assertions

If true, a number of expensive assertions are enabled.

map<int, list<EndDetails>> openDurationConstraints
vector<FFEvent*> planAsAVector

Protected Static Functions

static const Constraint *buildConstraint(RPGBuilder::RPGNumericPrecondition &d)
static void collateRelevantVariablesAndInvariants(InterestingMap &currInterest, CountedConstraintSet &activeInvariants, const int &stepID, const VAL::time_spec &currTS, const int &actID, vector<set<int>> &activeAncestorsOfStep, vector<map<int, ConstraintSet>> &invariantsThisStepStartsOnVariableI)
static void recordVariablesInvolvedInThisStepsInvariants(const list<const Constraint*> &invariants, map<int, ConstraintSet> &invariantsOnVariableI)

Record dependencies between numeric variables and the invariants given.

When building the LP, we need to know which active invariants depend on a given variable so that, if the value of the variable changes, the relevant invariants can be imposed upon the new value.

Parameters:
  • invariants – The invariants started at a given step

  • invariantsOnVariableI – Where the output from the function: for each variable index, the constraints that depend on it.

Protected Static Attributes

static double *weightScratch
static int *varScratch
static bool scratchInit
static vector<double> TILtimestamps

The timestamps of each timed initial literal, in order.

static vector<vector<list<pair<int, RPGBuilder::LinearEffects::EffectExpression>>>> gradientEffects

The gradient effects for each action. At present, the vector contains a single entry, defining the linear continuous effects that occur across the execution of the action. This may change if piecewise linear effects are introduced.

static vector<vector<list<RPGBuilder::RPGNumericEffect*>>> instantEffects

The instantaneous numeric effects of each action. Each entry is itself a vector:

  • instantEffects[a][0] contains the instantaneous numeric effects for the start of action a

  • instantEffects[a][1] contains the instantaneous numeric effects for the end of action a

static vector<vector<list<const Constraint*>>> constraints

The preconditions of the each action. Each entry is itself a vector:

  • constraints[a][0] contains the conditions that must hold at the start of action a

  • constraints[a][1] contains the conditions that must hold throughout the execution of action a

  • constraints[a][2] contains the conditions that must hold at the end of action a

static vector<vector<InterestingMap>> interesting

The numeric variables relevant to each point of each action. Each entry is a vector of size 3, where:

  • interesting[a][0] defines the variables relevant to the start of action a

  • interesting[a][1] defines the variables relevant to the invariants of action a

  • interesting[a][2] defines the variables relevant to the end of action a

In all cases, if the boolean value paired with a variable is true, the action will have an effect on the variable. Otherwise, it only requires to inspect its value (for a precondition).

static vector<vector<vector<double>>> pointsThatWouldBeMutexWithOptimisationTILs

If an action has a conditional effect on a metric-tracking variable, where that condition depends on a fact controlled by optimisation TILs (TILs relevant only to such conditional effects), then the mutexes between the action’s start/end and the TILs must be respected. Thus, for each conditional effect of an action a:

  • if it has a condition (at (start (fact))) then the start point of a cannot coincide with any TIL deleting (fact)

  • if it has a condition (at (end (fact))) then the end point of a cannot coincide with any TIL deleting (fact)

This vector contains the list of incompatible time points for each action, according to the optimisation TILs. Each entry is a vector of size 2, where:

  • pointsThatWouldBeMutexWithOptimisationTILs[a][0] contains the time points mutex with the start of action a

  • pointsThatWouldBeMutexWithOptimisationTILs[a][1] contains the time points mutex with the end of action a

static vector<vector<pair<bool, bool>>> boringAct

Whether the effects of an action are ‘boring’, i.e. it does not introduce duration-dependent or continuous effects. Each entry is a vector:

  • boringAct[a][0] is a pair:

    • boringAct[a][0].first is false if the start of the action introduces time-dependent change, in the case where metric tracking variables are ignored.

    • boringAct[a][0].second is false if the start of the action introduces time-dependent change, in the case where metric tracking variables are included.

  • boringAct[a][1] is a pair, defined similarly, for the end of the action.

static vector<double> initialValues

The values of each variable in the initial state

static list<const Constraint*> goalConstraints

The constraints that must hold in the goal state

static int numVars
static bool initialised

Friends

friend struct ConstraintAdder
friend struct DurationAdder
class Constraint

Public Functions

inline Constraint()
inline bool operator<(const Constraint &c) const

Public Members

vector<double> weights
vector<int> variables
double lower
double upper

Public Static Functions

static inline const Constraint *requestConstraint(const Constraint &c)

Protected Attributes

mutable int ID

Protected Static Attributes

static set<Constraint> constraintStore
static int constraintCount

Friends

friend class ConstraintPtrLT
struct ConstraintPtrLT

Public Functions

inline bool operator()(const Constraint *const a, const Constraint *const b) const
class CountedConstraintSet : public std::map<const Constraint*, unsigned int, ConstraintPtrLT>

Public Types

typedef map<const Constraint*, unsigned int, ConstraintPtrLT> __super
typedef __super::iterator iterator

Public Functions

void insert(const Constraint *const c)
void erase(const Constraint *const c)
void insert(const ConstraintSet &c)
void erase(const ConstraintSet &c)
inline iterator begin()
inline iterator end()
template<class _InputIterator>
inline void insert(_InputIterator itr, const _InputIterator &itrEnd)
template<class _InputIterator>
inline void erase(_InputIterator itr, const _InputIterator &itrEnd)
struct EndDetails

Public Functions

inline EndDetails(const int &min, const int &max, const int &cons)
inline EndDetails()

Public Members

list<StartEvent>::iterator first
int imaginaryMin
int imaginaryMax
int lastToMin
class FluentTracking

A class to track the changes on a task numeric variable as the LP is built for the plan so far.

Public Types

enum fluent_status

An enum defining three states a numeric variable can be in when building the LP:

  • FS_NORMAL denotes that the variable should be treated normally, with effects and preconditions on the variable being included in the LP.

  • FS_IGNORE denotes that the variable is a metric tracking variable, to be ignored (i.e. effects on it should be omitted from the LP)

  • FS_ORDER_INDEPENDENT denotes that the variable is an order-independent metric-tracking variable, and effects on it are to update the variables FluentTracking::orderIndependentValueTerms and FluentTracking::orderIndependentValueConstant, for eventual inclusion into the objective function.

Values:

enumerator FS_NORMAL
enumerator FS_IGNORE
enumerator FS_ORDER_INDEPENDENT

Public Functions

inline FluentTracking(const double &initial)

Initial constructor: the variable takes the given value (that from the initial state), its status is set to FS_NORMAL, and no continuous numeric change is active.

Parameters:

initial – The value of the fluent in the initial state.

inline FluentTracking()

Default constructor (unfortunately needed to be able to create a vector of FluentTracking objects).

Public Members

fluent_status statusOfThisFluent

The status of this fluent. For metric-tracking variables, this is set to either FS_IGNORE or FS_ORDER_INDEPENDENT in the LPScheduler constructor, depending on whether the plan is to be scheduled to the metric. For all other variables, this is set to FS_NORMAL.

double postLastEffectValue

The value of the variable following the last effect. This is only defined if FluentTracking::lastEffectValueVariable = -1.

int lastEffectValueVariable

The LP variable (column) containing the value of the variable following the last effect to act upon it. If this takes the value -1, then the value is a constant, not an LP variable, stored in FluentTracking::postLastEffectValue.

int lastEffectTimestampVariable

The timestamp variable of the last action with an effect upon this variable. If this takes the value -1, then no such action exists (i.e. there have been no effects on the variable so far).

double activeGradient

The gradient of the active continuous numeric change acting upon the variable.

int activeGradientCount

How many actions are having a continuous numeric effect upon the variable. This is used to prevent rounding errors: if this value takes the value 0, then FluentTracking::activeGradient is assigned the value 0.

map<int, double> orderIndependentValueTerms

For metric-traking variables with order-independent effects, this map contains column&#8212;weight pairs that contribute to its value.

double orderIndependentValueConstant

For metric-tracking variables with order-independent effects, the sum of this constant value and the weighted sum of the LP columns given in FluentTracking::orderIndependentValueTerms give the value of the variable at the end of the plan.

class InterestingMap : private std::map<int, bool>

Public Types

typedef map<int, bool> __super
typedef __super::iterator iterator
typedef __super::const_iterator const_iterator

Public Functions

inline iterator begin()
inline const_iterator begin() const
inline iterator end()
inline const_iterator end() const
inline const_iterator find(const int &i) const
inline iterator find(const int &i)
inline void erase(const int &i)
inline void erase(const iterator &i)
inline InterestingMap()
inline InterestingMap(const InterestingMap &other)
inline InterestingMap(const map<int, bool> &in)
inline InterestingMap &operator=(const __super &in)
template<class _InputIterator>
inline void insertKeepingTrues(_InputIterator srcItr, const _InputIterator &srcEnd)
virtual void insertKeepingTrues(const pair<int, bool> &toInsert)
inline virtual void insertEffect(const int &i)
inline virtual void insertPrecondition(const int &i)
template<class _InputIterator>
inline void insertPreconditions(_InputIterator itr, const _InputIterator &itrEnd)
template<class _InputIterator>
inline void insertEffects(_InputIterator itr, const _InputIterator &itrEnd)