mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
doxygen documentation for primary headers
This commit is contained in:
@@ -52,6 +52,9 @@ enum class RobotPackageType : int8_t
|
|||||||
PROGRAM_STATE_MESSAGE = 25
|
PROGRAM_STATE_MESSAGE = 25
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief This class represents the header for primary packages.
|
||||||
|
*/
|
||||||
class PackageHeader
|
class PackageHeader
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
@@ -60,6 +63,13 @@ public:
|
|||||||
|
|
||||||
using _package_size_type = int32_t;
|
using _package_size_type = int32_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Reads a buffer, interpreting the next bytes as the size of the contained package.
|
||||||
|
*
|
||||||
|
* \param buf The given byte stream containing a serialized package
|
||||||
|
*
|
||||||
|
* \returns The size of the given serialized package
|
||||||
|
*/
|
||||||
static size_t getPackageLength(uint8_t* buf)
|
static size_t getPackageLength(uint8_t* buf)
|
||||||
{
|
{
|
||||||
return be32toh(*(reinterpret_cast<_package_size_type*>(buf)));
|
return be32toh(*(reinterpret_cast<_package_size_type*>(buf)));
|
||||||
|
|||||||
@@ -51,7 +51,21 @@ public:
|
|||||||
}
|
}
|
||||||
virtual ~PrimaryPackage() = default;
|
virtual ~PrimaryPackage() = 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(comm::BinParser& bp);
|
virtual bool parseWith(comm::BinParser& bp);
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Produces a human readable representation of the package object.
|
||||||
|
*
|
||||||
|
* \returns A string representing the object
|
||||||
|
*/
|
||||||
virtual std::string toString() const;
|
virtual std::string toString() const;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|||||||
@@ -35,12 +35,25 @@ namespace ur_driver
|
|||||||
{
|
{
|
||||||
namespace primary_interface
|
namespace primary_interface
|
||||||
{
|
{
|
||||||
|
/*!
|
||||||
|
* \brief The primary specific parser. Interprets a given byte stream as serialized primary
|
||||||
|
* packages and parses it accordingly.
|
||||||
|
*/
|
||||||
class PrimaryParser : public comm::Parser<PackageHeader>
|
class PrimaryParser : public comm::Parser<PackageHeader>
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
PrimaryParser() = default;
|
PrimaryParser() = default;
|
||||||
virtual ~PrimaryParser() = default;
|
virtual ~PrimaryParser() = default;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Uses the given BinParser to create package objects from the contained serialization.
|
||||||
|
*
|
||||||
|
* \param bp A BinParser holding one or more serialized primary packages
|
||||||
|
* \param results A vector of pointers to created primary package objects
|
||||||
|
*
|
||||||
|
* \returns True, if the byte stream could successfully be parsed as primary packages, false
|
||||||
|
* otherwise
|
||||||
|
*/
|
||||||
bool parse(comm::BinParser& bp, std::vector<std::unique_ptr<comm::URPackage<PackageHeader>>>& results)
|
bool parse(comm::BinParser& bp, std::vector<std::unique_ptr<comm::URPackage<PackageHeader>>>& results)
|
||||||
{
|
{
|
||||||
int32_t packet_size;
|
int32_t packet_size;
|
||||||
|
|||||||
@@ -46,16 +46,39 @@ enum class RobotMessagePackageType : uint8_t
|
|||||||
ROBOT_MESSAGE_REQUEST_VALUE = 9,
|
ROBOT_MESSAGE_REQUEST_VALUE = 9,
|
||||||
ROBOT_MESSAGE_RUNTIME_EXCEPTION = 10
|
ROBOT_MESSAGE_RUNTIME_EXCEPTION = 10
|
||||||
};
|
};
|
||||||
class RobotMessage : public PrimaryPackage
|
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief The RobotMessage class is a parent class for the different received robot messages.
|
||||||
|
*/
|
||||||
|
class RobotMessage : public PrimaryPackage
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
/*!
|
||||||
|
* \brief Creates a new RobotMessage object to be filled from a package.
|
||||||
|
*
|
||||||
|
* \param timestamp Timestamp of the package
|
||||||
|
* \param source The package's source
|
||||||
|
*/
|
||||||
RobotMessage(const uint64_t timestamp, const uint8_t source) : timestamp_(timestamp), source_(source)
|
RobotMessage(const uint64_t timestamp, const uint8_t source) : timestamp_(timestamp), source_(source)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
virtual ~RobotMessage() = default;
|
virtual ~RobotMessage() = 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(comm::BinParser& bp);
|
virtual bool parseWith(comm::BinParser& bp);
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Produces a human readable representation of the package object.
|
||||||
|
*
|
||||||
|
* \returns A string representing the object
|
||||||
|
*/
|
||||||
virtual std::string toString() const;
|
virtual std::string toString() const;
|
||||||
|
|
||||||
uint64_t timestamp_;
|
uint64_t timestamp_;
|
||||||
|
|||||||
@@ -34,17 +34,39 @@ namespace ur_driver
|
|||||||
{
|
{
|
||||||
namespace primary_interface
|
namespace primary_interface
|
||||||
{
|
{
|
||||||
|
/*!
|
||||||
|
* \brief The VersionMessage class handles the version messages sent via the primary UR interface.
|
||||||
|
*/
|
||||||
class VersionMessage : public RobotMessage
|
class VersionMessage : public RobotMessage
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
VersionMessage() = delete;
|
VersionMessage() = delete;
|
||||||
|
/*!
|
||||||
|
* \brief Creates a new VersionMessage object to be filled from a package.
|
||||||
|
*
|
||||||
|
* \param timestamp Timestamp of the package
|
||||||
|
* \param source The package's source
|
||||||
|
*/
|
||||||
VersionMessage(uint64_t timestamp, uint8_t source) : RobotMessage(timestamp, source)
|
VersionMessage(uint64_t timestamp, uint8_t source) : RobotMessage(timestamp, source)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
virtual ~VersionMessage() = default;
|
virtual ~VersionMessage() = 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(comm::BinParser& bp);
|
virtual bool parseWith(comm::BinParser& bp);
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Produces a human readable representation of the package object.
|
||||||
|
*
|
||||||
|
* \returns A string representing the object
|
||||||
|
*/
|
||||||
virtual std::string toString() const;
|
virtual std::string toString() const;
|
||||||
|
|
||||||
int8_t project_name_length_;
|
int8_t project_name_length_;
|
||||||
|
|||||||
@@ -58,15 +58,34 @@ class RobotState : public PrimaryPackage
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
RobotState() = delete;
|
RobotState() = delete;
|
||||||
|
/*!
|
||||||
|
* \brief Creates a new RobotState object, setting the type of state message.
|
||||||
|
*
|
||||||
|
* \param type The type of state message
|
||||||
|
*/
|
||||||
RobotState(const RobotStateType type) : state_type_(type)
|
RobotState(const RobotStateType type) : state_type_(type)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
virtual ~RobotState() = default;
|
virtual ~RobotState() = 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(comm::BinParser& bp)
|
virtual bool parseWith(comm::BinParser& bp)
|
||||||
{
|
{
|
||||||
return PrimaryPackage::parseWith(bp);
|
return PrimaryPackage::parseWith(bp);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Produces a human readable representation of the package object.
|
||||||
|
*
|
||||||
|
* \returns A string representing the object
|
||||||
|
*/
|
||||||
virtual std::string toString() const
|
virtual std::string toString() const
|
||||||
{
|
{
|
||||||
std::stringstream ss;
|
std::stringstream ss;
|
||||||
|
|||||||
@@ -43,14 +43,38 @@ class KinematicsInfo : public RobotState
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
KinematicsInfo() = delete;
|
KinematicsInfo() = delete;
|
||||||
|
/*!
|
||||||
|
* \brief Creates a new KinematicsInfo object.
|
||||||
|
*
|
||||||
|
* \param type The type of RobotState message received
|
||||||
|
*/
|
||||||
KinematicsInfo(const RobotStateType type) : RobotState(type)
|
KinematicsInfo(const RobotStateType type) : RobotState(type)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
virtual ~KinematicsInfo() = default;
|
virtual ~KinematicsInfo() = 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(comm::BinParser& bp);
|
virtual bool parseWith(comm::BinParser& bp);
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Produces a human readable representation of the package object.
|
||||||
|
*
|
||||||
|
* \returns A string representing the object
|
||||||
|
*/
|
||||||
virtual std::string toString() const;
|
virtual std::string toString() const;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Calculates a hash value of the parameters to allow for identification of a calibration.
|
||||||
|
*
|
||||||
|
* \returns A hash value of the parameters
|
||||||
|
*/
|
||||||
std::string toHash() const;
|
std::string toHash() const;
|
||||||
|
|
||||||
vector6uint32_t checksum_;
|
vector6uint32_t checksum_;
|
||||||
|
|||||||
Reference in New Issue
Block a user