Classes | Public Member Functions | Private Types | Private Attributes | List of all members
gtsam::Scheduler Class Reference

#include <Scheduler.h>

Inheritance diagram for gtsam::Scheduler:
Inheritance graph
[legend]

Classes

struct  Student
 

Public Member Functions

void accumulateStats (sharedValues assignment, std::vector< size_t > &stats) const
 
void addArea (const std::string &facultyName, const std::string &areaName)
 
void addFaculty (const std::string &facultyName)
 
void addSlot (const std::string &slotName)
 
void addStudent (const std::string &studentName, const std::string &area1, const std::string &area2, const std::string &area3, const std::string &advisor)
 
void addStudentSpecificConstraints (size_t i, boost::optional< size_t > slot=boost::none)
 
sharedValues bestAssignment (sharedValues bestSchedule) const
 
sharedValues bestSchedule () const
 
void buildGraph (size_t mutexBound=7)
 
DiscreteBayesNet::shared_ptr eliminate () const
 
const DiscreteKeykey (size_t s, boost::optional< size_t > area=boost::none) const
 
size_t nrFaculty () const
 
size_t nrStudents () const
 current number of students More...
 
size_t nrTimeSlots () const
 
sharedValues optimalAssignment () const
 
void print (const std::string &s="Scheduler", const KeyFormatter &formatter=DefaultKeyFormatter) const override
 
void printAssignment (sharedValues assignment) const
 
void printSpecial (sharedValues assignment) const
 
 Scheduler (size_t maxNrStudents)
 
 Scheduler (size_t maxNrStudents, const std::string &filename)
 
void setAvailability (const std::string &available)
 
void setSlotsAvailable (const std::vector< double > &slotsAvailable)
 
const std::string & slotName (size_t s) const
 
const std::string & studentArea (size_t i, size_t area) const
 
const DiscreteKeystudentKey (size_t i) const
 
const std::string & studentName (size_t i) const
 
virtual ~Scheduler ()
 Destructor. More...
 
- Public Member Functions inherited from gtsam::CSP
void addAllDiff (const DiscreteKey &key1, const DiscreteKey &key2)
 Add a binary AllDiff constraint. More...
 
void addAllDiff (const DiscreteKeys &dkeys)
 Add a general AllDiff constraint. More...
 
void addSingleValue (const DiscreteKey &dkey, size_t value)
 Add a unary constraint, allowing only a single value. More...
 
sharedValues optimalAssignment () const
 Find the best total assignment - can be expensive. More...
 
sharedValues optimalAssignment (const Ordering &ordering) const
 Find the best total assignment - can be expensive. More...
 
void runArcConsistency (size_t cardinality, size_t nrIterations=10, bool print=false) const
 
- Public Member Functions inherited from gtsam::DiscreteFactorGraph
template<class SOURCE >
void add (const DiscreteKey &j, SOURCE table)
 
template<class SOURCE >
void add (const DiscreteKey &j1, const DiscreteKey &j2, SOURCE table)
 
template<class SOURCE >
void add (const DiscreteKeys &keys, SOURCE table)
 
 DiscreteFactorGraph ()
 
template<typename ITERATOR >
 DiscreteFactorGraph (ITERATOR firstFactor, ITERATOR lastFactor)
 
template<class CONTAINER >
 DiscreteFactorGraph (const CONTAINER &factors)
 
template<class DERIVEDFACTOR >
 DiscreteFactorGraph (const FactorGraph< DERIVEDFACTOR > &graph)
 
KeySet keys () const
 
double operator() (const DiscreteFactor::Values &values) const
 
DiscreteFactor::sharedValues optimize () const
 
DecisionTreeFactor product () const
 
virtual ~DiscreteFactorGraph ()
 Destructor. More...
 
bool equals (const This &fg, double tol=1e-9) const
 
- Public Member Functions inherited from gtsam::FactorGraph< DiscreteFactor >
virtual ~FactorGraph ()=default
 Default destructor. More...
 
void reserve (size_t size)
 
IsDerived< DERIVEDFACTOR > push_back (boost::shared_ptr< DERIVEDFACTOR > factor)
 Add a factor directly using a shared_ptr. More...
 
IsDerived< DERIVEDFACTOR > push_back (const DERIVEDFACTOR &factor)
 
IsDerived< DERIVEDFACTOR > emplace_shared (Args &&...args)
 Emplace a shared pointer to factor of given type. More...
 
IsDerived< DERIVEDFACTOR > add (boost::shared_ptr< DERIVEDFACTOR > factor)
 add is a synonym for push_back. More...
 
std::enable_if< std::is_base_of< FactorType, DERIVEDFACTOR >::value, boost::assign::list_inserter< RefCallPushBack< This > > >::type operator+= (boost::shared_ptr< DERIVEDFACTOR > factor)
 += works well with boost::assign list inserter. More...
 
HasDerivedElementType< ITERATOR > push_back (ITERATOR firstFactor, ITERATOR lastFactor)
 
HasDerivedValueType< ITERATOR > push_back (ITERATOR firstFactor, ITERATOR lastFactor)
 Push back many factors with an iterator (factors are copied) More...
 
HasDerivedElementType< CONTAINER > push_back (const CONTAINER &container)
 
HasDerivedValueType< CONTAINER > push_back (const CONTAINER &container)
 Push back non-pointer objects in a container (factors are copied). More...
 
void add (const FACTOR_OR_CONTAINER &factorOrContainer)
 
boost::assign::list_inserter< CRefCallPushBack< This > > operator+= (const FACTOR_OR_CONTAINER &factorOrContainer)
 
std::enable_if< std::is_base_of< This, typename CLIQUE::FactorGraphType >::value >::type push_back (const BayesTree< CLIQUE > &bayesTree)
 
FactorIndices add_factors (const CONTAINER &factors, bool useEmptySlots=false)
 
bool equals (const This &fg, double tol=1e-9) const
 
size_t size () const
 
bool empty () const
 
const sharedFactor at (size_t i) const
 
sharedFactorat (size_t i)
 
const sharedFactor operator[] (size_t i) const
 
sharedFactoroperator[] (size_t i)
 
const_iterator begin () const
 
const_iterator end () const
 
sharedFactor front () const
 
sharedFactor back () const
 
iterator begin ()
 
iterator end ()
 
void resize (size_t size)
 
void remove (size_t i)
 
void replace (size_t index, sharedFactor factor)
 
iterator erase (iterator item)
 
iterator erase (iterator first, iterator last)
 
size_t nrFactors () const
 
KeySet keys () const
 
KeyVector keyVector () const
 
bool exists (size_t idx) const
 
- Public Member Functions inherited from gtsam::EliminateableFactorGraph< DiscreteFactorGraph >
boost::shared_ptr< BayesTreeTypeeliminateMultifrontal (OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesTreeTypeeliminateMultifrontal (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesTreeTypeeliminateMultifrontal (const Ordering &ordering, const Eliminate &function, OptionalVariableIndex variableIndex, OptionalOrderingType orderingType) const
 
boost::shared_ptr< BayesTreeTypeeliminateMultifrontal (const Eliminate &function, OptionalVariableIndex variableIndex=boost::none, OptionalOrderingType orderingType=boost::none) const
 
std::pair< boost::shared_ptr< BayesTreeType >, boost::shared_ptr< FactorGraphType > > eliminatePartialMultifrontal (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
std::pair< boost::shared_ptr< BayesTreeType >, boost::shared_ptr< FactorGraphType > > eliminatePartialMultifrontal (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
std::pair< boost::shared_ptr< BayesNetType >, boost::shared_ptr< FactorGraphType > > eliminatePartialSequential (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
std::pair< boost::shared_ptr< BayesNetType >, boost::shared_ptr< FactorGraphType > > eliminatePartialSequential (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesNetTypeeliminateSequential (OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesNetTypeeliminateSequential (const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesNetTypeeliminateSequential (const Ordering &ordering, const Eliminate &function, OptionalVariableIndex variableIndex, OptionalOrderingType orderingType) const
 
boost::shared_ptr< BayesNetTypeeliminateSequential (const Eliminate &function, OptionalVariableIndex variableIndex=boost::none, OptionalOrderingType orderingType=boost::none) const
 
boost::shared_ptr< FactorGraphTypemarginal (const KeyVector &variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesNetTypemarginalMultifrontalBayesNet (boost::variant< const Ordering &, const KeyVector & > variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesNetTypemarginalMultifrontalBayesNet (boost::variant< const Ordering &, const KeyVector & > variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesNetTypemarginalMultifrontalBayesNet (boost::variant< const Ordering &, const KeyVector & > variables, boost::none_t, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesTreeTypemarginalMultifrontalBayesTree (boost::variant< const Ordering &, const KeyVector & > variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesTreeTypemarginalMultifrontalBayesTree (boost::variant< const Ordering &, const KeyVector & > variables, const Ordering &marginalizedVariableOrdering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 
boost::shared_ptr< BayesTreeTypemarginalMultifrontalBayesTree (boost::variant< const Ordering &, const KeyVector & > variables, boost::none_t, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
 

Private Types

typedef std::map< std::string, std::vector< double > > FacultyInArea
 

Private Attributes

std::vector< std::string > areaName_
 
std::string available_
 
FacultyInArea facultyInArea_
 
std::map< std::string, size_tfacultyIndex_
 
std::vector< std::string > facultyName_
 
size_t maxNrStudents_
 
std::vector< std::string > slotName_
 
std::vector< double > slotsAvailable_
 
std::vector< Studentstudents_
 

Additional Inherited Members

- Public Types inherited from gtsam::CSP
typedef KeyVector Indices
 
typedef boost::shared_ptr< ValuessharedValues
 
typedef Assignment< KeyValues
 
- Public Types inherited from gtsam::DiscreteFactorGraph
typedef FactorGraph< DiscreteFactorBase
 Typedef to base factor graph type. More...
 
typedef EliminateableFactorGraph< ThisBaseEliminateable
 Typedef to base elimination class. More...
 
typedef KeyVector Indices
 
typedef boost::shared_ptr< Thisshared_ptr
 shared_ptr to this class More...
 
typedef boost::shared_ptr< ValuessharedValues
 
typedef DiscreteFactorGraph This
 Typedef to this class. More...
 
typedef Assignment< KeyValues
 
- Public Types inherited from gtsam::FactorGraph< DiscreteFactor >
typedef FastVector< sharedFactor >::const_iterator const_iterator
 
typedef DiscreteFactor FactorType
 factor type More...
 
typedef FastVector< sharedFactor >::iterator iterator
 
typedef boost::shared_ptr< DiscreteFactorsharedFactor
 Shared pointer to a factor. More...
 
typedef sharedFactor value_type
 
- Public Types inherited from gtsam::EliminateableFactorGraph< DiscreteFactorGraph >
typedef EliminationTraitsType::BayesNetType BayesNetType
 Bayes net type produced by sequential elimination. More...
 
typedef EliminationTraitsType::BayesTreeType BayesTreeType
 Bayes tree type produced by multifrontal elimination. More...
 
typedef EliminationTraitsType::ConditionalType ConditionalType
 Conditional type stored in the Bayes net produced by elimination. More...
 
typedef boost::function< EliminationResult(const FactorGraphType &, const Ordering &)> Eliminate
 The function type that does a single dense elimination step on a subgraph. More...
 
typedef std::pair< boost::shared_ptr< ConditionalType >, boost::shared_ptr< _FactorType > > EliminationResult
 
typedef EliminationTraits< FactorGraphTypeEliminationTraitsType
 Typedef to the specific EliminationTraits for this graph. More...
 
typedef EliminationTraitsType::EliminationTreeType EliminationTreeType
 Elimination tree type that can do sequential elimination of this graph. More...
 
typedef EliminationTraitsType::JunctionTreeType JunctionTreeType
 Junction tree type that can do multifrontal elimination of this graph. More...
 
typedef boost::optional< Ordering::OrderingTypeOptionalOrderingType
 Typedef for an optional ordering type. More...
 
typedef boost::optional< const VariableIndex & > OptionalVariableIndex
 Typedef for an optional variable index as an argument to elimination functions. More...
 
- Protected Member Functions inherited from gtsam::FactorGraph< DiscreteFactor >
 FactorGraph ()
 
 FactorGraph (ITERATOR firstFactor, ITERATOR lastFactor)
 
 FactorGraph (const CONTAINER &factors)
 
- Protected Attributes inherited from gtsam::FactorGraph< DiscreteFactor >
FastVector< sharedFactorfactors_
 

Detailed Description

Scheduler class Creates one variable for each student, and three variables for each of the student's areas, for a total of 4*nrStudents variables. The "student" variable will determine when the student takes the qual. The "area" variables determine which faculty are on his/her committee.

Definition at line 21 of file Scheduler.h.

Member Typedef Documentation

typedef std::map<std::string, std::vector<double> > gtsam::Scheduler::FacultyInArea
private

area constraints

Definition at line 56 of file Scheduler.h.

Constructor & Destructor Documentation

gtsam::Scheduler::Scheduler ( size_t  maxNrStudents)
inline

Constructor We need to know the number of students in advance for ordering keys. then add faculty, slots, areas, availability, students, in that order

Definition at line 72 of file Scheduler.h.

virtual gtsam::Scheduler::~Scheduler ( )
inlinevirtual

Destructor.

Definition at line 75 of file Scheduler.h.

gtsam::Scheduler::Scheduler ( size_t  maxNrStudents,
const std::string &  filename 
)

Constructor that reads in faculty, slots, availibility. Still need to add areas and students after this

Definition at line 23 of file Scheduler.cpp.

Member Function Documentation

void gtsam::Scheduler::accumulateStats ( sharedValues  assignment,
std::vector< size_t > &  stats 
) const

Accumulate faculty stats

Definition at line 243 of file Scheduler.cpp.

void gtsam::Scheduler::addArea ( const std::string &  facultyName,
const std::string &  areaName 
)
inline

Definition at line 108 of file Scheduler.h.

void gtsam::Scheduler::addFaculty ( const std::string &  facultyName)
inline

Definition at line 77 of file Scheduler.h.

void gtsam::Scheduler::addSlot ( const std::string &  slotName)
inline

Definition at line 91 of file Scheduler.h.

void gtsam::Scheduler::addStudent ( const std::string &  studentName,
const std::string &  area1,
const std::string &  area2,
const std::string &  area3,
const std::string &  advisor 
)

addStudent has to be called after adding slots and faculty

Definition at line 60 of file Scheduler.cpp.

void gtsam::Scheduler::addStudentSpecificConstraints ( size_t  i,
boost::optional< size_t slot = boost::none 
)

Add student-specific constraints to the graph

Definition at line 105 of file Scheduler.cpp.

Scheduler::sharedValues gtsam::Scheduler::bestAssignment ( sharedValues  bestSchedule) const

find the corresponding most desirable committee assignment

Definition at line 293 of file Scheduler.cpp.

Scheduler::sharedValues gtsam::Scheduler::bestSchedule ( ) const

find the assignment of students to slots with most possible committees

Definition at line 286 of file Scheduler.cpp.

void gtsam::Scheduler::buildGraph ( size_t  mutexBound = 7)

Main routine that builds factor graph

Definition at line 152 of file Scheduler.cpp.

DiscreteBayesNet::shared_ptr gtsam::Scheduler::eliminate ( ) const

Eliminate, return a Bayes net

Definition at line 256 of file Scheduler.cpp.

const DiscreteKey & gtsam::Scheduler::key ( size_t  s,
boost::optional< size_t area = boost::none 
) const

get key for student and area, 0 is time slot itself

Definition at line 85 of file Scheduler.cpp.

size_t gtsam::Scheduler::nrFaculty ( ) const
inline

Definition at line 82 of file Scheduler.h.

size_t gtsam::Scheduler::nrStudents ( ) const
inline

current number of students

Definition at line 130 of file Scheduler.h.

size_t gtsam::Scheduler::nrTimeSlots ( ) const
inline

Definition at line 95 of file Scheduler.h.

Scheduler::sharedValues gtsam::Scheduler::optimalAssignment ( ) const

Find the best total assignment - can be expensive

Definition at line 269 of file Scheduler.cpp.

void gtsam::Scheduler::print ( const std::string &  s = "Scheduler",
const KeyFormatter formatter = DefaultKeyFormatter 
) const
overridevirtual

print

Reimplemented from gtsam::DiscreteFactorGraph.

Definition at line 181 of file Scheduler.cpp.

void gtsam::Scheduler::printAssignment ( sharedValues  assignment) const

Print readable form of assignment

Definition at line 215 of file Scheduler.cpp.

void gtsam::Scheduler::printSpecial ( sharedValues  assignment) const

Special print for single-student case

Definition at line 233 of file Scheduler.cpp.

void gtsam::Scheduler::setAvailability ( const std::string &  available)
inline

boolean std::string of nrTimeSlots * nrFaculty

Definition at line 87 of file Scheduler.h.

void gtsam::Scheduler::setSlotsAvailable ( const std::vector< double > &  slotsAvailable)
inline

slots available, boolean

Definition at line 104 of file Scheduler.h.

const std::string& gtsam::Scheduler::slotName ( size_t  s) const
inline

Definition at line 99 of file Scheduler.h.

const string & gtsam::Scheduler::studentArea ( size_t  i,
size_t  area 
) const

Definition at line 99 of file Scheduler.cpp.

const DiscreteKey & gtsam::Scheduler::studentKey ( size_t  i) const

Definition at line 94 of file Scheduler.cpp.

const string & gtsam::Scheduler::studentName ( size_t  i) const

Definition at line 89 of file Scheduler.cpp.

Member Data Documentation

std::vector<std::string> gtsam::Scheduler::areaName_
private

Definition at line 53 of file Scheduler.h.

std::string gtsam::Scheduler::available_
private

nrTimeSlots * nrFaculty availability constraints

Definition at line 60 of file Scheduler.h.

FacultyInArea gtsam::Scheduler::facultyInArea_
private

Definition at line 57 of file Scheduler.h.

std::map<std::string, size_t> gtsam::Scheduler::facultyIndex_
private

faculty identifiers

Definition at line 52 of file Scheduler.h.

std::vector<std::string> gtsam::Scheduler::facultyName_
private

Definition at line 53 of file Scheduler.h.

size_t gtsam::Scheduler::maxNrStudents_
private

Maximum number of students

Definition at line 46 of file Scheduler.h.

std::vector<std::string> gtsam::Scheduler::slotName_
private

Definition at line 53 of file Scheduler.h.

std::vector<double> gtsam::Scheduler::slotsAvailable_
private

which slots are good

Definition at line 63 of file Scheduler.h.

std::vector<Student> gtsam::Scheduler::students_
private

discrete keys, indexed by student and area index

Definition at line 49 of file Scheduler.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:27