Classes | |
| class | ROSaicNode |
| This class represents the ROsaic node, to be extended.. More... | |
Functions | |
| template<typename V , typename T > | |
| void | checkRange (V val, T min, T max, std::string name) |
| Checks whether the parameter is in the given range. More... | |
| template<typename V , typename T > | |
| void | checkRange (std::vector< V > val, T min, T max, std::string name) |
| Check whether the elements of the vector are in the given range. More... | |
| template<typename U > | |
| bool | getROSInt (const std::string &key, U &u) |
| Gets an integer or unsigned integer value from the parameter server. More... | |
| template<typename U > | |
| void | getROSInt (const std::string &key, U &u, U default_val) |
| Gets an integer or unsigned integer value from the parameter server. More... | |
| template<typename U > | |
| bool | getROSInt (const std::string &key, std::vector< U > &u) |
| Gets an unsigned integer or integer vector from the parameter server. More... | |
Variables | |
| io_comm_rx::Comm_IO | IO |
| Handles communication with the Rx. More... | |
This namespace is for the ROSaic node, handling all aspects regarding ROS parameters, ROS message publishing etc.
| void rosaic_node::checkRange | ( | V | val, |
| T | min, | ||
| T | max, | ||
| std::string | name | ||
| ) |
Checks whether the parameter is in the given range.
| [in] | val | The value to check |
| [in] | min | The minimum for this value |
| [in] | max | The maximum for this value |
| [in] | name | The name of the parameter |
| std::runtime_error | if it is out of bounds |
Definition at line 107 of file rosaic_node.hpp.
| void rosaic_node::checkRange | ( | std::vector< V > | val, |
| T | min, | ||
| T | max, | ||
| std::string | name | ||
| ) |
Check whether the elements of the vector are in the given range.
| [in] | val | The vector to check |
| [in] | min | The minimum for this value |
| [in] | max | The maximum for this value |
| [in] | name | The name of the parameter |
Definition at line 125 of file rosaic_node.hpp.
| bool rosaic_node::getROSInt | ( | const std::string & | key, |
| U & | u | ||
| ) |
Gets an integer or unsigned integer value from the parameter server.
| [in] | key | The key to be used in the parameter server's dictionary |
| [out] | u | Storage for the retrieved value, of type U, which can be either unsigned int or int |
| std::runtime_error | if the parameter is out of bounds |
Definition at line 143 of file rosaic_node.hpp.
| void rosaic_node::getROSInt | ( | const std::string & | key, |
| U & | u, | ||
| U | default_val | ||
| ) |
Gets an integer or unsigned integer value from the parameter server.
| [in] | key | The key to be used in the parameter server's dictionary |
| [out] | u | Storage for the retrieved value, of type U, which can be either unsigned int or int |
| [in] | val | Value to use if the server doesn't contain this parameter |
| std::runtime_error | if the parameter is out of bounds |
Definition at line 171 of file rosaic_node.hpp.
| bool rosaic_node::getROSInt | ( | const std::string & | key, |
| std::vector< U > & | u | ||
| ) |
Gets an unsigned integer or integer vector from the parameter server.
| [in] | key | The key to be used in the parameter server's dictionary |
| [out] | u | Storage for the retrieved value, of type std::vector<U>, where U can be either unsigned int or int |
| std::runtime_error | if the parameter is out of bounds |
Definition at line 185 of file rosaic_node.hpp.
| io_comm_rx::Comm_IO rosaic_node::IO |
Handles communication with the Rx.
Definition at line 96 of file rosaic_node.hpp.