#include <dynamic_parameters.h>
| Public Member Functions | |
| DynamicParameters () | |
| void | finalize () | 
| void | get (const std::string &name, float &variable, const float default_value, const std::string description="None.", const float min=-100, const float max=100) | 
| void | get (const std::string &name, FloatParam &variable, const float default_value, const std::string description="None.", const float min=-100, const float max=100) | 
| void | get (const std::string &name, double &variable, const double default_value, const std::string description="None.", const double min=-100, const double max=100) | 
| void | get (const std::string &name, DoubleParam &variable, const double default_value, const std::string description="None.", const double min=-100, const double max=100) | 
| void | get (const std::string &name, int &variable, const int default_value, const std::string description="None.", const int min=-100, const int max=100) | 
| void | get (const std::string &name, IntParam &variable, const int default_value, const std::string description="None.", const int min=-100, const int max=100) | 
| void | get (const std::string &name, bool &variable, const bool default_value, const std::string description="None.") | 
| void | get (const std::string &name, BoolParam &variable, const bool default_value, const std::string description="None.") | 
| void | get (const std::string &name, std::string &variable, const std::string default_value, const std::string description="None.") | 
| void | get (const std::string &name, StringParam &variable, const std::string default_value, const std::string description="None.") | 
| bool | getBool (const std::string &name) | 
| double | getDouble (const std::string &name) | 
| float | getFloat (const std::string &name) | 
| int | getInt (const std::string &name) | 
| std::string | getString (const std::string &name) | 
| void | initialize (ros::NodeHandle &pnh) | 
| boost::mutex::scoped_lock | lock_guard () | 
| boost::mutex & | mutex () | 
| void | setCallback (boost::function< void(DynamicParameters &)> fun) | 
| Private Member Functions | |
| bool | setConfigCallback (dynamic_reconfigure::Reconfigure::Request &req, dynamic_reconfigure::Reconfigure::Response &rsp) | 
| void | updateCurrent (dynamic_reconfigure::Config &config) | 
| Private Attributes | |
| ros::Publisher | descr_pub_ | 
| boost::shared_ptr< boost::mutex > | mutex_ | 
| ros::NodeHandle | nh_ | 
| boost::function< void(DynamicParameters &)> | on_change_ | 
| ros::ServiceServer | set_service_ | 
| ros::Publisher | update_pub_ | 
| std::map< std::string, DynamicValue > | values_ | 
Definition at line 119 of file dynamic_parameters.h.
| swri::DynamicParameters::DynamicParameters | ( | ) |  [inline] | 
Definition at line 288 of file dynamic_parameters.h.
| void swri::DynamicParameters::finalize | ( | ) |  [inline] | 
Definition at line 304 of file dynamic_parameters.h.
| void swri::DynamicParameters::get | ( | const std::string & | name, | 
| float & | variable, | ||
| const float | default_value, | ||
| const std::string | description = "None.", | ||
| const float | min = -100, | ||
| const float | max = 100 | ||
| ) |  [inline] | 
Definition at line 519 of file dynamic_parameters.h.
| void swri::DynamicParameters::get | ( | const std::string & | name, | 
| FloatParam & | variable, | ||
| const float | default_value, | ||
| const std::string | description = "None.", | ||
| const float | min = -100, | ||
| const float | max = 100 | ||
| ) |  [inline] | 
Definition at line 543 of file dynamic_parameters.h.
| void swri::DynamicParameters::get | ( | const std::string & | name, | 
| double & | variable, | ||
| const double | default_value, | ||
| const std::string | description = "None.", | ||
| const double | min = -100, | ||
| const double | max = 100 | ||
| ) |  [inline] | 
Definition at line 570 of file dynamic_parameters.h.
| void swri::DynamicParameters::get | ( | const std::string & | name, | 
| DoubleParam & | variable, | ||
| const double | default_value, | ||
| const std::string | description = "None.", | ||
| const double | min = -100, | ||
| const double | max = 100 | ||
| ) |  [inline] | 
Definition at line 594 of file dynamic_parameters.h.
| void swri::DynamicParameters::get | ( | const std::string & | name, | 
| int & | variable, | ||
| const int | default_value, | ||
| const std::string | description = "None.", | ||
| const int | min = -100, | ||
| const int | max = 100 | ||
| ) |  [inline] | 
Definition at line 620 of file dynamic_parameters.h.
| void swri::DynamicParameters::get | ( | const std::string & | name, | 
| IntParam & | variable, | ||
| const int | default_value, | ||
| const std::string | description = "None.", | ||
| const int | min = -100, | ||
| const int | max = 100 | ||
| ) |  [inline] | 
Definition at line 644 of file dynamic_parameters.h.
| void swri::DynamicParameters::get | ( | const std::string & | name, | 
| bool & | variable, | ||
| const bool | default_value, | ||
| const std::string | description = "None." | ||
| ) |  [inline] | 
Definition at line 671 of file dynamic_parameters.h.
| void swri::DynamicParameters::get | ( | const std::string & | name, | 
| BoolParam & | variable, | ||
| const bool | default_value, | ||
| const std::string | description = "None." | ||
| ) |  [inline] | 
Definition at line 691 of file dynamic_parameters.h.
| void swri::DynamicParameters::get | ( | const std::string & | name, | 
| std::string & | variable, | ||
| const std::string | default_value, | ||
| const std::string | description = "None." | ||
| ) |  [inline] | 
Definition at line 714 of file dynamic_parameters.h.
| void swri::DynamicParameters::get | ( | const std::string & | name, | 
| StringParam & | variable, | ||
| const std::string | default_value, | ||
| const std::string | description = "None." | ||
| ) |  [inline] | 
Definition at line 734 of file dynamic_parameters.h.
| bool swri::DynamicParameters::getBool | ( | const std::string & | name | ) |  [inline] | 
Definition at line 469 of file dynamic_parameters.h.
| double swri::DynamicParameters::getDouble | ( | const std::string & | name | ) |  [inline] | 
Definition at line 416 of file dynamic_parameters.h.
| float swri::DynamicParameters::getFloat | ( | const std::string & | name | ) |  [inline] | 
Definition at line 434 of file dynamic_parameters.h.
| int swri::DynamicParameters::getInt | ( | const std::string & | name | ) |  [inline] | 
Definition at line 451 of file dynamic_parameters.h.
| std::string swri::DynamicParameters::getString | ( | const std::string & | name | ) |  [inline] | 
Definition at line 487 of file dynamic_parameters.h.
| void swri::DynamicParameters::initialize | ( | ros::NodeHandle & | pnh | ) |  [inline] | 
Definition at line 294 of file dynamic_parameters.h.
| boost::mutex::scoped_lock swri::DynamicParameters::lock_guard | ( | ) |  [inline] | 
Definition at line 512 of file dynamic_parameters.h.
| boost::mutex& swri::DynamicParameters::mutex | ( | ) |  [inline] | 
Definition at line 506 of file dynamic_parameters.h.
| void swri::DynamicParameters::setCallback | ( | boost::function< void(DynamicParameters &)> | fun | ) |  [inline] | 
Definition at line 410 of file dynamic_parameters.h.
| bool swri::DynamicParameters::setConfigCallback | ( | dynamic_reconfigure::Reconfigure::Request & | req, | 
| dynamic_reconfigure::Reconfigure::Response & | rsp | ||
| ) |  [inline, private] | 
Definition at line 133 of file dynamic_parameters.h.
| void swri::DynamicParameters::updateCurrent | ( | dynamic_reconfigure::Config & | config | ) |  [inline, private] | 
Definition at line 236 of file dynamic_parameters.h.
Definition at line 121 of file dynamic_parameters.h.
| boost::shared_ptr<boost::mutex> swri::DynamicParameters::mutex_  [private] | 
Definition at line 131 of file dynamic_parameters.h.
| ros::NodeHandle swri::DynamicParameters::nh_  [private] | 
Definition at line 124 of file dynamic_parameters.h.
| boost::function<void(DynamicParameters&)> swri::DynamicParameters::on_change_  [private] | 
Definition at line 128 of file dynamic_parameters.h.
Definition at line 123 of file dynamic_parameters.h.
Definition at line 122 of file dynamic_parameters.h.
| std::map<std::string, DynamicValue> swri::DynamicParameters::values_  [private] | 
Definition at line 126 of file dynamic_parameters.h.