Class IIONode

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class IIONode : public rclcpp::Node

Public Functions

IIONode()
virtual ~IIONode()
void initBuffers()
bool rwAttrPath(std::string path, std::string &result, bool write = false, std::string value = "")
std::string convertAttrPathToTopicName(std::string path)
void attrReadSrv(const std::shared_ptr<adi_iio::srv::AttrReadString::Request> request, std::shared_ptr<adi_iio::srv::AttrReadString::Response> response)
void attrWriteSrv(const std::shared_ptr<adi_iio::srv::AttrWriteString::Request> request, std::shared_ptr<adi_iio::srv::AttrWriteString::Response> response)
void attrEnableTopicSrv(const std::shared_ptr<adi_iio::srv::AttrEnableTopic::Request> request, std::shared_ptr<adi_iio::srv::AttrEnableTopic::Response> response)
void attrDisableTopicSrv(const std::shared_ptr<adi_iio::srv::AttrDisableTopic::Request> request, std::shared_ptr<adi_iio::srv::AttrDisableTopic::Response> response)
void buffRefillSrv(const std::shared_ptr<adi_iio::srv::BufferRefill::Request> request, std::shared_ptr<adi_iio::srv::BufferRefill::Response> response)
void buffReadSrv(const std::shared_ptr<adi_iio::srv::BufferRead::Request> request, std::shared_ptr<adi_iio::srv::BufferRead::Response> response)
void buffWriteSrv(const std::shared_ptr<adi_iio::srv::BufferWrite::Request> request, std::shared_ptr<adi_iio::srv::BufferWrite::Response> response)
void buffCreateSrv(const std::shared_ptr<adi_iio::srv::BufferCreate::Request> request, std::shared_ptr<adi_iio::srv::BufferCreate::Response> response)
void buffDestroySrv(const std::shared_ptr<adi_iio::srv::BufferDestroy::Request> request, std::shared_ptr<adi_iio::srv::BufferDestroy::Response> response)
void buffEnableTopicSrv(const std::shared_ptr<adi_iio::srv::BufferEnableTopic::Request> request, std::shared_ptr<adi_iio::srv::BufferEnableTopic::Response> response)
void buffDisableTopicSrv(const std::shared_ptr<adi_iio::srv::BufferDisableTopic::Request> request, std::shared_ptr<adi_iio::srv::BufferDisableTopic::Response> response)
std::string uri()
bool initialized()
iio_context *ctx()