Classes | |
| class | BindSubscriberImpl |
| class | DynamicParameters |
| struct | DynamicValue |
| class | ImplRoot |
| class | LatchedSubscriber |
| class | NodeHandle |
| class | OptionalDiagnosedPublisher |
| class | OptionalSubscriber |
| class | OptionalSubscriberImpl |
| class | OptionalSubscriberImplRoot |
| class | ServiceServer |
| class | ServiceServerImpl |
| class | ServiceServerStatistics |
| class | StorageSubscriberImpl |
| class | Subscriber |
| class | SubscriberImpl |
| class | Timer |
| class | TimerImpl |
| class | TopicServiceClient |
| class | TopicServiceClientImpl |
| class | TopicServiceServer |
| class | TopicServiceServerImpl |
| struct | TrueType |
| struct | TypedParam |
| class | TypedServiceServerImpl |
| class | TypedSubscriberImpl |
| class | TypedTimerImpl |
Typedefs | |
| typedef TypedParam< bool > | BoolParam |
| typedef TypedParam< double > | DoubleParam |
| typedef TypedParam< float > | FloatParam |
| typedef TypedParam< int > | IntParam |
| typedef TypedParam< std::string > | StringParam |
Functions | |
| template<typename M > | |
| ros::Publisher | advertise (ros::NodeHandle &nh, const std::string name, uint32_t queue_size, bool latched=false) |
| template<typename M > | |
| ros::Publisher | advertise (swri::NodeHandle &nh, const std::string name, uint32_t queue_size, bool latched, const std::string description) |
| template<typename M > | |
| ros::Publisher | advertise (swri::NodeHandle &nh, const std::string name, uint32_t queue_size, const char *description) |
| template<class MReq , class MRes , class T > | |
| swri::ServiceServer | advertiseService (swri::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(const std::string &, const MReq &, MRes &), T *obj, const std::string description) |
| template<class MReq , class MRes , class T > | |
| swri::ServiceServer | advertiseService (swri::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj, const std::string description) |
| template<class MReq , class MRes , class T > | |
| swri::ServiceServer | advertiseService (swri::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(ros::ServiceEvent< MReq, MRes > &), T *obj, const std::string description) |
| int | comparePrefix (std::string const &string, std::string const &prefix) |
| static bool | getParam (const ros::NodeHandle &nh, const std::string &name, bool &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, int &variable) |
| static bool | getParam (const ros::NodeHandle &nh, const std::string &name, std::string &variable) |
| template<typename T > | |
| bool | getParam (swri::NodeHandle &nh, const std::string name, T &value, const std::string description) |
| 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, bool &variable, const bool 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, int &variable, const int default_value) |
| static void | param (const ros::NodeHandle &nh, const std::string &name, std::string &variable, const std::string default_value) |
| void | param (swri::NodeHandle &nh, const std::string name, std::string &value, const std::string def, const std::string description) |
| template<typename T > | |
| void | param (swri::NodeHandle &nh, const std::string name, T &value, const T def) |
| template<typename T > | |
| void | param (swri::NodeHandle &nh, const std::string name, T &value, const T def, const std::string description) |
| int | prefixLessThan (std::string const &string, std::string const &prefix) |
| void | ranged_param (swri::NodeHandle &nh, const std::string name, double &value, const double def, const std::string description="", const double min=-std::numeric_limits< double >::infinity(), const double max=std::numeric_limits< double >::infinity()) |
| template<typename T > | |
| void | setParam (swri::NodeHandle &nh, const std::string &name, T &value) |
| template<class M > | |
| swri::Subscriber | subscribe (swri::NodeHandle &nh, const std::string &name, boost::shared_ptr< M const > *dest, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints()) |
| template<class M , class T > | |
| swri::Subscriber | subscribe (swri::NodeHandle &nh, const std::string &name, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints()) |
| void | timeoutParam (swri::NodeHandle &nh, swri::Subscriber &sub, const std::string name, const double timeout, const std::string desc) |
| static void | warnUnusedParams (ros::NodeHandle const &n) |
Variables | |
| static std::set< std::string > | _used_params |
| typedef TypedParam<bool> swri::BoolParam |
Definition at line 121 of file dynamic_parameters.h.
| typedef TypedParam<double> swri::DoubleParam |
Definition at line 118 of file dynamic_parameters.h.
| typedef TypedParam<float> swri::FloatParam |
Definition at line 119 of file dynamic_parameters.h.
| typedef TypedParam<int> swri::IntParam |
Definition at line 120 of file dynamic_parameters.h.
| typedef TypedParam<std::string> swri::StringParam |
Definition at line 122 of file dynamic_parameters.h.
| 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.
| ros::Publisher swri::advertise | ( | swri::NodeHandle & | nh, |
| const std::string | name, | ||
| uint32_t | queue_size, | ||
| bool | latched, | ||
| const std::string | description | ||
| ) |
Definition at line 1223 of file node_handle.h.
| ros::Publisher swri::advertise | ( | swri::NodeHandle & | nh, |
| const std::string | name, | ||
| uint32_t | queue_size, | ||
| const char * | description | ||
| ) |
Definition at line 1233 of file node_handle.h.
| swri::ServiceServer swri::advertiseService | ( | swri::NodeHandle & | nh, |
| const std::string & | service, | ||
| bool(T::*)(const std::string &, const MReq &, MRes &) | srv_func, | ||
| T * | obj, | ||
| const std::string | description | ||
| ) |
Definition at line 1285 of file node_handle.h.
| swri::ServiceServer swri::advertiseService | ( | swri::NodeHandle & | nh, |
| const std::string & | service, | ||
| bool(T::*)(MReq &, MRes &) | srv_func, | ||
| T * | obj, | ||
| const std::string | description | ||
| ) |
Definition at line 1265 of file node_handle.h.
| swri::ServiceServer swri::advertiseService | ( | swri::NodeHandle & | nh, |
| const std::string & | service, | ||
| bool(T::*)(ros::ServiceEvent< MReq, MRes > &) | srv_func, | ||
| T * | obj, | ||
| const std::string | description | ||
| ) |
Definition at line 1275 of file node_handle.h.
|
inline |
Determines whether prefix is a prefix of string.
| string | The longer string to check, which may begin with the characters of prefix. |
| prefix | The shorter string, which may be a prefix of string. |
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.
|
inlinestatic |
Definition at line 86 of file parameters.h.
|
inlinestatic |
Definition at line 38 of file parameters.h.
|
inlinestatic |
Definition at line 54 of file parameters.h.
|
inlinestatic |
Definition at line 22 of file parameters.h.
|
inlinestatic |
Definition at line 70 of file parameters.h.
| bool swri::getParam | ( | swri::NodeHandle & | nh, |
| const std::string | name, | ||
| T & | value, | ||
| const std::string | description | ||
| ) |
Definition at line 1200 of file node_handle.h.
|
inlinestatic |
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.
| n | Nodehandle defining the namespace to restrict the list |
Definition at line 224 of file parameters.h.
|
inline |
Boolean wrapper around comparePrefix.
| string | The longer string to check, which may begin with the characters of prefix. |
| prefix | The shorter string, which may be a prefix of string. |
string are identical to prefix, where n is the length of prefix, false otherwise. Definition at line 186 of file parameters.h.
|
inlinestatic |
Definition at line 151 of file parameters.h.
|
inlinestatic |
Definition at line 114 of file parameters.h.
|
inlinestatic |
Definition at line 126 of file parameters.h.
|
inlinestatic |
Definition at line 102 of file parameters.h.
|
inlinestatic |
Definition at line 139 of file parameters.h.
|
inline |
Definition at line 1159 of file node_handle.h.
| void swri::param | ( | swri::NodeHandle & | nh, |
| const std::string | name, | ||
| T & | value, | ||
| const T | def | ||
| ) |
Definition at line 1180 of file node_handle.h.
| void swri::param | ( | swri::NodeHandle & | nh, |
| const std::string | name, | ||
| T & | value, | ||
| const T | def, | ||
| const std::string | description | ||
| ) |
Definition at line 1189 of file node_handle.h.
|
inline |
Less-than wrapper around comparePrefix, for algorithms that require a less-than comparator, such as sorting.
| string | The longer string to check, which may begin with the characters of prefix. |
| prefix | The shorter string, which may be a prefix of string. |
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.
|
inline |
Definition at line 1168 of file node_handle.h.
| void swri::setParam | ( | swri::NodeHandle & | nh, |
| const std::string & | name, | ||
| T & | value | ||
| ) |
Definition at line 1214 of file node_handle.h.
| swri::Subscriber swri::subscribe | ( | swri::NodeHandle & | nh, |
| const std::string & | name, | ||
| boost::shared_ptr< M const > * | dest, | ||
| const std::string | description, | ||
| const ros::TransportHints & | transport_hints = ros::TransportHints() |
||
| ) |
Definition at line 1255 of file node_handle.h.
| swri::Subscriber swri::subscribe | ( | swri::NodeHandle & | nh, |
| const std::string & | name, | ||
| uint32_t | queue_size, | ||
| void(T::*)(const boost::shared_ptr< M const > &) | fp, | ||
| T * | obj, | ||
| const std::string | description, | ||
| const ros::TransportHints & | transport_hints = ros::TransportHints() |
||
| ) |
Definition at line 1243 of file node_handle.h.
|
inline |
Definition at line 1294 of file node_handle.h.
|
inlinestatic |
Wrapper around getUnusedParamKeys that emits a warning for every unused parameter
| n | Nodehandle defining the namespace to restrict the list |
Definition at line 267 of file parameters.h.
|
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.