Classes | Functions | Variables
swri Namespace Reference

Classes

class  BindSubscriberImpl
class  LatchedSubscriber
class  OptionalDiagnosedPublisher
class  ServiceServer
class  ServiceServerImpl
class  ServiceServerStatistics
class  StorageSubscriberImpl
class  Subscriber
class  SubscriberImpl
class  Timer
class  TimerImpl
struct  TrueType
class  TypedServiceServerImpl
class  TypedSubscriberImpl
class  TypedTimerImpl

Functions

template<typename M >
ros::Publisher advertise (ros::NodeHandle &nh, const std::string name, uint32_t queue_size, bool latched=false)
int comparePrefix (std::string const &string, std::string const &prefix)
static bool getParam (const ros::NodeHandle &nh, const std::string &name, int &variable)
static bool getParam (const ros::NodeHandle &nh, const std::string &name, double &variable)
static bool getParam (const ros::NodeHandle &nh, const std::string &name, float &variable)
static bool getParam (const ros::NodeHandle &nh, const std::string &name, std::string &variable)
static bool getParam (const ros::NodeHandle &nh, const std::string &name, bool &variable)
static std::vector< std::string > getUnusedParamKeys (ros::NodeHandle const &n)
bool isPrefixOf (std::string const &string, std::string const &prefix)
static void param (const ros::NodeHandle &nh, const std::string &name, int &variable, const int default_value)
static void param (const ros::NodeHandle &nh, const std::string &name, double &variable, const double default_value)
static void param (const ros::NodeHandle &nh, const std::string &name, float &variable, const float default_value)
static void param (const ros::NodeHandle &nh, const std::string &name, std::string &variable, const std::string default_value)
static void param (const ros::NodeHandle &nh, const std::string &name, bool &variable, const bool default_value)
int prefixLessThan (std::string const &string, std::string const &prefix)
static void warnUnusedParams (ros::NodeHandle const &n)

Variables

static std::set< std::string > _used_params

Function Documentation

template<typename M >
ros::Publisher swri::advertise ( ros::NodeHandle nh,
const std::string  name,
uint32_t  queue_size,
bool  latched = false 
)

Definition at line 37 of file publisher.h.

int swri::comparePrefix ( std::string const &  string,
std::string const &  prefix 
) [inline]

Determines whether `prefix` is a prefix of `string`.

Parameters:
stringThe longer string to check, which may begin with the characters of `prefix`.
prefixThe shorter string, which may be a prefix of `string`.
Returns:
0 if the first n characters of `string` are identical to `prefix`, where n is the length of `prefix`. 1 or -1 otherwise, according to the conventions of std::string::compare()

Definition at line 172 of file parameters.h.

static bool swri::getParam ( const ros::NodeHandle nh,
const std::string &  name,
int &  variable 
) [inline, static]

Definition at line 22 of file parameters.h.

static bool swri::getParam ( const ros::NodeHandle nh,
const std::string &  name,
double &  variable 
) [inline, static]

Definition at line 38 of file parameters.h.

static bool swri::getParam ( const ros::NodeHandle nh,
const std::string &  name,
float &  variable 
) [inline, static]

Definition at line 54 of file parameters.h.

static bool swri::getParam ( const ros::NodeHandle nh,
const std::string &  name,
std::string &  variable 
) [inline, static]

Definition at line 70 of file parameters.h.

static bool swri::getParam ( const ros::NodeHandle nh,
const std::string &  name,
bool &  variable 
) [inline, static]

Definition at line 86 of file parameters.h.

static std::vector<std::string> swri::getUnusedParamKeys ( ros::NodeHandle const &  n) [inline, static]

Gets the list of parameters on the parameter server in the namespace of NodeHandle n that have not yet been got using any of the swri::param() or swri::getParam() functions.

The parameter keys are filtered by prefix, so if there exists a parameter /foo/bar/baz and parameter /foo/bar has been got, then /foo/bar/baz will not be returned as an unused parameter.

Note that this function has no way of knowing about parameters got using the ros::param() and ros::getParam() functions.

Parameters:
nNodehandle defining the namespace to restrict the list
Returns:
A vector of fully-qualified parameter names in n's namespace that haven't been got.

Definition at line 224 of file parameters.h.

bool swri::isPrefixOf ( std::string const &  string,
std::string const &  prefix 
) [inline]

Boolean wrapper around comparePrefix.

Parameters:
stringThe longer string to check, which may begin with the characters of `prefix`.
prefixThe shorter string, which may be a prefix of `string`.
Returns:
True if the first n characters of `string` are identical to `prefix`, where n is the length of `prefix`, false otherwise.

Definition at line 186 of file parameters.h.

static void swri::param ( const ros::NodeHandle nh,
const std::string &  name,
int &  variable,
const int  default_value 
) [inline, static]

Definition at line 102 of file parameters.h.

static void swri::param ( const ros::NodeHandle nh,
const std::string &  name,
double &  variable,
const double  default_value 
) [inline, static]

Definition at line 114 of file parameters.h.

static void swri::param ( const ros::NodeHandle nh,
const std::string &  name,
float &  variable,
const float  default_value 
) [inline, static]

Definition at line 126 of file parameters.h.

static void swri::param ( const ros::NodeHandle nh,
const std::string &  name,
std::string &  variable,
const std::string  default_value 
) [inline, static]

Definition at line 139 of file parameters.h.

static void swri::param ( const ros::NodeHandle nh,
const std::string &  name,
bool &  variable,
const bool  default_value 
) [inline, static]

Definition at line 151 of file parameters.h.

int swri::prefixLessThan ( std::string const &  string,
std::string const &  prefix 
) [inline]

Less-than wrapper around comparePrefix, for algorithms that require a less-than comparator, such as sorting.

Parameters:
stringThe longer string to check, which may begin with the characters of `prefix`.
prefixThe shorter string, which may be a prefix of `string`.
Returns:
True if the first n characters of `string` are "less than" the first n to `prefix`, where n is the length of `prefix`, according to the conventions of std::string::compare(). False otherwise.

Definition at line 202 of file parameters.h.

static void swri::warnUnusedParams ( ros::NodeHandle const &  n) [inline, static]

Wrapper around getUnusedParamKeys that emits a warning for every unused parameter

Parameters:
nNodehandle defining the namespace to restrict the list

Definition at line 267 of file parameters.h.


Variable Documentation

std::set<std::string> swri::_used_params [static]

This set stores all of the parameters that have been got with this library It is used for the getUnusedParamKeys and WarnUnusedParams functions

Definition at line 19 of file parameters.h.



swri_roscpp
Author(s):
autogenerated on Tue Oct 3 2017 03:19:27