#include <PNController.hpp>
Classes | |
struct | edge_writer |
struct | EdgeProperty |
struct | PlaceInfo |
struct | pn_writer |
struct | pn_writer2 |
struct | PNEdgeProperty |
struct | PNVertexProperty |
struct | VertexProperty |
Public Member Functions | |
void | addToGraph (const navcon_msgs::RegisterControllerRequest &info) |
void | addToPNGraph (const navcon_msgs::RegisterControllerRequest &info) |
void | addToRGraph (const std::string &name) |
void | addToRGraph2 (const std::string &name) |
void | get_firing (const std::string &name) |
void | get_firing_pn (const std::string &name) |
void | get_firing_r (const std::string &name) |
void | getDotDesc (std::string &desc) |
void | getDotDesc2 (std::string &desc) |
PNController () | |
void | reachability () |
Private Types | |
typedef boost::adjacency_list < boost::vecS, boost::vecS, boost::directedS, VertexProperty, boost::property < boost::edge_name_t, int > > | GraphType |
typedef boost::adjacency_list < boost::vecS, boost::vecS, boost::bidirectionalS, PNVertexProperty, boost::property < boost::edge_name_t, int > > | PNGraphType |
Private Member Functions | |
bool | firing_rec (int des_place, std::set< int > &skip_transitions, std::set< int > &visited_places) |
template<class PropertyMap , class NameMap > | |
edge_writer< PropertyMap, NameMap > | make_edge_writer (PropertyMap pmap, NameMap map) |
Private Attributes | |
std::vector < GraphType::vertex_descriptor > | all_idx |
std::vector< Eigen::VectorXi > | all_markings |
Eigen::MatrixXi | Dm |
Eigen::MatrixXi | Dp |
std::vector< int > | firing_seq |
Eigen::MatrixXi | I |
Eigen::VectorXi | marking |
std::map< std::string, PlaceInfo > | nameMap |
std::map< int, std::string > | placeMap |
std::map< int, int > | placeToVertexMap |
PNGraphType | pngraph |
int | pnum |
std::vector< int > | resourcePosition |
GraphType | rgraph |
GraphType | rgraph2 |
int | tnum |
std::map< int, std::string > | transitionMap |
The class contains implementation of Petri-Net builder and controller.
Add multiple desired places setup
Add place turn-off option
Add additional state enabled place in parallel with the control place.
Add weighted transitions for multi DOF controllers ?
Add simulation step for activation to detect wrong firing sequences.
Extract reachability graph building and ploting
Extract debugging information and structure it in a debug class
Possible optimizations: Incremental graph building
Possible optimizations: BFS only on a subset of the graph ?
Possible optimizations: Spin-off BFS for the new state in a thread to have it ready in advance
Recommended optimizations: Reachability calculation memory/time/copying/std::find usage
Add detection of faulty controller registrations or setups. -analyze if they have indirect dependencies to DOFs
Possible optimizations: Find sequences that can fire simultaneously
Definition at line 68 of file PNController.hpp.
typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, VertexProperty, boost::property<boost::edge_name_t, int> > labust::control::PNController::GraphType [private] |
Definition at line 188 of file PNController.hpp.
typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS, PNVertexProperty, boost::property<boost::edge_name_t, int> > labust::control::PNController::PNGraphType [private] |
Definition at line 208 of file PNController.hpp.
Main constructor
Definition at line 49 of file PNController.cpp.
void PNController::addToGraph | ( | const navcon_msgs::RegisterControllerRequest & | info | ) |
Add controller to the petri-net.
Definition at line 72 of file PNController.cpp.
void PNController::addToPNGraph | ( | const navcon_msgs::RegisterControllerRequest & | info | ) |
Calculates the pn graph incrementaly.
Definition at line 683 of file PNController.cpp.
void PNController::addToRGraph | ( | const std::string & | name | ) |
Calculates the reachability graph incrementaly.
Definition at line 917 of file PNController.cpp.
void PNController::addToRGraph2 | ( | const std::string & | name | ) |
Calculates the reachability graph incrementaly.
Definition at line 732 of file PNController.cpp.
bool PNController::firing_rec | ( | int | des_place, |
std::set< int > & | skip_transitions, | ||
std::set< int > & | visited_places | ||
) | [private] |
Firing sequence recursive calculation.
Definition at line 122 of file PNController.cpp.
void PNController::get_firing | ( | const std::string & | name | ) |
Get the firing sequence for the named controller.
Definition at line 243 of file PNController.cpp.
void PNController::get_firing_pn | ( | const std::string & | name | ) |
Get the firing sequence for the named controller by reverse graph search.
Definition at line 460 of file PNController.cpp.
void PNController::get_firing_r | ( | const std::string & | name | ) |
Get the firing sequence for the named controller.
Definition at line 333 of file PNController.cpp.
void PNController::getDotDesc | ( | std::string & | desc | ) |
Get the reachability graph DOT description.
Definition at line 1146 of file PNController.cpp.
void PNController::getDotDesc2 | ( | std::string & | desc | ) |
Get the reachability graph DOT description.
Definition at line 1159 of file PNController.cpp.
edge_writer<PropertyMap, NameMap> labust::control::PNController::make_edge_writer | ( | PropertyMap | pmap, |
NameMap | map | ||
) | [inline, private] |
Definition at line 261 of file PNController.hpp.
void PNController::reachability | ( | ) |
Calculates the reachability graph.
Definition at line 1054 of file PNController.cpp.
std::vector<GraphType::vertex_descriptor> labust::control::PNController::all_idx [private] |
Definition at line 272 of file PNController.hpp.
std::vector<Eigen::VectorXi> labust::control::PNController::all_markings [private] |
Definition at line 271 of file PNController.hpp.
Eigen::MatrixXi labust::control::PNController::Dm [private] |
PN matrices.
Definition at line 144 of file PNController.hpp.
Eigen::MatrixXi labust::control::PNController::Dp [private] |
Definition at line 144 of file PNController.hpp.
std::vector<int> labust::control::PNController::firing_seq [private] |
The last firing sequence.
Definition at line 160 of file PNController.hpp.
Eigen::MatrixXi labust::control::PNController::I [private] |
Definition at line 144 of file PNController.hpp.
Eigen::VectorXi labust::control::PNController::marking [private] |
Definition at line 148 of file PNController.hpp.
std::map<std::string, PlaceInfo> labust::control::PNController::nameMap [private] |
Helper name to p/t mapping.
Definition at line 156 of file PNController.hpp.
std::map<int, std::string> labust::control::PNController::placeMap [private] |
Helper maps for debugging.
Definition at line 152 of file PNController.hpp.
std::map<int, int> labust::control::PNController::placeToVertexMap [private] |
Definition at line 269 of file PNController.hpp.
Definition at line 267 of file PNController.hpp.
int labust::control::PNController::pnum [private] |
The place and transition number.
Definition at line 140 of file PNController.hpp.
std::vector<int> labust::control::PNController::resourcePosition [private] |
The current resource position.
Definition at line 164 of file PNController.hpp.
Definition at line 266 of file PNController.hpp.
Definition at line 266 of file PNController.hpp.
int labust::control::PNController::tnum [private] |
Definition at line 140 of file PNController.hpp.
std::map<int, std::string> labust::control::PNController::transitionMap [private] |
Definition at line 152 of file PNController.hpp.