ros2_control - rolling
|
A handle used to get and set a value on a given interface. More...
#include <handle.hpp>
Public Member Functions | |
Handle (const std::string &prefix_name, const std::string &interface_name, double *value_ptr=nullptr) | |
Handle (const InterfaceDescription &interface_description) | |
Handle (const std::string &interface_name) | |
Handle (const char *interface_name) | |
Handle (const Handle &other)=default | |
Handle (Handle &&other)=default | |
Handle & | operator= (const Handle &other)=default |
Handle & | operator= (Handle &&other)=default |
operator bool () const | |
Returns true if handle references a value. | |
const std::string & | get_name () const |
const std::string & | get_interface_name () const |
const std::string & | get_full_name () const |
const std::string & | get_prefix_name () const |
double | get_value () const |
void | set_value (double value) |
Protected Attributes | |
std::string | prefix_name_ |
std::string | interface_name_ |
std::string | handle_name_ |
HANDLE_DATATYPE | value_ |
double * | value_ptr_ |
A handle used to get and set a value on a given interface.