param.h File Reference

#include "forwards.h"
#include "XmlRpcValue.h"
Include dependency graph for param.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  ros
namespace  ros::param
 

Contains functions which allow you to query the parameter server.


Functions

bool ros::param::del (const std::string &key)
 Delete a parameter from the parameter server.
bool ros::param::get (const std::string &key, XmlRpc::XmlRpcValue &v)
 Get an arbitrary XML/RPC value from the parameter server.
bool ros::param::get (const std::string &key, bool &b)
 Get a boolean value from the parameter server.
bool ros::param::get (const std::string &key, int &i)
 Get a integer value from the parameter server.
bool ros::param::get (const std::string &key, double &d)
 Get a double value from the parameter server.
bool ros::param::get (const std::string &key, std::string &s)
 Get a string value from the parameter server.
bool ros::param::getCached (const std::string &key, XmlRpc::XmlRpcValue &v)
 Get an arbitrary XML/RPC value from the parameter server, with local caching.
bool ros::param::getCached (const std::string &key, bool &b)
 Get a boolean value from the parameter server, with local caching.
bool ros::param::getCached (const std::string &key, int &i)
 Get a integer value from the parameter server, with local caching.
bool ros::param::getCached (const std::string &key, double &d)
 Get a double value from the parameter server, with local caching.
bool ros::param::getCached (const std::string &key, std::string &s)
 Get a string value from the parameter server, with local caching.
bool ros::param::has (const std::string &key)
 Check whether a parameter exists on the parameter server.
template<typename T >
void ros::param::param (const std::string &param_name, T &param_val, const T &default_val)
 Assign value from parameter server, with default.
bool ros::param::search (const std::string &key, std::string &result)
 Search up the tree for a parameter with a given key. This version defaults to starting in the current node's name.
bool ros::param::search (const std::string &ns, const std::string &key, std::string &result)
 Search up the tree for a parameter with a given key.
void ros::param::set (const std::string &key, bool b)
 Set a integer value on the parameter server.
void ros::param::set (const std::string &key, int i)
 Set a integer value on the parameter server.
void ros::param::set (const std::string &key, double d)
 Set a double value on the parameter server.
void ros::param::set (const std::string &key, const char *s)
 Set a string value on the parameter server.
void ros::param::set (const std::string &key, const std::string &s)
 Set a string value on the parameter server.
void ros::param::set (const std::string &key, const XmlRpc::XmlRpcValue &v)
 Set an arbitrary XML/RPC value on the parameter server.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


roscpp
Author(s): Morgan Quigley mquigley@cs.stanford.edu, Josh Faust jfaust@willowgarage.com, Brian Gerkey gerkey@willowgarage.com
autogenerated on Fri Jan 11 10:08:18 2013