Program Listing for File lpscheduler.h
↰ Return to documentation for file (src/popf/lpscheduler.h)
/************************************************************************
* Copyright 2010, Strathclyde Planning Group,
* Department of Computer and Information Sciences,
* University of Strathclyde, Glasgow, UK
* http://planning.cis.strath.ac.uk/
*
* Andrew Coles, Amanda Coles - Code for POPF
* Maria Fox, Richard Howey and Derek Long - Code from VAL
* Stephen Cresswell - PDDL Parser
*
* This file is part of the planner POPF.
*
* POPF is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 2 of the License, or
* (at your option) any later version.
*
* POPF is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with POPF. If not, see <http://www.gnu.org/licenses/>.
*
************************************************************************/
#ifndef LPSCHEDULER
#define LPSCHEDULER
#include "FFSolver.h"
#include <map>
#include <list>
#include <set>
#include <vector>
#include <cstring>
using std::map;
using std::list;
using std::set;
using std::vector;
class MILPSolver;
namespace Planner
{
class ParentData;
class ChildData;
class LPScheduler
{
public:
static bool hybridBFLP;
static bool optimiseOrdering;
protected:
int tsVarCount;
ChildData * cd;
struct ConstraintPtrLT;
class Constraint
{
public:
vector<double> weights;
vector<int> variables;
double lower;
double upper;
Constraint() : lower(0.0), upper(0.0) {
};
static const Constraint * requestConstraint(const Constraint & c) {
const pair<set<Constraint>::iterator, bool> insResult = constraintStore.insert(c);
if (insResult.second) {
insResult.first->ID = constraintCount++;
}
return &(*(insResult.first));
}
bool operator <(const Constraint & c) const {
const unsigned int thisVC = weights.size();
const unsigned int otherVC = c.weights.size();
if (thisVC < otherVC) return true;
if (thisVC > otherVC) return false;
if (fabs(lower - c.lower) > 0.0000001) {
if (lower < c.lower) return true;
if (lower > c.lower) return false;
}
if (fabs(upper - c.upper) > 0.0000001) {
if (upper < c.upper) return true;
if (upper > c.upper) return false;
}
for (unsigned int i = 0; i < thisVC; ++i) {
if (variables[i] < c.variables[i]) return true;
if (variables[i] > c.variables[i]) return false;
if (fabs(weights[i] - c.weights[i]) > 0.0000001) {
if (weights[i] < c.weights[i]) return true;
if (weights[i] > c.weights[i]) return false;
}
}
return false;
}
protected:
static set<Constraint> constraintStore;
static int constraintCount;
mutable int ID;
friend class ConstraintPtrLT;
};
struct ConstraintPtrLT {
bool operator()(const Constraint * const a, const Constraint * const b) const {
return (a->ID < b->ID);
}
};
typedef set<const Constraint*, ConstraintPtrLT> ConstraintSet;
class CountedConstraintSet : public map<const Constraint*, unsigned int, ConstraintPtrLT>
{
public:
typedef map<const Constraint*, unsigned int, ConstraintPtrLT> __super;
typedef __super::iterator iterator;
void insert(const Constraint* const c);
void erase(const Constraint* const c);
void insert(const ConstraintSet & c);
void erase(const ConstraintSet & c);
iterator begin() {
return __super::begin();
}
iterator end() {
return __super::end();
}
template<class _InputIterator>
void insert(_InputIterator itr, const _InputIterator & itrEnd) {
bool firstTime = true;
iterator thisItr;
for (; itr != itrEnd; ++itr) {
if (firstTime) {
thisItr = __super::insert(make_pair(*itr, 0)).first;
firstTime = false;
} else {
thisItr = __super::insert(thisItr, make_pair(*itr, 0));
}
++thisItr->second;
}
};
template<class _InputIterator>
void erase(_InputIterator itr, const _InputIterator & itrEnd) {
for (; itr != itrEnd; ++itr) {
const iterator thisItr = __super::find(*itr);
if (thisItr != __super::end()) {
if (!(--(thisItr->second))) {
__super::erase(thisItr);
}
}
}
};
};
class FluentTracking
{
public:
enum fluent_status { FS_NORMAL = 0, FS_IGNORE = 1, FS_ORDER_INDEPENDENT = 2};
fluent_status statusOfThisFluent;
double postLastEffectValue;
int lastEffectValueVariable;
int lastEffectTimestampVariable;
double activeGradient;
int activeGradientCount;
map<int,double> orderIndependentValueTerms;
double orderIndependentValueConstant;
FluentTracking(const double & initial)
: statusOfThisFluent(FS_NORMAL), postLastEffectValue(initial), lastEffectValueVariable(-1), lastEffectTimestampVariable(-1), activeGradient(0.0), activeGradientCount(0), orderIndependentValueConstant(0.0) {
}
FluentTracking() { // unfortunately needed for vector<FluentTracking>
}
};
class InterestingMap : map<int, bool>
{
public:
typedef map<int, bool> __super;
typedef __super::iterator iterator;
typedef __super::const_iterator const_iterator;
iterator begin() {
return __super::begin();
}
const_iterator begin() const {
return __super::begin();
}
iterator end() {
return __super::end();
}
const_iterator end() const {
return __super::end();
}
const_iterator find(const int & i) const {
return __super::find(i);
}
iterator find(const int & i) {
return __super::find(i);
}
void erase(const int & i) {
__super::erase(i);
}
void erase(const iterator & i) {
__super::erase(i);
}
InterestingMap() {
}
InterestingMap(const InterestingMap & other) : __super(other) {
}
InterestingMap(const map<int, bool> & in) : __super(in) {
}
InterestingMap & operator =(const __super & in) {
__super::operator=(in);
return *this;
}
template<class _InputIterator>
void insertKeepingTrues(_InputIterator srcItr, const _InputIterator & srcEnd) {
__super::iterator lastPos;
bool firstTime = true;
for (; srcItr != srcEnd; ++srcItr) {
if (firstTime) {
lastPos = __super::insert(*srcItr).first;
firstTime = false;
} else {
lastPos = __super::insert(lastPos, *srcItr);
}
if (srcItr->second) lastPos->second = true;
}
};
virtual void insertKeepingTrues(const pair<int, bool> & toInsert);
virtual void insertEffect(const int & i) {
__super::insert(make_pair(i, true)).first->second = true;
}
virtual void insertPrecondition(const int & i) {
__super::insert(make_pair(i, false));
}
template<class _InputIterator>
void insertPreconditions(_InputIterator itr, const _InputIterator & itrEnd) {
bool firstTime = true;
__super::iterator thisItr;
for (; itr != itrEnd; ++itr) {
if (firstTime) {
thisItr = __super::insert(make_pair(*itr, false)).first;
firstTime = false;
} else {
thisItr = __super::insert(thisItr, make_pair(*itr, false));
}
}
};
template<class _InputIterator>
void insertEffects(_InputIterator itr, const _InputIterator & itrEnd) {
bool firstTime = true;
__super::iterator thisItr;
for (; itr != itrEnd; ++itr) {
if (firstTime) {
thisItr = __super::insert(make_pair(*itr, true)).first;
firstTime = false;
} else {
thisItr = __super::insert(thisItr, make_pair(*itr, true));
}
thisItr->second = true;
}
};
};
static double* weightScratch;
static int* varScratch;
static bool scratchInit;
struct ConstraintAdder;
struct DurationAdder;
friend struct ConstraintAdder;
friend struct DurationAdder;
MILPSolver * lp;
int timestampToUpdateVar;
int timestampToUpdateStep;
FFEvent * timestampToUpdate;
int timestampToUpdatePartnerVar;
int timestampToUpdatePartnerStep;
FFEvent * timestampToUpdatePartner;
int previousObjectiveVar;
//list<int> mutexCols;
//list<int> mutexRows;
vector<int> timestampVars;
vector<FluentTracking> finalNumericVars;
list<int> endsOfThreads;
double makespanVarMinimum;
vector<bool> stableVariable;
bool solved;
bool nameLPElements;
bool includeMetricTrackingVariables;
bool assertions;
static vector<double> TILtimestamps;
struct EndDetails {
list<StartEvent>::iterator first;
int imaginaryMin;
int imaginaryMax;
int lastToMin;
EndDetails(const int & min, const int & max, const int & cons) : imaginaryMin(min), imaginaryMax(max), lastToMin(cons) {};
EndDetails() {};
};
map<int, list<EndDetails> > openDurationConstraints;
static vector<vector<list<pair<int, RPGBuilder::LinearEffects::EffectExpression> > > > gradientEffects;
static vector<vector<list<RPGBuilder::RPGNumericEffect* > > > instantEffects;
static vector<vector<list<const Constraint*> > > constraints;
static vector<vector<InterestingMap> > interesting;
static vector<vector<vector<double> > > pointsThatWouldBeMutexWithOptimisationTILs;
static vector<vector<pair<bool,bool> > > boringAct;
static vector<double> initialValues;
static list<const Constraint*> goalConstraints;
static const Constraint* buildConstraint(RPGBuilder::RPGNumericPrecondition & d);
static int numVars;
static bool initialised;
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);
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);
void addConstraintsForTILMutexes(const int & timestampVar, const vector<double> & mutexTimestamps);
bool addAnyNumericConstraints(const list<pair<int, VAL::time_spec> > & numericConditions,
const int & actStartAt, const int & actEndAt, list<int> & conditionVars);
bool addAnyTimeWindowConstraints(const list<pair<Literal*, VAL::time_spec> > & propositionalConditions,
const int & actStartAt, const int & actEndAt, list<int> & conditionVars);
bool scheduleToMetric();
void pushTimestampToMin();
vector<FFEvent*> planAsAVector;
public:
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();
static inline bool isBoring(const int & a, const int & s, const bool & includeMetric) {
if (includeMetric) {
return boringAct[a][s].second;
} else {
return boringAct[a][s].first;
}
};
const bool & isSolved() const {
return solved;
};
void updateStateFluents(vector<double> & min, vector<double> & max);
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);
static ParentData* prime(list<FFEvent> & header, const TemporalConstraints * const cons, list<StartEvent> & open, const bool includeMetric=false);
static void initialise();
static int lpDebug;
static const double & getTILTimestamp(const int & i) {
return TILtimestamps[i];
};
};
class LPQueueSet
{
private:
const int arrSize;
list<int> Q;
bool * qSet;
public:
bool * UB;
bool * LB;
bool * UBP;
bool * LBP;
int * NEW;
LPQueueSet(const int & i) : arrSize(i + 1), qSet(new bool[arrSize]),
UB(new bool[arrSize]), LB(new bool[arrSize]),
UBP(new bool[arrSize]), LBP(new bool[arrSize]), NEW(new int[arrSize]) {
++qSet; ++UB; ++LB; ++UBP; ++LBP; ++NEW;
memset(&qSet[-1], 0, arrSize * sizeof(bool));
memset(&UB[-1], 0, arrSize * sizeof(bool));
memset(&LB[-1], 0, arrSize * sizeof(bool));
memset(&UBP[-1], 0, arrSize * sizeof(bool));
memset(&LBP[-1], 0, arrSize * sizeof(bool));
for (int j = -1; j < i; ++j) NEW[j] = -2;
};
~LPQueueSet() {
delete [](--qSet);
delete [](--UB);
delete [](--LB);
delete [](--UBP);
delete [](--LBP);
delete [](--NEW);
};
void push_back(const int & u) {
if (!qSet[u]) {
Q.push_back(u);
qSet[u] = true;
}
}
bool empty() const {
return (Q.empty());
}
int pop_front() {
int toReturn = Q.front();
qSet[toReturn] = false;
Q.pop_front();
return toReturn;
}
void cleanup(const int & from, const int & to) {
reset(from, to);
memset(&qSet[-1], 0, arrSize * sizeof(bool));
Q.clear();
}
void reset(const int & from, const int & to) {
memset(&UB[-1], 0, arrSize * sizeof(bool));
memset(&LB[-1], 0, arrSize * sizeof(bool));
memset(&UBP[-1], 0, arrSize * sizeof(bool));
memset(&LBP[-1], 0, arrSize * sizeof(bool));
NEW[from] = -2;
NEW[to] = -2;
}
void visit(const int & from, const int & to) {
push_back(from);
push_back(to);
LB[from] = true;
UB[from] = true;
NEW[from] = to;
LB[to] = true;
UB[to] = true;
NEW[to] = from;
}
};
class IncomingAndOutgoing
{
protected:
map<int, bool> mustFollowThisD;
map<int, bool> mustPrecedeThisD;
public:
const map<int, bool> & mustFollowThis() const {
return mustFollowThisD;
}
const map<int, bool> & mustPrecedeThis() const {
return mustPrecedeThisD;
}
void addFollower(const int & a, const bool & b) {
if (Globals::globalVerbosity & 4096) {
if (b) {
cout << "Insisting that " << a << " is at least epsilon after this step\n";
} else {
cout << "Insisting that " << a << " is at least 0 after this step\n";
}
}
bool & orWith = mustFollowThisD.insert(make_pair(a, b)).first->second;
orWith = (orWith || b);
}
void initialisePredecessors(const map<int, bool> & p) {
assert(mustPrecedeThisD.empty());
mustPrecedeThisD = p;
}
void addPredecessor(const int & a, const bool & b) {
if (Globals::globalVerbosity & 4096) {
if (b) {
cout << "Insisting that " << a << " is at least epsilon before this step\n";
} else {
cout << "Insisting that " << a << " is at least 0 before this step\n";
}
}
bool & orWith = mustPrecedeThisD.insert(make_pair(a, b)).first->second;
orWith = (orWith || b);
}
};
class ParentData
{
public:
LPQueueSet Q;
private:
int qs;
int startGap;
int endGap;
vector<double> distFromZero;
vector<double> distToZero;
vector<int> pairWith;
vector<FFEvent*> eventsWithFakes;
list<FFEvent> * parentPlan;
map<int, IncomingAndOutgoing > temporaryEdges;
bool needsLP;
int nextTIL;
public:
ParentData(const int & qSize, list<FFEvent> * h, const int & nt)
: Q(qSize), qs(qSize), startGap(-1), endGap(-1),
distFromZero(qSize, DBL_MAX), distToZero(qSize, 0.0),
pairWith(qSize, -1), eventsWithFakes(qSize, (FFEvent*)0),
parentPlan(h), nextTIL(nt) {};
~ParentData() {
for (int i = 0; i < qs; ++i) {
delete eventsWithFakes[i];
}
}
void setWhetherNeedsLP(const bool & b) {
needsLP = b;
};
const vector<double> & getDistFromZero() const {
return distFromZero;
};
const vector<double> & getDistToZero() const {
return distToZero;
};
const vector<FFEvent*> & getEventsWithFakes() const {
return eventsWithFakes;
};
const vector<int> & getPairWith() const {
return pairWith;
};
const map<int, IncomingAndOutgoing > & getTemporaryEdges() const {
return temporaryEdges;
};
inline void setRawDistToFromZero(const int & i, const double & t, const double & f) {
distToZero[i] = t;
distFromZero[i] = f;
};
inline void setPairWith(const int & i, const int & w) {
pairWith[i] = w; pairWith[w] = i;
};
inline void setTIL(const int & i) {
pairWith[i] = -2;
};
inline void setNonTemporal(const int & i) {
pairWith[i] = -3;
};
inline void supplyFake(const int & i, FFEvent * const f) {
eventsWithFakes[i] = f;
};
inline IncomingAndOutgoing & makeEdgeListFor(const int & i) {
return temporaryEdges[i];
};
inline void startGapIsStep(const int & i) {
startGap = i;
};
inline void endGapIsStep(const int & i) {
endGap = i;
};
const int & whereIsStartGap() const {
return startGap;
};
const int & whereIsEndGap() const {
return endGap;
};
ChildData * spawnChildData(list<StartEvent> & seq,
list<FFEvent> & header, list<FFEvent> & succ,
const bool & includeMetric,
const TemporalConstraints * const cons,
const int & stepID);
void sanityCheck() {
const int loopLim = distToZero.size();
list<FFEvent>::iterator hItr = parentPlan->begin();
for (int i = 0; i < loopLim; ++i) {
if (hItr != parentPlan->end()) {
if (hItr->time_spec == VAL::E_AT && pairWith[i] != -2) {
cout << "Header event " << i << " is a TIL, but is not paired with -2\n";
assert(pairWith[i] == -2);
}
++hItr;
} else {
if (eventsWithFakes[i] && eventsWithFakes[i]->time_spec == VAL::E_AT && pairWith[i] != -2) {
cout << "Event " << i << " is a TIL, but is not paired with -2\n";
assert(pairWith[i] == -2);
}
}
}
}
};
};
#endif