Class RPGBuilder

Nested Relationships

Nested Types

Class Documentation

class RPGBuilder

Public Types

enum math_op

Values:

enumerator NE_ADD
enumerator NE_SUBTRACT
enumerator NE_MULTIPLY
enumerator NE_DIVIDE
enumerator NE_CONSTANT
enumerator NE_FLUENT
enumerator NE_VIOLATION

Public Static Functions

static double calculateRHS(const list<Operand> &formula, vector<double> &fluents)
static pair<double, bool> constRHS(const list<Operand> &formula)
static inline bool canSkipToEnd(const int &i)
static pair<bool, bool> &isStatic(Literal *l)
static void simplify(pair<list<double>, list<int>> &s)
static void makeOneSided(pair<list<double>, list<int>> &LHSvariable, pair<list<double>, list<int>> &RHSvariable, const int &negOffset)
static void makeWeightedSum(list<Operand> &formula, pair<list<double>, list<int>> &result)
static inline const vector<double> &getNonTemporalDurationToPrint()
static inline const vector<FakeTILAction*> &getAllTimedInitialLiterals()
static inline vector<list<NumericPrecondition*>> &getFixedDEs()
static inline vector<list<NumericPrecondition*>> &getMinDEs()
static inline vector<list<NumericPrecondition*>> &getMaxDEs()
static inline vector<RPGDuration*> &getRPGDEs(const int &a)
static inline vector<LinearEffects*> &getLinearDiscretisation()
static inline vector<list<int>> &getStartPreNumerics()
static inline vector<list<int>> &getInvariantNumerics()
static inline vector<list<int>> &getEndPreNumerics()
static inline vector<list<int>> &getStartEffNumerics()
static inline vector<list<int>> &getEndEffNumerics()
static inline const vector<list<ConditionalEffect>> &getActionsToConditionalEffects()
static inline vector<list<Literal*>> &getStartPropositionAdds()
static inline vector<list<Literal*>> &getStartPropositionDeletes()
static inline vector<list<Literal*>> &getEndPropositionAdds()
static inline vector<list<Literal*>> &getEndPropositionDeletes()
static inline vector<list<Literal*>> &getProcessedStartPropositionalPreconditions()
static inline vector<list<Literal*>> &getStartPropositionalPreconditions()
static inline vector<list<Literal*>> &getStartNegativePropositionalPreconditions()
static inline vector<list<Literal*>> &getInvariantPropositionalPreconditions()
static inline vector<list<Literal*>> &getInvariantNegativePropositionalPreconditions()
static inline vector<list<Literal*>> &getEndPropositionalPreconditions()
static inline vector<list<Literal*>> &getEndNegativePropositionalPreconditions()
static inline vector<list<Literal*>> &getProcessedStartNegativePropositionalPreconditions()
static inline vector<RPGNumericPrecondition> &getNumericPreTable()

@Return A reference to rpgNumericPreconditions, the preconditions used in the problem, in LNF.

static inline vector<RPGNumericEffect> &getNumericEff()

@Return A reference to rpgNumericEffects, the effects used in the problem, in LNF.

static inline const vector<list<pair<int, VAL::time_spec>>> &getRpgNumericEffectsToActions()

@Return a reference to rpgNumericEffectsToActions: for each numeric effects, which actions have it.

static inline const vector<ArtificialVariable> &getArtificialVariableTable()

@Return A const reference to rpgArtificialVariables, the artificial variables built so that multi-variable preconditions and can be written in terms of a single ‘artificial’ variable.

static inline vector<list<pair<int, VAL::time_spec>>> &getPresToActions()
static inline vector<list<pair<int, VAL::time_spec>>> &getRawPresToActions()
static void initialise()
static inline bool nonTemporalProblem()
static inline list<Literal*> &getLiteralGoals()
static RPGHeuristic *generateRPGHeuristic()
static inline RPGHeuristic *getHeuristic()
static void getInitialState(LiteralSet &initialState, vector<double> &initialFluents)
static void getNonStaticInitialState(LiteralSet &initialState, vector<double> &initialFluents)
static inline instantiatedOp *getInstantiatedOp(const int &i)
static inline Literal *getLiteral(const int &i)
static inline list<FakeTILAction> &getTILs()
static inline list<pair<int, VAL::time_spec>> &getEffectsToActions(const int &i)
static inline vector<FakeTILAction*> &getTILVec()
static void getEffects(instantiatedOp *op, const bool &start, list<Literal*> &add, list<Literal*> &del, list<NumericEffect> &numeric)
static void getPrecInv(instantiatedOp *op, const bool &start, list<Literal*> &precs, list<Literal*> &inv, list<NumericPrecondition> &numericPrec, list<NumericPrecondition> &numericInv)
static inline Metric *getMetric()
static inline list<int> &getMentioned(const int &i)
static bool stepNeedsToHaveFinished(const ActionSegment &act, const MinimalState &s, set<int> &dest)
static double getOpMinDuration(instantiatedOp *op, const int &div)
static double getOpMinDuration(const int &op, const int &div)
static double getOpMaxDuration(instantiatedOp *op, const int &div)
static double getOpMaxDuration(const int &op, const int &div)
static pair<double, double> getOpDuration(instantiatedOp *op, const int &div, const vector<double> &minFluents, const vector<double> &maxFluents)
static pair<double, double> getOpDuration(const int &op, const int &div, const vector<double> &minFluents, const vector<double> &maxFluents)
static inline PNE *getPNE(const int &i)
static inline int getPNECount()
static inline int getAVCount()
static inline ArtificialVariable &getArtificialVariable(const int &i)
static inline list<int> &getVariableDependencies(const int &i)
static inline list<int> &affectsRPGNumericPreconditions(int i)
static inline int howManyTimes(const int &actID, const MinimalState &e)
static inline int howManyTimesOptimistic(const int &actID, const MinimalState &e)
static inline bool literalIsOneShot(const int &lID)
static inline bool isSelfMutex(const int &actID)
static inline list<pair<int, int>> &getNumericRPGGoals()
static inline list<NumericPrecondition> &getNumericGoals()
static bool isInteresting(const int &act, const map<int, PropositionAnnotation> &facts, const map<int, set<int>> &started)
static inline LiteralSet &getEndOneShots(const int &i)

Public Static Attributes

static bool doSkipAnalysis
static Metric *theMetric
static set<int> metricVars
static const vector<bool> &rogueActions
static vector<bool> realRogueActions
static bool sortedExpansion
static bool fullFFHelpfulActions
static bool modifiedRPG
static bool noSelfOverlaps
static bool doTemporalAnalysis
class ArtificialVariable

Public Functions

inline ArtificialVariable()
inline ArtificialVariable(const int &id, const int &s, const vector<double> &w, const vector<int> &f, const double &d, const double &maxIn)
inline double evaluate(const vector<double> &fluentTable)
double evaluateWCalculate(const vector<double> &fluentTable, const int &pneCount)
double evaluateWCalculate(const vector<double> &minFluentTable, const vector<double> &maxFluentTable, const int &pneCount)
bool operator<(const ArtificialVariable &v) const
void display(ostream &o) const
inline void updateMax(const double &m)

Public Members

int ID
int size
vector<double> weights
vector<int> fluents
double constant
double maxNeed
class ConditionalEffect

Class to represent a conditional effect. The class is capable of storing more fields than can currently be used by the planner - currently, only conditional effects upon metric tracking variables are supported, conditional on either propositions controlled exclusively by timed initial literals, or on numeric values.

Public Functions

inline ConditionalEffect()
inline void addCondition(Literal *const l, const VAL::time_spec &t)
inline void addCondition(const int &p, const VAL::time_spec &t)
inline void addNumericEffect(const int &p, const VAL::time_spec &t)
inline void addAddEffect(Literal *const l, const VAL::time_spec &t)
inline void addDeleteEffect(Literal *const l, const VAL::time_spec &t)
inline const list<pair<Literal*, VAL::time_spec>> &getPropositionalConditions() const
inline const list<pair<int, VAL::time_spec>> &getNumericPreconditions() const
inline const list<pair<int, VAL::time_spec>> &getNumericEffects() const
inline const list<pair<Literal*, VAL::time_spec>> &getPropositionalAddEffects() const
inline const list<pair<Literal*, VAL::time_spec>> &getPropositionalDeleteEffects() const
struct Constraint

Public Functions

inline Constraint()
inline Constraint(const string &n)

Public Members

string name
VAL::constraint_sort cons
list<Literal*> goal
list<Literal*> trigger
list<NumericPrecondition> goalNum
list<NumericPrecondition> triggerNum
list<int> goalRPGNum
list<int> triggerRPGNum
double deadline
double from
double cost
bool neverTrue
class DurationExpr

A class defining a single duration constraint, in LNF.

Public Functions

inline DurationExpr()
inline DurationExpr(const double &d)

Create a duration expression, with unknown operator and empty weights and variables.

Parameters:

d – The constant term for the duration expression

double minOf(const vector<double> &minVars, const vector<double> &maxVars)

Evaluate the minimum possible value that satisfies this duration expression, given the provided lower- and upper-bounds on the values of the task numeric variables.

Parameters:
  • minVars – Minimum values of the task variables

  • maxvars – Maximum values of the task variables

Returns:

The lowest permissible duration, according to this duration expression.

double maxOf(const vector<double> &minVars, const vector<double> &maxVars)

Evaluate the maximum possible value that satisfies this duration expression, given the provided lower- and upper-bounds on the values of the task numeric variables.

Parameters:
  • minVars – Minimum values of the task variables

  • maxvars – Maximum values of the task variables

Returns:

The greatest permissible duration, according to this duration expression.

Public Members

vector<double> weights

The weights of the variables in the duration expression

vector<int> variables

The IDs of the variables in the duration expression.

See also

RPGBuilder::getPNE

VAL::comparison_op op

The comparison operator for this duration expression. Is one of:

  • VAL::E_GREATEQ for (>= ?duration ...)

  • VAL::E_GREATER for (> ?duration ...)

  • VAL::E_EQUALS for (= ?duration ...)

  • VAL::E_LESS for (< ?duration ...)

  • VAL::E_LESSEQ for (<= ?duration ...)

double constant

The constant term for the duration expression

class FakeTILAction

Class to represent the ‘action’ whose application corresponds to a timed initial literal.

Public Functions

inline void mergeIn(const LiteralSet &adds, const LiteralSet &dels)

Add the specified add and delete effects to the timed initial literal action. Is used when multiple TILs are found at a given time-stamp.

Parameters:
  • adds – Add effects to include in this TIL action

  • dels – Delete effects to include in this TIL action

inline FakeTILAction(const double &dur, const LiteralSet &adds, const LiteralSet &dels)

Constructor for an action corresponding to a Timed Initial Literal.

Parameters:
  • dur – The time at which the timed initial occurs

  • adds – The facts added at time dur

  • dels – The facts deleted at time dur

Public Members

const double duration

The time-stamp of the timed initial literal

list<Literal*> addEffects

The facts added at the specified time

list<Literal*> delEffects

The facts deleted at the specified time

class KShotFormula

Subclassed by Planner::RPGBuilder::KShotKShotFormula, Planner::RPGBuilder::OneShotKShotFormula, Planner::RPGBuilder::UnlimitedKShotFormula

Public Functions

inline KShotFormula()
virtual int getLimit(const MinimalState &s) const = 0
virtual int getOptimisticLimit(const MinimalState &s) const = 0
inline virtual ~KShotFormula()
class KShotKShotFormula : public Planner::RPGBuilder::KShotFormula

Public Functions

inline KShotKShotFormula(list<ShotCalculator> &c)
virtual int getLimit(const MinimalState &s) const
virtual int getOptimisticLimit(const MinimalState &s) const
class LinearEffects

A class defining the linear continuous effects of an action

Public Members

vector<int> vars

The IDs of the variables upon which this action has continuous effects.

See also

RPGBuilder::getPNE

vector<vector<EffectExpression>> effects

The effects themselves. Each entry is a vector describing the effect upon the corresponding variable in vars. For now, at most one such vector exists, but in the future this may change if support for piecewise-linear effects is added.

int divisions

The number of divisions for the continuous numeric effects of the action. At present this is always 1, i.e. the gradients of the effects remain fixed across the execution of the action, but this may change if support for piecewise-linear effects is added.

struct EffectExpression

A single linear continuous numeric effect expression. The gradient of the effect is stored in LNF.

Public Functions

inline EffectExpression(const double &g)

Constructor for a constant-gradient linear continuous effect

Parameters:

g – The gradient of the effect

Public Members

vector<double> weights

The weights for the variables in the LNF expression of the gradient.

vector<int> variables

The variables in the LNF expression of the gradient.

double constant

The constant term of the LNF expression of the gradient.

class Metric

Public Functions

inline Metric(const bool &m)

Public Members

bool minimise
list<double> weights
list<int> variables
class NoDuplicatePair

Public Functions

inline NoDuplicatePair()
inline NoDuplicatePair(list<Literal*> *const listIn, LiteralSet *const setIn)
inline void push_back(Literal *const toAdd)
inline Literal *back() const
inline bool operator!() const
template<typename T>
inline void insert(T itr, const T &itrEnd)

Protected Attributes

list<Literal*> *first
LiteralSet *second
class NumericEffect

Public Functions

NumericEffect(const VAL::assign_op &opIn, const int &fIn, VAL::expression *formulaIn, VAL::FastEnvironment *f, VAL::TypeChecker *t = 0)
double applyEffect(vector<double> &fluents) const
void display(ostream &o) const

Public Members

int fluentIndex
VAL::assign_op op
list<Operand> formula
class NumericPrecondition

Public Functions

NumericPrecondition(const VAL::comparison_op &opIn, VAL::expression *LHSformulaIn, VAL::expression *RHSformulaIn, VAL::FastEnvironment *f, VAL::TypeChecker *t = 0, const bool negated = false)
bool isSatisfied(vector<double> &fluents) const
void display(ostream &o) const
double evaluateRHS(vector<double> &fluentTable) const
pair<double, bool> constRHS() const

Public Members

VAL::comparison_op op
list<Operand> LHSformula
list<Operand> RHSformula
bool valid
bool polarity
class OneShotKShotFormula : public Planner::RPGBuilder::KShotFormula

Public Functions

inline OneShotKShotFormula(list<int> &toWatch)
virtual int getLimit(const MinimalState &s) const
virtual int getOptimisticLimit(const MinimalState &s) const
struct Operand

Public Functions

inline Operand(const math_op &o)
inline Operand(const int &f)
inline Operand(const double &c)
inline Operand(const string &s)

Public Members

math_op numericOp
int fluentValue
double constantValue
string isviolated
class ProtoConditionalEffect

Public Members

list<Literal*> startPrec
LiteralSet startPrecSet
list<Literal*> inv
LiteralSet invSet
list<Literal*> endPrec
LiteralSet endPrecSet
list<Literal*> startNegPrec
LiteralSet startNegPrecSet
list<Literal*> negInv
LiteralSet negInvSet
list<Literal*> endNegPrec
LiteralSet endNegPrecSet
list<RPGBuilder::NumericPrecondition> startPrecNumeric
list<RPGBuilder::NumericPrecondition> invNumeric
list<RPGBuilder::NumericPrecondition> endPrecNumeric
list<Literal*> startAddEff
LiteralSet startAddEffSet
list<Literal*> startDelEff
LiteralSet startDelEffSet
list<RPGBuilder::NumericEffect> startNumericEff
list<Literal*> endAddEff
LiteralSet endAddEffSet
list<Literal*> endDelEff
LiteralSet endDelEffSet
list<RPGBuilder::NumericEffect> endNumericEff
class RPGDuration

A class containing all the duration constraints imposed on an action.

Public Functions

inline RPGDuration(list<DurationExpr*> &eq, list<DurationExpr*> &low, list<DurationExpr*> &high)
inline const list<DurationExpr*> &operator[](const int &i) const

Return one of the lists of durations contained in the object.

Parameters:

i – Which list of durations to return:

  • 0 returns the fixed duration expressions;

  • 1 returns the min duration expressions;

  • 2 returns the max duration expressions.

Returns:

The requested list of duration expressions.

Public Members

list<DurationExpr*> fixed

The fixed durations of the action, those of the form (= ?duration ...)

list<DurationExpr*> min

The minimum durations of the action, those of the form (>= ?duration ...) or (> ?duration ...)

list<DurationExpr*> max

The maximum durations of the action, those of the form (<= ?duration ...) or (< ?duration ...)

class RPGNumericEffect

Public Functions

inline RPGNumericEffect()
inline RPGNumericEffect(const int &idIn, const int &fluent, const bool &ass, const vector<double> &weightsIn, const vector<int> &vars, const int &s, const double &con)
inline double evaluate(const vector<double> &maxFluents, const double &minDur, const double &maxDur) const
pair<double, double> applyEffectMinMax(const vector<double> &minFluents, const vector<double> &maxFluents, const double &minDur, const double &maxDur)
bool operator<(const RPGNumericEffect &e) const
void display(ostream &o) const

Public Members

int ID
int fluentIndex
bool isAssignment
vector<double> weights
vector<int> variables
double constant
int size
class RPGNumericPrecondition

Public Functions

inline RPGNumericPrecondition()
inline RPGNumericPrecondition(const int &i, const int &lv, const double &lw, const VAL::comparison_op &o, const double &rw)
inline bool isSatisfied(vector<double> &maxFluents) const
bool isSatisfiedWCalculate(const vector<double> &maxFluents) const
bool isSatisfiedWCalculate(const vector<double> &minFluents, const vector<double> &maxFluents) const
bool operator<(const RPGNumericPrecondition &r) const
void display(ostream &o) const

Public Members

int ID
int LHSVariable
double LHSConstant
VAL::comparison_op op
int RHSVariable
double RHSConstant
struct ShotCalculator

Public Functions

inline ShotCalculator(const int &v, const double &g, const double &d)

Public Members

int variable
double greaterThan
double decreaseBy
class UnlimitedKShotFormula : public Planner::RPGBuilder::KShotFormula

Public Functions

inline UnlimitedKShotFormula()
inline virtual int getLimit(const MinimalState&) const
inline virtual int getOptimisticLimit(const MinimalState&) const