mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
Doxygen updates comm part 1
This commit is contained in:
@@ -36,6 +36,10 @@ namespace ur_driver
|
|||||||
{
|
{
|
||||||
namespace comm
|
namespace comm
|
||||||
{
|
{
|
||||||
|
/*!
|
||||||
|
* \brief The BinParser class handles a byte buffer and functionality to iteratively parse the
|
||||||
|
* content.
|
||||||
|
*/
|
||||||
class BinParser
|
class BinParser
|
||||||
{
|
{
|
||||||
private:
|
private:
|
||||||
@@ -74,21 +78,44 @@ private:
|
|||||||
}
|
}
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
/*!
|
||||||
|
* \brief Creates a new BinParser object from a given buffer.
|
||||||
|
*
|
||||||
|
* \param buffer The byte buffer to parse
|
||||||
|
* \param buf_len Size of the buffer
|
||||||
|
*/
|
||||||
BinParser(uint8_t* buffer, size_t buf_len) : buf_pos_(buffer), buf_end_(buffer + buf_len), parent_(*this)
|
BinParser(uint8_t* buffer, size_t buf_len) : buf_pos_(buffer), buf_end_(buffer + buf_len), parent_(*this)
|
||||||
{
|
{
|
||||||
assert(buf_pos_ <= buf_end_);
|
assert(buf_pos_ <= buf_end_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Creates a new BinParser object for part of a buffer from a parent BinParser.
|
||||||
|
*
|
||||||
|
* \param parent Parent BinParser
|
||||||
|
* \param sub_len Size of the sub-buffer to parse
|
||||||
|
*/
|
||||||
BinParser(BinParser& parent, size_t sub_len)
|
BinParser(BinParser& parent, size_t sub_len)
|
||||||
: buf_pos_(parent.buf_pos_), buf_end_(parent.buf_pos_ + sub_len), parent_(parent)
|
: buf_pos_(parent.buf_pos_), buf_end_(parent.buf_pos_ + sub_len), parent_(parent)
|
||||||
{
|
{
|
||||||
assert(buf_pos_ <= buf_end_);
|
assert(buf_pos_ <= buf_end_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Deconstructor for the BinParser.
|
||||||
|
*/
|
||||||
~BinParser()
|
~BinParser()
|
||||||
{
|
{
|
||||||
parent_.buf_pos_ = buf_pos_;
|
parent_.buf_pos_ = buf_pos_;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses the next bytes as given type without moving the buffer pointer.
|
||||||
|
*
|
||||||
|
* @tparam T Type to parse as
|
||||||
|
*
|
||||||
|
* \returns Value of the next bytes as type T
|
||||||
|
*/
|
||||||
template <typename T>
|
template <typename T>
|
||||||
T peek()
|
T peek()
|
||||||
{
|
{
|
||||||
@@ -98,6 +125,12 @@ public:
|
|||||||
return decode(val);
|
return decode(val);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses the next bytes as given type.
|
||||||
|
*
|
||||||
|
* @tparam T Type to parse as
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
*/
|
||||||
template <typename T>
|
template <typename T>
|
||||||
void parse(T& val)
|
void parse(T& val)
|
||||||
{
|
{
|
||||||
@@ -105,12 +138,22 @@ public:
|
|||||||
buf_pos_ += sizeof(T);
|
buf_pos_ += sizeof(T);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses the next bytes as a double.
|
||||||
|
*
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
*/
|
||||||
void parse(double& val)
|
void parse(double& val)
|
||||||
{
|
{
|
||||||
uint64_t inner;
|
uint64_t inner;
|
||||||
parse<uint64_t>(inner);
|
parse<uint64_t>(inner);
|
||||||
std::memcpy(&val, &inner, sizeof(double));
|
std::memcpy(&val, &inner, sizeof(double));
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Parses the next bytes as a float.
|
||||||
|
*
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
*/
|
||||||
void parse(float& val)
|
void parse(float& val)
|
||||||
{
|
{
|
||||||
uint32_t inner;
|
uint32_t inner;
|
||||||
@@ -118,8 +161,15 @@ public:
|
|||||||
std::memcpy(&val, &inner, sizeof(float));
|
std::memcpy(&val, &inner, sizeof(float));
|
||||||
}
|
}
|
||||||
|
|
||||||
// UR uses 1 byte for boolean values but sizeof(bool) is implementation
|
/*!
|
||||||
// defined so we must ensure they're parsed as uint8_t on all compilers
|
* \brief Parses the next byte as a bool.
|
||||||
|
*
|
||||||
|
* UR uses 1 byte for boolean values but sizeof(bool) is implementation defined, so we must ensure
|
||||||
|
* they're parsed as uint8_t on all compilers
|
||||||
|
*
|
||||||
|
*
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
*/
|
||||||
void parse(bool& val)
|
void parse(bool& val)
|
||||||
{
|
{
|
||||||
uint8_t inner;
|
uint8_t inner;
|
||||||
@@ -127,6 +177,11 @@ public:
|
|||||||
val = inner != 0;
|
val = inner != 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses the next bytes as a vector of 3 doubles.
|
||||||
|
*
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
*/
|
||||||
void parse(vector3d_t& val)
|
void parse(vector3d_t& val)
|
||||||
{
|
{
|
||||||
for (size_t i = 0; i < val.size(); ++i)
|
for (size_t i = 0; i < val.size(); ++i)
|
||||||
@@ -135,6 +190,11 @@ public:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses the next bytes as a vector of 6 doubles.
|
||||||
|
*
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
*/
|
||||||
void parse(vector6d_t& val)
|
void parse(vector6d_t& val)
|
||||||
{
|
{
|
||||||
for (size_t i = 0; i < val.size(); ++i)
|
for (size_t i = 0; i < val.size(); ++i)
|
||||||
@@ -143,6 +203,11 @@ public:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses the next bytes as a vector of 6 32 bit integers.
|
||||||
|
*
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
*/
|
||||||
void parse(vector6int32_t& val)
|
void parse(vector6int32_t& val)
|
||||||
{
|
{
|
||||||
for (size_t i = 0; i < val.size(); ++i)
|
for (size_t i = 0; i < val.size(); ++i)
|
||||||
@@ -151,6 +216,11 @@ public:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses the next bytes as a vector of 6 unsigned 32 bit integers.
|
||||||
|
*
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
*/
|
||||||
void parse(vector6uint32_t& val)
|
void parse(vector6uint32_t& val)
|
||||||
{
|
{
|
||||||
for (size_t i = 0; i < val.size(); ++i)
|
for (size_t i = 0; i < val.size(); ++i)
|
||||||
@@ -159,6 +229,12 @@ public:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Writes the remaining bytes into a given buffer without parsing them.
|
||||||
|
*
|
||||||
|
* \param buffer The buffer to copy the remaining bytes to.
|
||||||
|
* \param buffer_length Reference to write the number of remaining bytes to.
|
||||||
|
*/
|
||||||
void rawData(std::unique_ptr<uint8_t>& buffer, size_t& buffer_length)
|
void rawData(std::unique_ptr<uint8_t>& buffer, size_t& buffer_length)
|
||||||
{
|
{
|
||||||
buffer_length = buf_end_ - buf_pos_;
|
buffer_length = buf_end_ - buf_pos_;
|
||||||
@@ -167,18 +243,33 @@ public:
|
|||||||
consume();
|
consume();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses the remaining bytes as a string.
|
||||||
|
*
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
*/
|
||||||
void parseRemainder(std::string& val)
|
void parseRemainder(std::string& val)
|
||||||
{
|
{
|
||||||
parse(val, size_t(buf_end_ - buf_pos_));
|
parse(val, size_t(buf_end_ - buf_pos_));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses a given number of bytes as a string.
|
||||||
|
*
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
* \param len Number of bytes to parse
|
||||||
|
*/
|
||||||
void parse(std::string& val, size_t len)
|
void parse(std::string& val, size_t len)
|
||||||
{
|
{
|
||||||
val.assign(reinterpret_cast<char*>(buf_pos_), len);
|
val.assign(reinterpret_cast<char*>(buf_pos_), len);
|
||||||
buf_pos_ += len;
|
buf_pos_ += len;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Special string parse function that assumes uint8_t len followed by chars
|
/*!
|
||||||
|
* \brief Special string parse function that assumes uint8_t len followed by chars
|
||||||
|
*
|
||||||
|
* \param val Reference to write the parsed value to
|
||||||
|
*/
|
||||||
void parse(std::string& val)
|
void parse(std::string& val)
|
||||||
{
|
{
|
||||||
uint8_t len;
|
uint8_t len;
|
||||||
@@ -186,6 +277,13 @@ public:
|
|||||||
parse(val, size_t(len));
|
parse(val, size_t(len));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses the next bytes as an array of a given type and size.
|
||||||
|
*
|
||||||
|
* @tparam T Type of the array
|
||||||
|
* @tparam N Number of elements in the array
|
||||||
|
* \param array Reference of an array to parse to.
|
||||||
|
*/
|
||||||
template <typename T, size_t N>
|
template <typename T, size_t N>
|
||||||
void parse(std::array<T, N>& array)
|
void parse(std::array<T, N>& array)
|
||||||
{
|
{
|
||||||
@@ -195,6 +293,13 @@ public:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parses the next bytes as a value of a given type, but also copies it to a bitset.
|
||||||
|
*
|
||||||
|
* @tparam T Type to parse as
|
||||||
|
* @tparam N Size of the bitset to copy to
|
||||||
|
* \param set Reference to the bitset to copy the value to.
|
||||||
|
*/
|
||||||
template <typename T, size_t N>
|
template <typename T, size_t N>
|
||||||
void parse(std::bitset<N>& set)
|
void parse(std::bitset<N>& set)
|
||||||
{
|
{
|
||||||
@@ -203,30 +308,60 @@ public:
|
|||||||
set = std::bitset<N>(val);
|
set = std::bitset<N>(val);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Sets the current buffer position to the end of the buffer, finishing parsing.
|
||||||
|
*/
|
||||||
void consume()
|
void consume()
|
||||||
{
|
{
|
||||||
buf_pos_ = buf_end_;
|
buf_pos_ = buf_end_;
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Moves the current buffer position ahead by a given amount.
|
||||||
|
*
|
||||||
|
* \param bytes Number of bytes to move the buffer position
|
||||||
|
*/
|
||||||
void consume(size_t bytes)
|
void consume(size_t bytes)
|
||||||
{
|
{
|
||||||
buf_pos_ += bytes;
|
buf_pos_ += bytes;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Checks if at least a given number of bytes is still remaining unparsed in the buffer.
|
||||||
|
*
|
||||||
|
* \param bytes Number of bytes to check for
|
||||||
|
*
|
||||||
|
* \returns True, if at least the given number of bytes are unparsed, false otherwise.
|
||||||
|
*/
|
||||||
bool checkSize(size_t bytes)
|
bool checkSize(size_t bytes)
|
||||||
{
|
{
|
||||||
return bytes <= size_t(buf_end_ - buf_pos_);
|
return bytes <= size_t(buf_end_ - buf_pos_);
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Checks if enough bytes for a given type remain unparsed in the buffer.
|
||||||
|
*
|
||||||
|
* @tparam T The type to check for
|
||||||
|
*
|
||||||
|
* \returns True, if enough bytes are unparsed, false otherwise.
|
||||||
|
*/
|
||||||
template <typename T>
|
template <typename T>
|
||||||
bool checkSize(void)
|
bool checkSize(void)
|
||||||
{
|
{
|
||||||
return checkSize(T::SIZE);
|
return checkSize(T::SIZE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Checks if no unparsed bytes remain in the buffer.
|
||||||
|
*
|
||||||
|
* \returns True, if all bytes were parsed, false otherwise.
|
||||||
|
*/
|
||||||
bool empty()
|
bool empty()
|
||||||
{
|
{
|
||||||
return buf_pos_ == buf_end_;
|
return buf_pos_ == buf_end_;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Logs debugging information about the BinParser object.
|
||||||
|
*/
|
||||||
void debug()
|
void debug()
|
||||||
{
|
{
|
||||||
LOG_DEBUG("BinParser: %p - %p (%zu bytes)", buf_pos_, buf_end_, buf_end_ - buf_pos_);
|
LOG_DEBUG("BinParser: %p - %p (%zu bytes)", buf_pos_, buf_end_, buf_end_ - buf_pos_);
|
||||||
|
|||||||
@@ -49,8 +49,21 @@ public:
|
|||||||
URPackage() = default;
|
URPackage() = default;
|
||||||
virtual ~URPackage() = default;
|
virtual ~URPackage() = default;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Sets the attributes of the package by parsing a serialized representation of the
|
||||||
|
* package.
|
||||||
|
*
|
||||||
|
* \param bp A parser containing a serialized version of the package
|
||||||
|
*
|
||||||
|
* \returns true, if the package was parsed successfully, false otherwise
|
||||||
|
*/
|
||||||
virtual bool parseWith(BinParser& bp) = 0;
|
virtual bool parseWith(BinParser& bp) = 0;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Produces a human readable representation of the package obejct.
|
||||||
|
*
|
||||||
|
* \returns A string representing the object
|
||||||
|
*/
|
||||||
virtual std::string toString() const = 0;
|
virtual std::string toString() const = 0;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|||||||
@@ -35,9 +35,22 @@ namespace ur_driver
|
|||||||
{
|
{
|
||||||
namespace comm
|
namespace comm
|
||||||
{
|
{
|
||||||
|
/*!
|
||||||
|
* \brief A helper class to serialize packages. Contains methods for serializing all relevant
|
||||||
|
* datatypes.
|
||||||
|
*/
|
||||||
class PackageSerializer
|
class PackageSerializer
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
/*!
|
||||||
|
* \brief A generalized serialization method for arbitrary datatypes.
|
||||||
|
*
|
||||||
|
* @tparam T The type to serialize
|
||||||
|
* \param buffer The buffer to write the serialization into
|
||||||
|
* \param val The value to serialize
|
||||||
|
*
|
||||||
|
* \returns Size in byte of the serialization
|
||||||
|
*/
|
||||||
template <typename T>
|
template <typename T>
|
||||||
static size_t serialize(uint8_t* buffer, T val)
|
static size_t serialize(uint8_t* buffer, T val)
|
||||||
{
|
{
|
||||||
@@ -47,6 +60,14 @@ public:
|
|||||||
return size;
|
return size;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief A serialization method for double values.
|
||||||
|
*
|
||||||
|
* \param buffer The buffer to write the serialization into.
|
||||||
|
* \param val The value to serialize.
|
||||||
|
*
|
||||||
|
* \returns Size in byte of the serialization.
|
||||||
|
*/
|
||||||
static size_t serialize(uint8_t* buffer, double val)
|
static size_t serialize(uint8_t* buffer, double val)
|
||||||
{
|
{
|
||||||
size_t size = sizeof(double);
|
size_t size = sizeof(double);
|
||||||
@@ -57,6 +78,14 @@ public:
|
|||||||
return size;
|
return size;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief A serialization method for strings.
|
||||||
|
*
|
||||||
|
* \param buffer The buffer to write the serialization into.
|
||||||
|
* \param val The string to serialize.
|
||||||
|
*
|
||||||
|
* \returns Size in byte of the serialization.
|
||||||
|
*/
|
||||||
static size_t serialize(uint8_t* buffer, std::string val)
|
static size_t serialize(uint8_t* buffer, std::string val)
|
||||||
{
|
{
|
||||||
const uint8_t* c_val = reinterpret_cast<const uint8_t*>(val.c_str());
|
const uint8_t* c_val = reinterpret_cast<const uint8_t*>(val.c_str());
|
||||||
|
|||||||
@@ -41,10 +41,10 @@ public:
|
|||||||
virtual ~Parser() = default;
|
virtual ~Parser() = default;
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief declares the parse function.
|
* \brief Declares the parse function.
|
||||||
*
|
*
|
||||||
* \param bp instant of class binaryParser
|
* \param bp Instance of class binaryParser
|
||||||
* \param results unique pointer
|
* \param results A unique pointer
|
||||||
*/
|
*/
|
||||||
virtual bool parse(BinParser& bp, std::vector<std::unique_ptr<URPackage<HeaderT>>>& results) = 0;
|
virtual bool parse(BinParser& bp, std::vector<std::unique_ptr<URPackage<HeaderT>>>& results) = 0;
|
||||||
using _header_type = HeaderT;
|
using _header_type = HeaderT;
|
||||||
|
|||||||
@@ -36,27 +36,57 @@ namespace comm
|
|||||||
// TODO: Remove these!!!
|
// TODO: Remove these!!!
|
||||||
using namespace moodycamel;
|
using namespace moodycamel;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parent class for for arbitrary consumers.
|
||||||
|
*
|
||||||
|
* @tparam T Type of the consumed products
|
||||||
|
*/
|
||||||
template <typename T>
|
template <typename T>
|
||||||
class IConsumer
|
class IConsumer
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
/*!
|
||||||
|
* \brief Set-up functionality of the consumer.
|
||||||
|
*/
|
||||||
virtual void setupConsumer()
|
virtual void setupConsumer()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Fully tears down the consumer - by default no difference to stopping it.
|
||||||
|
*/
|
||||||
virtual void teardownConsumer()
|
virtual void teardownConsumer()
|
||||||
{
|
{
|
||||||
stopConsumer();
|
stopConsumer();
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Stops the consumer.
|
||||||
|
*/
|
||||||
virtual void stopConsumer()
|
virtual void stopConsumer()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Functionality for handling consumer timeouts.
|
||||||
|
*/
|
||||||
virtual void onTimeout()
|
virtual void onTimeout()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Consumes a product, utilizing it's contents.
|
||||||
|
*
|
||||||
|
* \param product Shared pointer to the product to be consumed.
|
||||||
|
*
|
||||||
|
* \returns Success of the consumption.
|
||||||
|
*/
|
||||||
virtual bool consume(std::shared_ptr<T> product) = 0;
|
virtual bool consume(std::shared_ptr<T> product) = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Consumer, that allows one product to be consumed by multiple arbitrary
|
||||||
|
* conusmers.
|
||||||
|
*
|
||||||
|
* @tparam T Type of the consumed products
|
||||||
|
*/
|
||||||
template <typename T>
|
template <typename T>
|
||||||
class MultiConsumer : public IConsumer<T>
|
class MultiConsumer : public IConsumer<T>
|
||||||
{
|
{
|
||||||
@@ -64,10 +94,18 @@ private:
|
|||||||
std::vector<IConsumer<T>*> consumers_;
|
std::vector<IConsumer<T>*> consumers_;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
/*!
|
||||||
|
* \brief Creates a new MultiConsumer object.
|
||||||
|
*
|
||||||
|
* \param consumers The list of consumers that should all consume given products
|
||||||
|
*/
|
||||||
MultiConsumer(std::vector<IConsumer<T>*> consumers) : consumers_(consumers)
|
MultiConsumer(std::vector<IConsumer<T>*> consumers) : consumers_(consumers)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Sets up all registered consumers.
|
||||||
|
*/
|
||||||
virtual void setupConsumer()
|
virtual void setupConsumer()
|
||||||
{
|
{
|
||||||
for (auto& con : consumers_)
|
for (auto& con : consumers_)
|
||||||
@@ -75,6 +113,9 @@ public:
|
|||||||
con->setupConsumer();
|
con->setupConsumer();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Tears down all registered consumers.
|
||||||
|
*/
|
||||||
virtual void teardownConsumer()
|
virtual void teardownConsumer()
|
||||||
{
|
{
|
||||||
for (auto& con : consumers_)
|
for (auto& con : consumers_)
|
||||||
@@ -82,6 +123,9 @@ public:
|
|||||||
con->teardownConsumer();
|
con->teardownConsumer();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Stops all registered consumers.
|
||||||
|
*/
|
||||||
virtual void stopConsumer()
|
virtual void stopConsumer()
|
||||||
{
|
{
|
||||||
for (auto& con : consumers_)
|
for (auto& con : consumers_)
|
||||||
@@ -89,6 +133,9 @@ public:
|
|||||||
con->stopConsumer();
|
con->stopConsumer();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Triggers timeout functionality for all registered consumers.
|
||||||
|
*/
|
||||||
virtual void onTimeout()
|
virtual void onTimeout()
|
||||||
{
|
{
|
||||||
for (auto& con : consumers_)
|
for (auto& con : consumers_)
|
||||||
@@ -97,6 +144,13 @@ public:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Consumes a given product with all registered consumers.
|
||||||
|
*
|
||||||
|
* \param product Shared pointer to the product to be consumed.
|
||||||
|
*
|
||||||
|
* \returns Success of the consumption.
|
||||||
|
*/
|
||||||
bool consume(std::shared_ptr<T> product)
|
bool consume(std::shared_ptr<T> product)
|
||||||
{
|
{
|
||||||
bool res = true;
|
bool res = true;
|
||||||
@@ -109,35 +163,72 @@ public:
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parent class for arbitrary producers of packages.
|
||||||
|
*
|
||||||
|
* @tparam HeaderT Header type of the produced packages
|
||||||
|
*/
|
||||||
template <typename HeaderT>
|
template <typename HeaderT>
|
||||||
class IProducer
|
class IProducer
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
/*!
|
||||||
|
* \brief Set-up functionality of the producers.
|
||||||
|
*/
|
||||||
virtual void setupProducer()
|
virtual void setupProducer()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Fully tears down the producer - by default no difference to stopping it.
|
||||||
|
*/
|
||||||
virtual void teardownProducer()
|
virtual void teardownProducer()
|
||||||
{
|
{
|
||||||
stopProducer();
|
stopProducer();
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Stops the producer.
|
||||||
|
*/
|
||||||
virtual void stopProducer()
|
virtual void stopProducer()
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Reads packages from some source and produces corresponding objects.
|
||||||
|
*
|
||||||
|
* \param products Vector of unique pointers to be filled with produced packages.
|
||||||
|
*
|
||||||
|
* \returns Success of the package production.
|
||||||
|
*/
|
||||||
virtual bool tryGet(std::vector<std::unique_ptr<URPackage<HeaderT>>>& products) = 0;
|
virtual bool tryGet(std::vector<std::unique_ptr<URPackage<HeaderT>>>& products) = 0;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Parent class for notifiers.
|
||||||
|
*/
|
||||||
class INotifier
|
class INotifier
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
/*!
|
||||||
|
* \brief Start notification.
|
||||||
|
*/
|
||||||
virtual void started(std::string name)
|
virtual void started(std::string name)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Stop notification.
|
||||||
|
*/
|
||||||
virtual void stopped(std::string name)
|
virtual void stopped(std::string name)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief The Pipepline manages the production and optionally consumption of packages. Cyclically
|
||||||
|
* the producer is called and returned packages are saved in a queue. This queue is then either also
|
||||||
|
* cyclically utilized by the registered consumer or can be externally used.
|
||||||
|
*
|
||||||
|
* @tparam HeaderT Header type of the managed packages
|
||||||
|
*/
|
||||||
template <typename HeaderT>
|
template <typename HeaderT>
|
||||||
class Pipeline
|
class Pipeline
|
||||||
{
|
{
|
||||||
@@ -145,21 +236,44 @@ public:
|
|||||||
typedef std::chrono::high_resolution_clock Clock;
|
typedef std::chrono::high_resolution_clock Clock;
|
||||||
typedef Clock::time_point Time;
|
typedef Clock::time_point Time;
|
||||||
using _package_type = URPackage<HeaderT>;
|
using _package_type = URPackage<HeaderT>;
|
||||||
|
/*!
|
||||||
|
* \brief Creates a new Pipeline object, registering producer, consumer and notifier.
|
||||||
|
* Additionally, an empty queue is initialized.
|
||||||
|
*
|
||||||
|
* \param producer The producer to run in the pipeline
|
||||||
|
* \param consumer The consumer to run in the pipeline
|
||||||
|
* \param name The pipeline's name
|
||||||
|
* \param notifier The notifier to use
|
||||||
|
*/
|
||||||
Pipeline(IProducer<HeaderT>& producer, IConsumer<_package_type>& consumer, std::string name, INotifier& notifier)
|
Pipeline(IProducer<HeaderT>& producer, IConsumer<_package_type>& consumer, std::string name, INotifier& notifier)
|
||||||
: producer_(producer), consumer_(&consumer), name_(name), notifier_(notifier), queue_{ 32 }, running_{ false }
|
: producer_(producer), consumer_(&consumer), name_(name), notifier_(notifier), queue_{ 32 }, running_{ false }
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
/*!
|
||||||
|
* \brief Creates a new Pipeline object, registering producer and notifier while no consumer is
|
||||||
|
* used. Additionally, an empty queue is initialized.
|
||||||
|
*
|
||||||
|
* \param producer The producer to run in the pipeline
|
||||||
|
* \param name The pipeline's name
|
||||||
|
* \param notifier The notifier to use
|
||||||
|
*/
|
||||||
Pipeline(IProducer<HeaderT>& producer, std::string name, INotifier& notifier)
|
Pipeline(IProducer<HeaderT>& producer, std::string name, INotifier& notifier)
|
||||||
: producer_(producer), consumer_(nullptr), name_(name), notifier_(notifier), queue_{ 32 }, running_{ false }
|
: producer_(producer), consumer_(nullptr), name_(name), notifier_(notifier), queue_{ 32 }, running_{ false }
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief The Pipeline object's destructor, stopping the pipeline and joining all running threads.
|
||||||
|
*/
|
||||||
virtual ~Pipeline()
|
virtual ~Pipeline()
|
||||||
{
|
{
|
||||||
LOG_DEBUG("Destructing pipeline");
|
LOG_DEBUG("Destructing pipeline");
|
||||||
stop();
|
stop();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Starts the producer and, if existing, the consumer in new threads.
|
||||||
|
*/
|
||||||
void run()
|
void run()
|
||||||
{
|
{
|
||||||
if (running_)
|
if (running_)
|
||||||
@@ -173,6 +287,9 @@ public:
|
|||||||
notifier_.started(name_);
|
notifier_.started(name_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Stops the pipeline and all running threads.
|
||||||
|
*/
|
||||||
void stop()
|
void stop()
|
||||||
{
|
{
|
||||||
if (!running_)
|
if (!running_)
|
||||||
@@ -193,6 +310,14 @@ public:
|
|||||||
notifier_.stopped(name_);
|
notifier_.stopped(name_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Returns the next package in the queue. Can be used instead of registering a consumer.
|
||||||
|
*
|
||||||
|
* \param product Unique pointer to be set to the package
|
||||||
|
* \param timeout Time to wait if no package is in the queue before returning
|
||||||
|
*
|
||||||
|
* \returns
|
||||||
|
*/
|
||||||
bool getLatestProduct(std::unique_ptr<URPackage<HeaderT>>& product, std::chrono::milliseconds timeout)
|
bool getLatestProduct(std::unique_ptr<URPackage<HeaderT>>& product, std::chrono::milliseconds timeout)
|
||||||
{
|
{
|
||||||
return queue_.waitDequeTimed(product, timeout);
|
return queue_.waitDequeTimed(product, timeout);
|
||||||
|
|||||||
Reference in New Issue
Block a user