Class ReceivingInterface

Inheritance Relationships

Base Type

  • public Poco::Runnable

Derived Types

Class Documentation

class ReceivingInterface : public Poco::Runnable

The ReceivingInterface class is the base class for all receiving interfaces, such as ClientControlModeInterface, etc.

Subclassed by ClientControlModeInterface, ClientGlobalAlignVisualizationInterface, ClientLocalizationMapInterface, ClientLocalizationPoseInterface, ClientLocalizationVisualizationInterface, ClientMapMapInterface, ClientMapVisualizationInterface, ClientRecordingMapInterface, ClientRecordingVisualizationInterface

Public Functions

ReceivingInterface(const Poco::Net::IPAddress &hostadress, Poco::UInt16 port, rclcpp::Node::SharedPtr node)
virtual ~ReceivingInterface()
virtual void onReadEvent(const Poco::AutoPtr<Poco::Net::ReadableNotification> &notification)
void run()

Protected Functions

virtual size_t tryToParseData(const std::vector<char> &datagram_buffer, rclcpp::Node::SharedPtr node) = 0

Actual function to be overwritten by child to handle data, e.g., convert to ros messages and publish.

Parameters:

datagram_buffer – The data received via the binary connection socket

Returns:

amount of bytes successfully parsed and can be removed from the buffer (0 if not parsing failed)

Protected Attributes

rclcpp::Node::SharedPtr node_

Node.

Protected Static Attributes

static constexpr Poco::UInt16 BINARY_CLIENT_CONTROL_MODE_PORT = {9004}
static constexpr Poco::UInt16 BINARY_CLIENT_MAP_MAP_PORT = {9005}
static constexpr Poco::UInt16 BINARY_CLIENT_MAP_VISUALIZATION_PORT = {9006}
static constexpr Poco::UInt16 BINARY_CLIENT_RECORDING_MAP_PORT = {9007}
static constexpr Poco::UInt16 BINARY_CLIENT_RECORDING_VISUALIZATION_PORT = {9008}
static constexpr Poco::UInt16 BINARY_CLIENT_LOCALIZATION_MAP_PORT = {9009}
static constexpr Poco::UInt16 BINARY_CLIENT_LOCALIZATION_VISUALIZATION_PORT = {9010}
static constexpr Poco::UInt16 BINARY_CLIENT_LOCALIZATION_POSE_PORT = {9011}
static constexpr Poco::UInt16 BINARY_CLIENT_GLOBAL_ALIGN_VISUALIZATION_PORT = {9012}