#include <ExecControl.hpp>
Classes | |
struct | ControllerInfo |
struct | REdgeProperty |
struct | RVertexProperty |
struct | VertexProperty |
Public Member Functions | |
void | add_pn_edge (int i, int j, GraphType &graph) |
void | addToGraph (const std::string &name="") |
void | addToMatrix (const std::string &name) |
ExecControl () | |
void | find_path () |
bool | firing_rec (int des_place, std::vector< int > &skip_transitions, std::vector< int > &visited_places) |
bool | firing_rec2 (int des_place, std::vector< int > &skip_transitions, std::vector< int > &visited_places) |
void | get_firing (const std::string &name) |
void | get_firing2 (const std::string &name) |
void | onActivateController (const std_msgs::String::ConstPtr &name) |
void | onInit () |
bool | onRegisterController (navcon_msgs::RegisterController::Request &req, navcon_msgs::RegisterController::Response &resp) |
void | reachability () |
Public Attributes | |
ros::Subscriber | activateController |
std::list< std::string > | active_cnt |
std::string | active_dof [6] |
ControllerMap | controllers |
ExecDepGraph | depGraph |
ros::Publisher | depGraphPub |
Eigen::MatrixXi | Dm |
Eigen::MatrixXi | Dp |
std::vector< int > | firing_seq |
GraphType | graph |
Eigen::VectorXi | marking |
std::vector< std::string > | names |
std::map< int, std::string > | pname |
PNController | pnCon |
ExecPNGraph | pnGraph |
ros::Publisher | pnGraphPub |
int | pnum |
ros::ServiceServer | registerController |
RGraphType | rgraph |
int | tnum |
Private Types | |
enum | { u = 0, v, w, p, q, r } |
enum | { X = 0, Y, Z, K, M, N } |
enum | { alpha = 0, beta, betaa } |
enum | { Kp = 0, Ki, Kd, Kt } |
typedef struct labust::control::ExecControl::ControllerInfo | ControllerInfo |
typedef std::map< std::string, ControllerInfo > | ControllerMap |
typedef boost::adjacency_list < boost::vecS, boost::vecS, boost::directedS, VertexProperty, boost::property < boost::edge_weight_t, int > > | GraphType |
typedef boost::adjacency_list < boost::vecS, boost::vecS, boost::directedS, RVertexProperty, REdgeProperty > | RGraphType |
The class contains the implementation of the execution controller that manages different controller dependencies and tracks variable publishing for safety applications.
Add full dependency check.
Add unregister controller option.
Remove the named maps form helper classes and pass only the controller id number to classes.
When everythin is working, build dep and pn graphs directly from the petri-net matrices
Definition at line 67 of file ExecControl.hpp.
typedef struct labust::control::ExecControl::ControllerInfo labust::control::ExecControl::ControllerInfo [private] |
typedef std::map<std::string, ControllerInfo> labust::control::ExecControl::ControllerMap [private] |
Definition at line 87 of file ExecControl.hpp.
typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, VertexProperty, boost::property < boost::edge_weight_t, int > > labust::control::ExecControl::GraphType [private] |
Definition at line 120 of file ExecControl.hpp.
typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, RVertexProperty, REdgeProperty > labust::control::ExecControl::RGraphType [private] |
Definition at line 124 of file ExecControl.hpp.
anonymous enum [private] |
Definition at line 69 of file ExecControl.hpp.
anonymous enum [private] |
Definition at line 70 of file ExecControl.hpp.
anonymous enum [private] |
Definition at line 71 of file ExecControl.hpp.
anonymous enum [private] |
Definition at line 72 of file ExecControl.hpp.
Main constructor
Definition at line 49 of file ExecControl.cpp.
void labust::control::ExecControl::add_pn_edge | ( | int | i, |
int | j, | ||
GraphType & | graph | ||
) |
Helper method for ensuring PetriNet connections. It is always i->j
void labust::control::ExecControl::addToGraph | ( | const std::string & | name = "" | ) |
Builds the petri net graph.
void ExecControl::addToMatrix | ( | const std::string & | name | ) |
Add to PN matrix.
Definition at line 157 of file ExecControl.cpp.
The helper function to find graph transitions.
bool ExecControl::firing_rec | ( | int | des_place, |
std::vector< int > & | skip_transitions, | ||
std::vector< int > & | visited_places | ||
) |
Helper recursion function
Definition at line 349 of file ExecControl.cpp.
bool ExecControl::firing_rec2 | ( | int | des_place, |
std::vector< int > & | skip_transitions, | ||
std::vector< int > & | visited_places | ||
) |
Definition at line 240 of file ExecControl.cpp.
void ExecControl::get_firing | ( | const std::string & | name | ) |
Calculates the firing sequence to enable a desired controller.
Definition at line 351 of file ExecControl.cpp.
void ExecControl::get_firing2 | ( | const std::string & | name | ) |
Definition at line 354 of file ExecControl.cpp.
void ExecControl::onActivateController | ( | const std_msgs::String::ConstPtr & | name | ) |
Activate controller tester.
Definition at line 213 of file ExecControl.cpp.
void ExecControl::onInit | ( | ) |
Initialize and setup controller.
Definition at line 57 of file ExecControl.cpp.
bool ExecControl::onRegisterController | ( | navcon_msgs::RegisterController::Request & | req, |
navcon_msgs::RegisterController::Response & | resp | ||
) |
Performs one iteration. Start the controller loop. Handle incoming reference message. Handle incoming estimates message. Handle incoming estimates message. Handle incoming estimates message. Handle incoming estimates message. Handle controller registration.
Definition at line 80 of file ExecControl.cpp.
void ExecControl::reachability | ( | ) |
Calculates the reachability graph.
Definition at line 384 of file ExecControl.cpp.
The subscribed topics.
Definition at line 283 of file ExecControl.hpp.
std::list<std::string> labust::control::ExecControl::active_cnt |
Active controllers.
Definition at line 316 of file ExecControl.hpp.
std::string labust::control::ExecControl::active_dof[6] |
Active dofs.
Definition at line 312 of file ExecControl.hpp.
The dynamic reconfigure parameters. The dynamic reconfigure server. Variable access helper mass. The controller map.
Definition at line 304 of file ExecControl.hpp.
The dependency graph tool.
Definition at line 352 of file ExecControl.hpp.
Handle the enable control request. Dynamic reconfigure callback. The safety test. Update the dynamic reconfiguration settings. Perform the identification step. The ROS node handles. Last message times. Timeout Initialize the controller parameters etc. The velocity controllers. The identification controllers. The mesurement needed for identification. Joystick message. Joystick scaling. Enable/disable controllers, external windup flag. Timeout management. Dynamic reconfigure server. The publisher of the TAU message.
Definition at line 279 of file ExecControl.hpp.
Eigen::MatrixXi labust::control::ExecControl::Dm |
PN matrices.
Definition at line 336 of file ExecControl.hpp.
Eigen::MatrixXi labust::control::ExecControl::Dp |
Definition at line 336 of file ExecControl.hpp.
The last firing sequence.
Definition at line 348 of file ExecControl.hpp.
The controller dependency graph.
Definition at line 320 of file ExecControl.hpp.
Eigen::VectorXi labust::control::ExecControl::marking |
Definition at line 340 of file ExecControl.hpp.
std::vector<std::string> labust::control::ExecControl::names |
The controller names list.
Definition at line 308 of file ExecControl.hpp.
std::map<int, std::string> labust::control::ExecControl::pname |
Map placenum to name.
Definition at line 344 of file ExecControl.hpp.
The Petri-Net controller.
Definition at line 360 of file ExecControl.hpp.
The petri-net graph tool.
Definition at line 356 of file ExecControl.hpp.
Definition at line 279 of file ExecControl.hpp.
The place num.
Definition at line 332 of file ExecControl.hpp.
High level controller service.
Definition at line 287 of file ExecControl.hpp.
The reachability graph
Definition at line 324 of file ExecControl.hpp.
The transition number.
Definition at line 328 of file ExecControl.hpp.