Go to the documentation of this file.00001
00025 #include <predicate_manager/predicate.h>
00026
00027 #include <ros/ros.h>
00028
00029 using namespace std;
00030 using namespace predicate_manager;
00031
00032
00033 Predicate::
00034 Predicate ( const string& name,
00035 const Dependencies& deps,
00036 bool initial_value ) :
00037 PredicateDependentEntity ( deps ),
00038 name_ ( name ),
00039 value_ ( initial_value ),
00040 trigger_ (),
00041 requested_updates_ ( 0 )
00042 {}
00043
00044 Predicate::
00045 Predicate ( const string& name,
00046 bool initial_value ) :
00047 PredicateDependentEntity(),
00048 name_ ( name ),
00049 value_ ( initial_value ),
00050 trigger_ (),
00051 requested_updates_ ( 0 )
00052 {}
00053
00054 void
00055 Predicate::
00056 setValue ( bool val )
00057 {
00058 if ( value_ != val )
00059 {
00060 if ( requested_updates_ > 0 )
00061 {
00062 ROS_WARN_STREAM ( "Predicate " << name_ << " is part of a cyclic dependency." );
00063 }
00064
00065 if ( requested_updates_ > MAX_CYCLIC_UPDATES )
00066 {
00067 ROS_FATAL_STREAM ( "Predicate " << name_ << " is in a livelock. Terminating." );
00068 ros::shutdown();
00069 }
00070
00071 requested_updates_++;
00072
00073 value_ = val;
00074
00075 if ( trigger_ )
00076 trigger_ ( value_ );
00077 else
00078 ROS_WARN_STREAM ( "Predicate " << name_ << " changed its value, but it is not bound to any Predicate manager." );
00079
00080 requested_updates_--;
00081 }
00082 }
00083
00084 std::string Predicate::getName()
00085 {
00086 return name_;
00087 }
00088
00089 bool Predicate::getValue()
00090 {
00091 return value_;
00092 }
00093
00094 std::string Predicate::setName ( const std::string& new_name )
00095 {
00096 name_ = new_name;
00097 }
00098
00099 void Predicate::setTrigger ( const boost::function<void ( bool ) > trigger )
00100 {
00101 trigger_ = trigger;
00102 }