1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-09 17:40:47 +02:00

doxygen documentation for rtde headers

This commit is contained in:
Tristan Schnell
2019-09-24 17:01:16 +02:00
parent 14010979e5
commit c72a76ef33
13 changed files with 413 additions and 0 deletions

View File

@@ -34,23 +34,49 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief This class handles the robot's response to a requested stop in RTDE data package
* communication.
*/
class ControlPackagePause : public RTDEPackage
{
public:
/*!
* \brief Creates a new ControlPackagePause object.
*/
ControlPackagePause() : RTDEPackage(PackageType::RTDE_CONTROL_PACKAGE_PAUSE)
{
}
virtual ~ControlPackagePause() = 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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
uint8_t accepted_;
};
/*!
* \brief This class is used to request a stop in RTDE data package communication.
*/
class ControlPackagePauseRequest : public RTDEPackage
{
public:
/*!
* \brief Creates a new ControlPackagePauseRequest object.
*/
ControlPackagePauseRequest() : RTDEPackage(PackageType::RTDE_CONTROL_PACKAGE_PAUSE)
{
}

View File

@@ -34,29 +34,62 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief This class handles the robot's response to a requested input recipe setup.
*/
class ControlPackageSetupInputs : public RTDEPackage
{
public:
/*!
* \brief Creates a new ControlPackageSetupInputs object.
*/
ControlPackageSetupInputs() : RTDEPackage(PackageType::RTDE_CONTROL_PACKAGE_SETUP_INPUTS)
{
}
virtual ~ControlPackageSetupInputs() = 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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
uint8_t input_recipe_id_;
std::string variable_types_;
};
/*!
* \brief This class is used to setup the input recipe as part of the initial RTDE handshake.
*/
class ControlPackageSetupInputsRequest : public RTDEPackage
{
public:
/*!
* \brief Creates a new ControlPackageSetupInputsRequest object.
*/
ControlPackageSetupInputsRequest() : RTDEPackage(PackageType::RTDE_CONTROL_PACKAGE_SETUP_INPUTS)
{
}
virtual ~ControlPackageSetupInputsRequest() = default;
/*!
* \brief Generates a serialized package.
*
* \param buffer Buffer to fill with the serialization
* \param variable_names The input recipe to set
*
* \returns The total size of the serialized package
*/
static size_t generateSerializedRequest(uint8_t* buffer, std::vector<std::string> variable_names);
std::string variable_names_;

View File

@@ -35,32 +35,74 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief This class handles the robot's response to a requested output recipe setup.
*/
class ControlPackageSetupOutputs : public RTDEPackage
{
public:
/*!
* \brief Creates a new ControlPackageSetupOutputs object.
*/
ControlPackageSetupOutputs() : RTDEPackage(PackageType::RTDE_CONTROL_PACKAGE_SETUP_OUTPUTS)
{
}
virtual ~ControlPackageSetupOutputs() = 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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
uint8_t output_recipe_id_;
std::string variable_types_;
};
/*!
* \brief This class is used to setup the output recipe as part of the initial RTDE handshake.
*/
class ControlPackageSetupOutputsRequest : public RTDEPackage
{
public:
/*!
* \brief Creates a new ControlPackageSetupOutputsRequest object.
*/
ControlPackageSetupOutputsRequest() : RTDEPackage(PackageType::RTDE_CONTROL_PACKAGE_SETUP_OUTPUTS)
{
}
virtual ~ControlPackageSetupOutputsRequest() = default;
/*!
* \brief Generates a serialized package.
*
* \param buffer Buffer to fill with the serialization
* \param output_frequency Frequency of data packages to be sent by the robot
* \param variable_names The output recipe to set
*
* \returns The total size of the serialized package
*/
static size_t generateSerializedRequest(uint8_t* buffer, double output_frequency,
std::vector<std::string> variable_names);
/*!
* \brief Generates a serialized package.
*
* \param buffer Buffer to fill with the serialization
* \param variable_names The output recipe to set
*
* \returns The total size of the serialized package
*/
static size_t generateSerializedRequest(uint8_t* buffer, std::vector<std::string> variable_names);
double output_frequency_;

View File

@@ -34,28 +34,61 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief This class handles the robot's response to a requested start in RTDE data package
* communication.
*/
class ControlPackageStart : public RTDEPackage
{
public:
/*!
* \brief Creates a new ControlPackageStart object.
*/
ControlPackageStart() : RTDEPackage(PackageType::RTDE_CONTROL_PACKAGE_START)
{
}
virtual ~ControlPackageStart() = 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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
uint8_t accepted_;
};
/*!
* \brief This class is used to request a stop in RTDE data package communication.
*/
class ControlPackageStartRequest : public RTDEPackage
{
public:
/*!
* \brief Creates a new ControlPackageStartRequest object.
*/
ControlPackageStartRequest() : RTDEPackage(PackageType::RTDE_CONTROL_PACKAGE_START)
{
}
virtual ~ControlPackageStartRequest() = default;
/*!
* \brief Generates a serialized package.
*
* \param buffer Buffer to fill with the serialization
*
* \returns The total size of the serialized package
*/
static size_t generateSerializedRequest(uint8_t* buffer);
private:

View File

@@ -83,6 +83,10 @@ struct SerializeVisitor : public boost::static_visitor<size_t>
}
};
/*!
* \brief The DataPackage class handles communication in the form of RTDE data packages both to and
* from the robot. It contains functionality to parse and serialize packages for arbitrary recipes.
*/
class DataPackage : public RTDEPackage
{
public:
@@ -90,16 +94,44 @@ public:
vector6int32_t, vector6uint32_t, std::string>;
DataPackage() = delete;
/*!
* \brief Creates a new DataPackage object, based on a given recipe.
*
* \param recipe The used recipe
*/
DataPackage(const std::vector<std::string>& recipe) : RTDEPackage(PackageType::RTDE_DATA_PACKAGE), recipe_(recipe)
{
}
virtual ~DataPackage() = default;
/*!
* \brief Initializes to contained list with empty values based on the recipe.
*/
void initEmpty();
/*!
* \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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
/*!
* \brief Serializes the package.
*
* \param buffer Buffer to fill with the serialization
*
* \returns The total size of the serialized package
*/
size_t serializePackage(uint8_t* buffer);
/*!
@@ -177,6 +209,11 @@ public:
return true;
}
/*!
* \brief Setter of the recipe id value used to identify the used recipe to the robot.
*
* \param recipe_id The new value
*/
void setRecipeID(const uint8_t& recipe_id)
{
recipe_id_ = recipe_id;

View File

@@ -35,15 +35,34 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief This class handles the package detailing the UR control version sent by the robot.
*/
class GetUrcontrolVersion : public RTDEPackage
{
public:
/*!
* \brief Creates a new GetUrcontrolVersion object.
*/
GetUrcontrolVersion() : RTDEPackage(PackageType::RTDE_GET_URCONTROL_VERSION)
{
}
virtual ~GetUrcontrolVersion() = 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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
VersionInformation version_information_;
@@ -54,14 +73,27 @@ public:
uint32_t build_;
};
/*!
* \brief This class is used to request the used UR control version from the robot.
*/
class GetUrcontrolVersionRequest : public RTDEPackage
{
public:
/*!
* \brief Creates a new GetUrcontrolVersionRequest object.
*/
GetUrcontrolVersionRequest() : RTDEPackage(PackageType::RTDE_GET_URCONTROL_VERSION)
{
}
virtual ~GetUrcontrolVersionRequest() = default;
/*!
* \brief Generates a serialized package.
*
* \param buffer Buffer to fill with the serialization
*
* \returns The total size of the serialized package
*/
static size_t generateSerializedRequest(uint8_t* buffer);
private:

View File

@@ -50,6 +50,9 @@ enum class PackageType : uint8_t
RTDE_CONTROL_PACKAGE_PAUSE = 80 // ascii P
};
/*!
* \brief This class represents the header for RTDE packages.
*/
class PackageHeader
{
public:
@@ -57,11 +60,27 @@ public:
virtual ~PackageHeader() = default;
using _package_size_type = uint16_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)
{
return be16toh(*(reinterpret_cast<_package_size_type*>(buf)));
}
/*!
* \brief Creates a serialization of a header based on given values.
*
* \param buffer The buffer to write the serialization to
* \param package_type The type of the package
* \param payload_length The length of the package's payload
*
* \returns
*/
static size_t serializeHeader(uint8_t* buffer, PackageType package_type, uint16_t payload_length)
{
uint16_t header_size = sizeof(_package_size_type) + sizeof(PackageType);

View File

@@ -35,29 +35,63 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief This class handles the robot's response after trying to set the used RTDE protocol version.
*/
class RequestProtocolVersion : public RTDEPackage
{
public:
/*!
* \brief Creates a new RequestProtocolVersion object.
*/
RequestProtocolVersion() : RTDEPackage(PackageType::RTDE_REQUEST_PROTOCOL_VERSION)
{
}
virtual ~RequestProtocolVersion() = 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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
uint8_t accepted_;
};
/*!
* \brief This class handles producing a request towards the robot to use a specific RTDE protocol
* version.
*/
class RequestProtocolVersionRequest : public RTDEPackage
{
public:
/*!
* \brief Creates a new RequestProtocolVersionRequest object.
*/
RequestProtocolVersionRequest() : RTDEPackage(PackageType::RTDE_REQUEST_PROTOCOL_VERSION)
{
}
virtual ~RequestProtocolVersionRequest() = default;
/*!
* \brief Generates a serialized package.
*
* \param buffer Buffer to fill with the serialization
* \param version RTDE protocol version to request usage of
*
* \returns The total size of the serialized package
*/
static size_t generateSerializedRequest(uint8_t* buffer, uint16_t version);
uint16_t protocol_version_;

View File

@@ -48,22 +48,64 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief The RTDEClient class manages communication over the RTDE interface. It contains the RTDE
* handshake and read and write functionality to and from the robot.
*/
class RTDEClient
{
public:
RTDEClient() = delete;
/*!
* \brief Creates a new RTDEClient object, including a used URStream and Pipeline to handle the
* communication with the robot.
*
* \param robot_ip The IP of the robot
* \param notifier The notifier to use in the pipeline
* \param output_recipe_file Path to the file containing the output recipe
* \param input_recipe_file Path to the file containing the input recipe
*/
RTDEClient(std::string robot_ip, comm::INotifier& notifier, const std::string& output_recipe_file,
const std::string& input_recipe_file);
~RTDEClient() = default;
/*!
* \brief Sets up RTDE communication with the robot. The handshake includes negotiation of the
* used protocol version and setting of input and output recipes.
*
* \returns Success of the handshake
*/
bool init();
/*!
* \brief Triggers the robot to start sending RTDE data packages in the negotiated format.
*
* \returns Success of the requested start
*/
bool start();
/*!
* \brief Reads the pipeline to fetch the next data package.
*
* \param data_package Pointer to set to the next data package
* \param timeout Time to wait if no data package is currently in the queue
*
* \returns True, if a package was fetched successfully
*/
bool getDataPackage(std::unique_ptr<comm::URPackage<PackageHeader>>& data_package, std::chrono::milliseconds timeout);
/*!
* \brief Getter for the frequency the robot will publish RTDE data packages with.
*
* \returns The used frequency
*/
double getMaxFrequency() const
{
return max_frequency_;
}
/*!
* \brief Getter for the UR control version received from the robot.
*
* \returns The VersionInformation received from the robot
*/
VersionInformation getVersion()
{
return urcontrol_version_;
@@ -76,6 +118,12 @@ public:
*/
std::string getIP() const;
/*!
* \brief Getter for the RTDE writer, which is used to send data via the RTDE interface to the
* robot.
*
* \returns A reference to the used RTDEWriter
*/
RTDEWriter& getWriter();
private:

View File

@@ -51,7 +51,20 @@ public:
}
virtual ~RTDEPackage() = 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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
protected:

View File

@@ -38,15 +38,33 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief The RTDE specific parser. Interprets a given byte stream as serialized RTDE packages
* and parses it accordingly.
*/
class RTDEParser : public comm::Parser<PackageHeader>
{
public:
RTDEParser() = delete;
/*!
* \brief Creates a new RTDEParser object, registering the used recipe.
*
* \param recipe The recipe used in RTDE data communication
*/
RTDEParser(const std::vector<std::string>& recipe) : recipe_(recipe)
{
}
virtual ~RTDEParser() = default;
/*!
* \brief Uses the given BinParser to create package objects from the contained serialization.
*
* \param bp A BinParser holding one or more serialized RTDE packages
* \param results A vector of pointers to created RTDE package objects
*
* \returns True, if the byte stream could successfully be parsed as RTDE packages, false
* otherwise
*/
bool parse(comm::BinParser& bp, std::vector<std::unique_ptr<comm::URPackage<PackageHeader>>>& results)
{

View File

@@ -39,19 +39,78 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief The RTDEWriter class offers an abstraction layer to send data to the robot via the RTDE
* interface. Several simple to use functions to create data packages to send exist, which are
* then sent to the robot in an additional thread.
*/
class RTDEWriter
{
public:
RTDEWriter() = delete;
/*!
* \brief Creates a new RTDEWriter object using a given URStream and recipe.
*
* \param stream The URStream to use for communication with the robot
* \param recipe The recipe to use for communication
*/
RTDEWriter(comm::URStream<PackageHeader>* stream, const std::vector<std::string>& recipe);
~RTDEWriter() = default;
/*!
* \brief Starts the writer thread, which periodically clears the queue to write packages to the
* robot.
*
* \param recipe_id The recipe id to use, so the robot correctly identifies the used recipe
*/
void init(uint8_t recipe_id);
/*!
* \brief The writer thread loop, continually serializing and sending packages to the robot.
*/
void run();
/*!
* \brief Creates a package to request setting a new value for the speed slider.
*
* \param speed_slider_fraction The new speed slider fraction as a value between 0.0 and 1.0
*
* \returns Success of the package creation
*/
bool sendSpeedSlider(double speed_slider_fraction);
/*!
* \brief Creates a package to request setting a new value for one of the standard digital output pins.
*
* \param output_pin The pin to change
* \param value The new value
*
* \returns Success of the package creation
*/
bool sendStandardDigitalOutput(uint8_t output_pin, bool value);
/*!
* \brief Creates a package to request setting a new value for one of the configurable digital output pins.
*
* \param output_pin The pin to change
* \param value The new value
*
* \returns Success of the package creation
*/
bool sendConfigurableDigitalOutput(uint8_t output_pin, bool value);
/*!
* \brief Creates a package to request setting a new value for one of the tool output pins.
*
* \param output_pin The pin to change
* \param value The new value
*
* \returns Success of the package creation
*/
bool sendToolDigitalOutput(uint8_t output_pin, bool value);
/*!
* \brief Creates a package to request setting a new value for one of the standard analog output pins.
*
* \param output_pin The pin to change
* \param value The new value
*
* \returns Success of the package creation
*/
bool sendStandardAnalogOuput(uint8_t output_pin, double value);
private:

View File

@@ -34,15 +34,34 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief This class handles RTDE text messages sent by the robot.
*/
class TextMessage : public RTDEPackage
{
public:
/*!
* \brief Creates a new TextMessage object.
*/
TextMessage() : RTDEPackage(PackageType::RTDE_TEXT_MESSAGE)
{
}
virtual ~TextMessage() = 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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
uint8_t message_length_;