Go to the documentation of this file.00001
00026 #include <topological_tools/topological_predicate.h>
00027
00028
00029 using namespace std;
00030 using namespace ros;
00031 using namespace predicate_manager;
00032 using namespace topological_tools;
00033
00034
00035 TopologicalPredicate::
00036 TopologicalPredicate ( const string& label_topic,
00037 const string& name ) :
00038 Predicate ( name ),
00039 label_subs_ ( nh_.subscribe ( label_topic, 1, &TopologicalPredicate::labelCallback, this ) )
00040 {
00041 nh_.getParam ( "predicate_labels/" + getName(), ( int& ) target_label_ );
00042 }
00043
00044 TopologicalPredicate::TopologicalPredicate ( const string& label_topic,
00045 const string& name,
00046 const uint32_t target_label ) :
00047 Predicate ( name ),
00048 label_subs_ ( nh_.subscribe ( label_topic, 1, &TopologicalPredicate::labelCallback, this ) ),
00049 target_label_ ( target_label )
00050 {}
00051
00052 void TopologicalPredicate::labelCallback ( const PoseLabelConstPtr& msg )
00053 {
00054 received_label_ = msg->label;
00055 update();
00056 }
00057
00058 void TopologicalPredicate::update()
00059 {
00060 setValue ( received_label_ == target_label_ );
00061 }