#include <state_layer.h>
Definition at line 42 of file state_layer.h.
typedef boost::shared_ptr<std::set<uint32_t> > mdm_library::StateLayer::SFIDSetPtr |
Definition at line 45 of file state_layer.h.
Definition at line 38 of file state_layer.cpp.
void StateLayer::addStateFactor | ( | const StateDep::SFDeps & | deps | ) |
factor index is factored_state_.size()
Definition at line 165 of file state_layer.cpp.
void StateLayer::addStateFactor | ( | const StateDep & | deps | ) |
Definition at line 186 of file state_layer.cpp.
std::string StateLayer::factorString | ( | unsigned | k | ) | [private] |
binary state factor
mutually-exclusive-valued state factor
Definition at line 105 of file state_layer.cpp.
void StateLayer::predicateMapCallback | ( | const predicate_manager::PredicateInfoMapConstPtr & | msg | ) |
name_id has been registered as the dependency of some SF
now we can access the value by the NrID instead
Definition at line 144 of file state_layer.cpp.
void StateLayer::predicateUpdatesCallback | ( | const predicate_manager::PredicateUpdateConstPtr & | msg | ) |
Definition at line 48 of file state_layer.cpp.
void StateLayer::publishJointState | ( | ) | [private] |
Definition at line 195 of file state_layer.cpp.
void StateLayer::updateStateInfo | ( | const uint32_t & | factor | ) | [private] |
Definition at line 223 of file state_layer.cpp.
std::vector<uint32_t> mdm_library::StateLayer::factored_state_ [private] |
Definition at line 79 of file state_layer.h.
std::vector<StateDep::SFDeps> mdm_library::StateLayer::factored_state_deps_ [private] |
Definition at line 77 of file state_layer.h.
boost::unordered_map<predicate_manager::NameID, SFIDSetPtr > mdm_library::StateLayer::named_pred_observer_ [private] |
Definition at line 75 of file state_layer.h.
boost::unordered_map<predicate_manager::NameID, boost::shared_ptr<bool> > mdm_library::StateLayer::named_value_map_ [private] |
Definition at line 69 of file state_layer.h.
ros::NodeHandle mdm_library::StateLayer::nh_ [private] |
Definition at line 60 of file state_layer.h.
boost::unordered_map<predicate_manager::NrID, SFIDSetPtr, predicate_manager::cantor_pair_hash> mdm_library::StateLayer::nr_pred_observer_ [private] |
Definition at line 74 of file state_layer.h.
boost::unordered_map<predicate_manager::NrID, boost::shared_ptr<bool>, predicate_manager::cantor_pair_hash> mdm_library::StateLayer::nr_value_map_ [private] |
Definition at line 68 of file state_layer.h.
Definition at line 61 of file state_layer.h.
Definition at line 62 of file state_layer.h.
Definition at line 63 of file state_layer.h.
Definition at line 64 of file state_layer.h.