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

Merge branch 'update_doxygen' into master

This commit is contained in:
Felix Mauch
2019-09-25 09:56:36 +02:00
41 changed files with 1310 additions and 88 deletions

View File

@@ -1,4 +1,4 @@
- builder: doxygen
name: C++ API
output_dir: c++
file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'
name: C++ API
output_dir: c++
file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox'

View File

@@ -37,29 +37,16 @@ namespace ur_driver
{
namespace comm
{
/*!
* \brief The BinParser class handles a byte buffer and functionality to iteratively parse the
* content.
*/
class BinParser
{
private:
uint8_t *buf_pos_, *buf_end_;
BinParser& parent_;
public:
BinParser(uint8_t* buffer, size_t buf_len) : buf_pos_(buffer), buf_end_(buffer + buf_len), parent_(*this)
{
assert(buf_pos_ <= buf_end_);
}
BinParser(BinParser& parent, size_t sub_len)
: buf_pos_(parent.buf_pos_), buf_end_(parent.buf_pos_ + sub_len), parent_(parent)
{
assert(buf_pos_ <= buf_end_);
}
~BinParser()
{
parent_.buf_pos_ = buf_pos_;
}
// Decode from network encoding (big endian) to host encoding
template <typename T>
T decode(T val)
@@ -91,6 +78,45 @@ public:
return be64toh(val);
}
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)
{
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)
: buf_pos_(parent.buf_pos_), buf_end_(parent.buf_pos_ + sub_len), parent_(parent)
{
assert(buf_pos_ <= buf_end_);
}
/*!
* \brief Deconstructor for the BinParser.
*/
~BinParser()
{
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>
T peek()
{
@@ -103,6 +129,12 @@ public:
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>
void parse(T& val)
{
@@ -110,12 +142,22 @@ public:
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)
{
uint64_t inner;
parse<uint64_t>(inner);
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)
{
uint32_t inner;
@@ -123,8 +165,15 @@ public:
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)
{
uint8_t inner;
@@ -132,6 +181,11 @@ public:
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)
{
for (size_t i = 0; i < val.size(); ++i)
@@ -140,6 +194,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)
{
for (size_t i = 0; i < val.size(); ++i)
@@ -148,6 +207,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)
{
for (size_t i = 0; i < val.size(); ++i)
@@ -156,6 +220,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)
{
for (size_t i = 0; i < val.size(); ++i)
@@ -164,6 +233,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)
{
buffer_length = buf_end_ - buf_pos_;
@@ -172,18 +247,33 @@ public:
consume();
}
/*!
* \brief Parses the remaining bytes as a string.
*
* \param val Reference to write the parsed value to
*/
void parseRemainder(std::string& val)
{
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)
{
val.assign(reinterpret_cast<char*>(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)
{
uint8_t len;
@@ -191,6 +281,13 @@ public:
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>
void parse(std::array<T, N>& array)
{
@@ -200,6 +297,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>
void parse(std::bitset<N>& set)
{
@@ -208,30 +312,60 @@ public:
set = std::bitset<N>(val);
}
/*!
* \brief Sets the current buffer position to the end of the buffer, finishing parsing.
*/
void consume()
{
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)
{
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)
{
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>
bool checkSize(void)
{
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()
{
return buf_pos_ == buf_end_;
}
/*!
* \brief Logs debugging information about the BinParser object.
*/
void debug()
{
LOG_DEBUG("BinParser: %p - %p (%zu bytes)", buf_pos_, buf_end_, buf_end_ - buf_pos_);

View File

@@ -49,8 +49,21 @@ public:
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;
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const = 0;
private:

View File

@@ -35,9 +35,22 @@ namespace ur_driver
{
namespace comm
{
/*!
* \brief A helper class to serialize packages. Contains methods for serializing all relevant
* datatypes.
*/
class PackageSerializer
{
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>
static size_t serialize(uint8_t* buffer, T val)
{
@@ -47,6 +60,14 @@ public:
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)
{
size_t size = sizeof(double);
@@ -57,6 +78,14 @@ public:
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)
{
const uint8_t* c_val = reinterpret_cast<const uint8_t*>(val.c_str());

View File

@@ -41,10 +41,10 @@ public:
virtual ~Parser() = default;
/*!
* \brief declares the parse function.
* \brief Declares the parse function.
*
* \param bp instant of class binaryParser
* \param results unique pointer
* \param bp Instance of class binaryParser
* \param results A unique pointer
*/
virtual bool parse(BinParser& bp, std::vector<std::unique_ptr<URPackage<HeaderT>>>& results) = 0;
using _header_type = HeaderT;

View File

@@ -36,27 +36,57 @@ namespace comm
// TODO: Remove these!!!
using namespace moodycamel;
/*!
* \brief Parent class for for arbitrary consumers.
*
* @tparam T Type of the consumed products
*/
template <typename T>
class IConsumer
{
public:
/*!
* \brief Set-up functionality of the consumer.
*/
virtual void setupConsumer()
{
}
/*!
* \brief Fully tears down the consumer - by default no difference to stopping it.
*/
virtual void teardownConsumer()
{
stopConsumer();
}
/*!
* \brief Stops the consumer.
*/
virtual void stopConsumer()
{
}
/*!
* \brief Functionality for handling consumer timeouts.
*/
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;
};
/*!
* \brief Consumer, that allows one product to be consumed by multiple arbitrary
* conusmers.
*
* @tparam T Type of the consumed products
*/
template <typename T>
class MultiConsumer : public IConsumer<T>
{
@@ -64,10 +94,18 @@ private:
std::vector<IConsumer<T>*> consumers_;
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)
{
}
/*!
* \brief Sets up all registered consumers.
*/
virtual void setupConsumer()
{
for (auto& con : consumers_)
@@ -75,6 +113,9 @@ public:
con->setupConsumer();
}
}
/*!
* \brief Tears down all registered consumers.
*/
virtual void teardownConsumer()
{
for (auto& con : consumers_)
@@ -82,6 +123,9 @@ public:
con->teardownConsumer();
}
}
/*!
* \brief Stops all registered consumers.
*/
virtual void stopConsumer()
{
for (auto& con : consumers_)
@@ -89,6 +133,9 @@ public:
con->stopConsumer();
}
}
/*!
* \brief Triggers timeout functionality for all registered consumers.
*/
virtual void onTimeout()
{
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 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>
class IProducer
{
public:
/*!
* \brief Set-up functionality of the producers.
*/
virtual void setupProducer()
{
}
/*!
* \brief Fully tears down the producer - by default no difference to stopping it.
*/
virtual void teardownProducer()
{
stopProducer();
}
/*!
* \brief Stops the producer.
*/
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;
};
/*!
* \brief Parent class for notifiers.
*/
class INotifier
{
public:
/*!
* \brief Start notification.
*/
virtual void started(std::string name)
{
}
/*!
* \brief Stop notification.
*/
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>
class Pipeline
{
@@ -145,21 +236,44 @@ public:
typedef std::chrono::high_resolution_clock Clock;
typedef Clock::time_point Time;
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)
: 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)
: 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()
{
LOG_DEBUG("Destructing pipeline");
stop();
}
/*!
* \brief Starts the producer and, if existing, the consumer in new threads.
*/
void run()
{
if (running_)
@@ -173,6 +287,9 @@ public:
notifier_.started(name_);
}
/*!
* \brief Stops the pipeline and all running threads.
*/
void stop()
{
if (!running_)
@@ -193,6 +310,14 @@ public:
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)
{
return queue_.waitDequeTimed(product, timeout);

View File

@@ -30,6 +30,12 @@ namespace ur_driver
{
namespace comm
{
/*!
* \brief A general producer for URPackages. Implements funcionality to produce packages by
* reading and parsing from a byte stream.
*
* @tparam HeaderT Header type of packages to produce.
*/
template <typename HeaderT>
class URProducer : public IProducer<HeaderT>
{
@@ -39,10 +45,19 @@ private:
std::chrono::seconds timeout_;
public:
/*!
* \brief Creates a URProducer object, registering a stream and a parser.
*
* \param stream The stream to read from
* \param parser The parser to use to interpret received byte information
*/
URProducer(URStream<HeaderT>& stream, Parser<HeaderT>& parser) : stream_(stream), parser_(parser), timeout_(1)
{
}
/*!
* \brief Triggers the stream to connect to the robot.
*/
void setupProducer()
{
timeval tv;
@@ -54,14 +69,27 @@ public:
throw UrException("Failed to connect to robot. Please check if the robot is booted and connected.");
}
}
/*!
* \brief Tears down the producer. Currently no special handling needed.
*/
void teardownProducer()
{
stopProducer();
}
/*!
* \brief Stops the producer. Currently no functionality needed.
*/
void stopProducer()
{
}
/*!
* \brief Attempts to read byte stream from the robot and parse it as a URPackage.
*
* \param products Unique pointer to hold the produced package
*
* \returns Success of reading and parsing the package
*/
bool tryGet(std::vector<std::unique_ptr<URPackage<HeaderT>>>& products)
{
// 4KB should be enough to hold any packet received from UR

View File

@@ -37,10 +37,19 @@ namespace ur_driver
{
namespace comm
{
/*!
* \brief The ReverseInterface class handles communication to the robot. It starts a server and
* waits for the robot to connect via its URCaps program.
*/
class ReverseInterface
{
public:
ReverseInterface() = delete;
/*!
* \brief Creates a ReverseInterface object including a URServer.
*
* \param port Port the Server is started on
*/
ReverseInterface(uint32_t port) : server_(port)
{
if (!server_.bind())
@@ -52,11 +61,22 @@ public:
throw std::runtime_error("Failed to accept robot connection");
}
}
/*!
* \brief Disconnects possible clients so the reverse interface object can be safely destroyed.
*/
~ReverseInterface()
{
server_.disconnectClient();
}
/*!
* \brief Writes needed information to the robot to be read by the URCaps program.
*
* \param positions A vector of joint position targets for the robot
* \param type An additional integer used to command the program to end when needed
*
* \returns True, if the write was performed successfully, false otherwise.
*/
bool write(const vector6d_t* positions, const int32_t type = 2)
{
uint8_t buffer[sizeof(uint32_t) * 7];
@@ -80,6 +100,11 @@ public:
return server_.write(buffer, sizeof(buffer), written);
}
/*!
* \brief Reads a keepalive signal from the robot.
*
* \returns The received keepalive string or the empty string, if nothing was received
*/
std::string readKeepalive()
{
size_t buf_len = 16;
@@ -97,6 +122,10 @@ public:
}
}
private:
URServer server_;
static const int32_t MULT_JOINTSTATE = 1000000;
template <typename T>
size_t append(uint8_t* buffer, T& val)
{
@@ -104,10 +133,6 @@ public:
std::memcpy(buffer, &val, s);
return s;
}
private:
URServer server_;
static const int32_t MULT_JOINTSTATE = 1000000;
};
} // namespace comm

View File

@@ -36,10 +36,20 @@ namespace ur_driver
{
namespace comm
{
/*!
* \brief The ScriptSender class starts a URServer for a robot to connect to and waits for a
* request to receive a program. This program is then delivered to the requesting robot.
*/
class ScriptSender
{
public:
ScriptSender() = delete;
/*!
* \brief Creates a ScriptSender object, including a new URServer and not yet started thread.
*
* \param port Port to start the server on
* \param program Program to send to the robot upon request
*/
ScriptSender(uint32_t port, const std::string& program) : server_(port), script_thread_(), program_(program)
{
if (!server_.bind())
@@ -48,6 +58,9 @@ public:
}
}
/*!
* \brief Starts the thread that handles program requests by a robot.
*/
void start()
{
script_thread_ = std::thread(&ScriptSender::runScriptSender, this);

View File

@@ -34,6 +34,10 @@ namespace comm
{
#define MAX_SERVER_BUF_LEN 50
/*!
* \brief The URServer class abstracts communication with the robot. It opens a socket on a given
* port and waits for a robot to connect, at which point two way communication can be established.
*/
class URServer : private comm::TCPSocket
{
private:
@@ -44,13 +48,56 @@ protected:
virtual bool open(int socket_fd, struct sockaddr* address, size_t address_len);
public:
/*!
* \brief Creates a URServer object with a given port.
*
* \param port The port to open a socket on
*/
URServer(int port);
/*!
* \brief Closes the socket to allow for destruction of the object.
*/
~URServer();
/*!
* \brief Getter for the server IP.
*
* \returns The IP of the server
*/
std::string getIP();
/*!
* \brief Binds to server's port, setting up a socket if possible.
*
* \returns Success of setting up the socket
*/
bool bind();
/*!
* \brief Waits for a robot to connect to the socket.
*
* \returns True, if a robot successfully connected, false otherwise.
*/
bool accept();
/*!
* \brief Triggers a disconnect of the currently connected robot.
*/
void disconnectClient();
/*!
* \brief Reads the byte-stream from the robot to the next linebreak.
*
* \param buffer The buffer to write the received bytes to
* \param buf_len Size of the buffer
*
* \returns True if a successful read occurred, false otherwise
*/
bool readLine(char* buffer, size_t buf_len);
/*!
* \brief Writes a buffer to the robot.
*
* \param buf The buffer to write from
* \param buf_len The length to write
* \param written A reference used to indicate how many bytes were written
*
* \returns Success of the write
*/
bool write(const uint8_t* buf, size_t buf_len, size_t& written);
};
} // namespace comm

View File

@@ -36,6 +36,12 @@ namespace ur_driver
{
namespace comm
{
/*!
* \brief The ShellConsumer class is a simple consumer that writes a readable representation to
* the logging info channel.
*
* @tparam HeaderT Header type of the packages to consume
*/
template <typename HeaderT>
class ShellConsumer : public IConsumer<URPackage<HeaderT>>
{
@@ -43,6 +49,13 @@ public:
ShellConsumer() = default;
virtual ~ShellConsumer() = default;
/*!
* \brief Consumes a package, writing a human readable representation to the logging.
*
* \param product The package to consume
*
* \returns True if the output was successful
*/
virtual bool consume(std::shared_ptr<URPackage<HeaderT>> product)
{
LOG_INFO("%s", product->toString().c_str());

View File

@@ -56,7 +56,7 @@ public:
/*!
* \brief Connects to the configured socket.
*
* \returns True on success, false if connection could not be established.
* \returns True on success, false if connection could not be established
*/
bool connect()
{
@@ -89,7 +89,7 @@ public:
* \param[in] buf_len Number of bytes allocated for the buffer
* \param[out] read Number of bytes actually read from the socket
*
* \returns True on success, false on error, e.g. the buffer is smaller than the package size.
* \returns True on success, false on error, e.g. the buffer is smaller than the package size
*/
bool read(uint8_t* buf, const size_t buf_len, size_t& read);
@@ -98,9 +98,9 @@ public:
*
* \param[in] buf Byte stream that should be sent
* \param[in] buf_len Number of bytes in buffer
* \param[out] written Number of bytes actually written to the socket.
* \param[out] written Number of bytes actually written to the socket
*
* \returns false if sending went wrong
* \returns False if sending went wrong
*/
bool write(const uint8_t* buf, const size_t buf_len, size_t& written);

View File

@@ -31,12 +31,15 @@ namespace ur_driver
{
namespace comm
{
/*!
* \brief State the socket can be in
*/
enum class SocketState
{
Invalid,
Connected,
Disconnected,
Closed
Invalid, ///< Socket is initialized or setup failed
Connected, ///< Socket is connected and ready to use
Disconnected, ///< Socket is disconnected and cannot be used
Closed ///< Connection to socket got closed
};
/*!
@@ -59,18 +62,38 @@ protected:
bool setup(std::string& host, int port);
public:
/*!
* \brief Creates a TCPSocket object
*/
TCPSocket();
virtual ~TCPSocket();
/*!
* \brief Getter for the state of the socket.
*
* \returns Returns the current state of the socket
*/
SocketState getState()
{
return state_;
}
/*!
* \brief Getter for the file descriptor of the socket.
*
* \returns The file descriptor of the socket
*/
int getSocketFD()
{
return socket_fd_;
}
/*!
* \brief Setter for the file descriptor of the socket.
*
* \param socket_fd The new value
*
* \returns False, if the socket is in state connected
*/
bool setSocketFD(int socket_fd);
/*!
@@ -83,7 +106,7 @@ public:
/*!
* \brief Reads one byte from the socket
*
* \param character[out] Target buffer
* \param[out] character Target buffer
*
* \returns True on success, false otherwise
*/

View File

@@ -55,6 +55,9 @@ private:
/* data */
};
/*!
* \brief A specialized exception representing detection of a not supported UR control version.
*/
class VersionMismatch : public UrException
{
public:
@@ -83,6 +86,9 @@ private:
std::string text_;
};
/*!
* \brief A specialized exception representing that communication to the tool is not possible.
*/
class ToolCommNotAvailable : public VersionMismatch
{
public:

View File

@@ -40,6 +40,9 @@ namespace primary_interface
{
static const int UR_PRIMARY_PORT = 30001;
static const int UR_SECONDARY_PORT = 30002;
/*!
* \brief Possible RobotPackage types
*/
enum class RobotPackageType : int8_t
{
DISCONNECT = -1,
@@ -52,6 +55,9 @@ enum class RobotPackageType : int8_t
PROGRAM_STATE_MESSAGE = 25
};
/*!
* \brief This class represents the header for primary packages.
*/
class PackageHeader
{
public:
@@ -60,6 +66,13 @@ public:
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)
{
return be32toh(*(reinterpret_cast<_package_size_type*>(buf)));

View File

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

View File

@@ -35,12 +35,25 @@ namespace ur_driver
{
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>
{
public:
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)
{
int32_t packet_size;

View File

@@ -34,6 +34,9 @@ namespace ur_driver
{
namespace primary_interface
{
/*!
* \brief Possible RobotMessage types
*/
enum class RobotMessagePackageType : uint8_t
{
ROBOT_MESSAGE_TEXT = 0,
@@ -46,16 +49,39 @@ enum class RobotMessagePackageType : uint8_t
ROBOT_MESSAGE_REQUEST_VALUE = 9,
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:
/*!
* \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)
{
}
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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
uint64_t timestamp_;

View File

@@ -34,17 +34,39 @@ namespace ur_driver
{
namespace primary_interface
{
/*!
* \brief The VersionMessage class handles the version messages sent via the primary UR interface.
*/
class VersionMessage : public RobotMessage
{
public:
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)
{
}
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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
virtual std::string toString() const;
int8_t project_name_length_;

View File

@@ -37,6 +37,9 @@ namespace ur_driver
{
namespace primary_interface
{
/*!
* \brief Possible RobotState types
*/
enum class RobotStateType : uint8_t
{
ROBOT_MODE_DATA = 0,
@@ -58,15 +61,34 @@ class RobotState : public PrimaryPackage
{
public:
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)
{
}
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)
{
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
{
std::stringstream ss;

View File

@@ -43,14 +43,38 @@ class KinematicsInfo : public RobotState
{
public:
KinematicsInfo() = delete;
/*!
* \brief Creates a new KinematicsInfo object.
*
* \param type The type of RobotState message received
*/
KinematicsInfo(const RobotStateType type) : RobotState(type)
{
}
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);
/*!
* \brief Produces a human readable representation of the package object.
*
* \returns A string representing the object
*/
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;
vector6uint32_t checksum_;

View File

@@ -52,6 +52,9 @@
namespace ur_driver
{
/*!
* \brief Possible states for robot control
*/
enum class PausingState
{
PAUSED,
@@ -59,25 +62,91 @@ enum class PausingState
RAMPUP
};
/*!
* \brief The HardwareInterface class handles the interface between the ROS system and the main
* driver. It contains the read and write methods of the main control loop and registers various ROS
* topics and services.
*/
class HardwareInterface : public hardware_interface::RobotHW
{
public:
/*!
* \brief Creates a new HardwareInterface object.
*/
HardwareInterface();
virtual ~HardwareInterface() = default;
/*!
* \brief Handles the setup functionality for the ROS interface. This includes parsing ROS
* parameters, creating interfaces, starting the main driver and advertising ROS services.
*
* \param root_nh Root level ROS node handle
* \param robot_hw_nh ROS node handle for the robot namespace
*
* \returns True, if the setup was performed successfully
*/
virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) override;
/*!
* \brief Read method of the control loop. Reads a RTDE package from the robot and handles and
* publishes the information as needed.
*
* \param time Current time
* \param period Duration of current control loop iteration
*/
virtual void read(const ros::Time& time, const ros::Duration& period) override;
/*!
* \brief Write method of the control loop. Writes target joint positions to the robot to be read
* by its URCaps program.
*
* \param time Current time
* \param period Duration of current control loop iteration
*/
virtual void write(const ros::Time& time, const ros::Duration& period) override;
/*!
* \brief Preparation to start and stop loaded controllers.
*
* \param start_list List of controllers to start
* \param stop_list List of controllers to stop
*
* \returns True, if the controllers can be switched
*/
virtual bool prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) override;
/*!
* \brief Starts and stops controllers.
*
* \param start_list List of controllers to start
* \param stop_list List of controllers to stop
*/
virtual void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list) override;
/*!
* \brief Getter for the current control frequency
*
* \returns The used control frequency
*/
uint32_t getControlFrequency() const;
/*!
* \brief Checks if the URCaps program is running on the robot.
*
* \returns True, if the program is currently running, false otherwise.
*/
bool isRobotProgramRunning() const;
/*!
* \brief Callback to handle a change in the current state of the URCaps program running on the
* robot.
*
* \param program_running The new state of the program
*/
void handleRobotProgramState(bool program_running);
/*!
* \brief Checks if a reset of the ROS controllers is necessary.
*
* \returns Necessity of ROS controller reset
*/
bool shouldResetControllers();
protected:

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

@@ -38,6 +38,9 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief Possible values for the runtime state
*/
enum class RUNTIME_STATE : uint32_t
{
STOPPING = 0,
@@ -48,41 +51,10 @@ enum class RUNTIME_STATE : uint32_t
RESUMING = 5
};
struct ParseVisitor : public boost::static_visitor<>
{
template <typename T>
void operator()(T& d, comm::BinParser& bp) const
{
bp.parse(d);
}
};
struct StringVisitor : public boost::static_visitor<std::string>
{
template <typename T>
std::string operator()(T& d) const
{
std::stringstream ss;
ss << d;
return ss.str();
}
};
struct SizeVisitor : public boost::static_visitor<uint16_t>
{
template <typename T>
uint16_t operator()(T& d) const
{
return sizeof(d);
}
};
struct SerializeVisitor : public boost::static_visitor<size_t>
{
template <typename T>
size_t operator()(T& d, uint8_t* buffer) const
{
return comm::PackageSerializer::serialize(buffer, d);
}
};
/*!
* \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 +62,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);
/*!
@@ -109,6 +109,7 @@ public:
*
* \param name The string identifier for the data field as used in the documentation.
* \param val Target variable. Make sure, it's the correct type.
* \exception boost::bad_get if the type under given \p name does not match the template type T.
*
* \returns True on success, false if the field cannot be found inside the package.
*/
@@ -134,6 +135,7 @@ public:
*
* \param name The string identifier for the data field as used in the documentation.
* \param val Target variable. Make sure, it's the correct type.
* \exception boost::bad_get if the type under given \p name does not match the template type T.
*
* \returns True on success, false if the field cannot be found inside the package.
*/
@@ -177,6 +179,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;
@@ -188,6 +195,41 @@ private:
uint8_t recipe_id_;
std::unordered_map<std::string, _rtde_type_variant> data_;
std::vector<std::string> recipe_;
struct ParseVisitor : public boost::static_visitor<>
{
template <typename T>
void operator()(T& d, comm::BinParser& bp) const
{
bp.parse(d);
}
};
struct StringVisitor : public boost::static_visitor<std::string>
{
template <typename T>
std::string operator()(T& d) const
{
std::stringstream ss;
ss << d;
return ss.str();
}
};
struct SizeVisitor : public boost::static_visitor<uint16_t>
{
template <typename T>
uint16_t operator()(T& d) const
{
return sizeof(d);
}
};
struct SerializeVisitor : public boost::static_visitor<size_t>
{
template <typename T>
size_t operator()(T& d, uint8_t* buffer) const
{
return comm::PackageSerializer::serialize(buffer, d);
}
};
};
} // namespace rtde_interface

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

@@ -38,6 +38,9 @@ namespace ur_driver
{
namespace rtde_interface
{
/*!
* \brief Possible package types
*/
enum class PackageType : uint8_t
{
RTDE_REQUEST_PROTOCOL_VERSION = 86, // ascii V
@@ -50,6 +53,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 +63,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), protocol_version_(1)
{
}
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 sendStandardAnalogOutput(uint8_t output_pin, double value);
private:

View File

@@ -34,16 +34,37 @@ 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.
*
* \param protocol_version Protocol version used for the RTDE communication
*/
TextMessage(uint16_t protocol_version)
: RTDEPackage(PackageType::RTDE_TEXT_MESSAGE), protocol_version_(protocol_version)
{
}
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_;

View File

@@ -33,27 +33,63 @@
namespace ur_driver
{
/*!
* \brief The CalibrationChecker class consumes primary packages ignoring all but KinematicsInfo
* packages. These are then checked against the used kinematics to see if the correct calibration
* is used.
*/
class CalibrationChecker : public comm::IConsumer<comm::URPackage<primary_interface::PackageHeader>>
{
public:
/*!
* \brief Creates a new CalibrationChecker object with an expected hash calculated from the used
* kinematics.
*
* \param expected_hash The expected kinematics hash
*/
CalibrationChecker(const std::string& expected_hash);
virtual ~CalibrationChecker() = default;
/*!
* \brief Empty setup function, as no setup is needed.
*/
virtual void setupConsumer()
{
}
/*!
* \brief Tears down the consumer.
*/
virtual void teardownConsumer()
{
}
/*!
* \brief Stops the consumer.
*/
virtual void stopConsumer()
{
}
/*!
* \brief Handles timeouts.
*/
virtual void onTimeout()
{
}
/*!
* \brief Consumes a package, checking its hash if it is a KinematicsInfo package. If the hash
* does not match the expected hash, an error is logged.
*
* \param product The package to consume
*
* \returns True, if the package was consumed correctly
*/
virtual bool consume(std::shared_ptr<comm::URPackage<primary_interface::PackageHeader>> product);
/*!
* \brief Used to make sure the calibration check is not performed several times.
*
* \returns True, if the calibration was already checked, false otherwise
*/
bool isChecked()
{
return checked_;

View File

@@ -34,13 +34,19 @@
namespace ur_driver
{
/*!
* \brief Possible values for the tool voltage
*/
enum class ToolVoltage : int
{
OFF = 0,
_12V = 12,
_24V = 24
OFF = 0, ///< 0V
_12V = 12, ///< 12V
_24V = 24 ///< 24V
};
/*!
* \brief Possible values for th parity flag
*/
enum class Parity : int
{
NONE = 0,
@@ -62,11 +68,24 @@ public:
using Datatype = T;
/*!
* \brief Create a new Limited object
*
* \param lower Lower boundary used for this Limited object
* \param upper Upper boundary used for this Limited object
*/
Limited(const T lower, const T upper) : lower_(lower), upper_(upper)
{
data_ = lower_;
}
/*!
* \brief Set the data field with a given value
*
* If the given value is out of the configured range, an exception is thrown.
*
* \param data
*/
void setData(const T data)
{
if (data >= lower_ && data <= upper_)
@@ -79,6 +98,9 @@ public:
}
}
/*!
* \brief Returns the data stored in this object
*/
T getData() const
{
return data_;
@@ -103,59 +125,110 @@ public:
using RxIdleCharsT = Limited<float>;
using TxIdleCharsT = Limited<float>;
/*!
* \brief Setup the tool voltage that will be configured on the robot. This will not immediately
* change values on the robot, it will only be stored inside the ToolCommSetup object.
*/
void setToolVoltage(const ToolVoltage tool_voltage)
{
tool_voltage_ = tool_voltage;
}
/*!
* \brief Return the tool voltage currently stored
*/
ToolVoltage getToolVoltage() const
{
return tool_voltage_;
}
/*!
* \brief Setup the tool communication parity that will be configured on the robot. This will not immediately
* change values on the robot, it will only be stored inside the ToolCommSetup object.
*/
void setParity(const Parity parity)
{
parity_ = parity;
}
/*!
* \brief Return the parity currently stored
*/
Parity getParity() const
{
return parity_;
}
/*!
* \brief Setup the tool communication baud rate that will be configured on the robot. This will not immediately
* change values on the robot, it will only be stored inside the ToolCommSetup object.
*
* \param baud_rate must be one of baud_rates_allowed_ or an exception will be thrown
*/
void setBaudRate(const uint32_t baud_rate);
/*!
* \brief Return the baud rate currently stored
*/
uint32_t getBaudRate() const
{
return baud_rate_;
};
/*!
* \brief Setup the tool communication number of stop bits that will be configured on the robot. This will not
* immediately change values on the robot, it will only be stored inside the ToolCommSetup object.
*
* \param stop_bits must be inside [1,2] or this will throw an exception.
*/
void setStopBits(const StopBitsT::Datatype stop_bits)
{
stop_bits_.setData(stop_bits);
}
/*!
* \brief Return the number of stop bits currently stored
*/
StopBitsT::Datatype getStopBits() const
{
return stop_bits_.getData();
}
/*!
* \brief Setup the tool communication number of idle chars for the rx channel that will be configured on the robot.
* This will not immediately change values on the robot, it will only be stored inside the ToolCommSetup object.
*
* \param rx_idle_chars must be inside [1.0, 40] or this will throw an exception.
*/
void setRxIdleChars(const RxIdleCharsT::Datatype rx_idle_chars)
{
rx_idle_chars_.setData(rx_idle_chars);
}
/*!
* \brief Return the number of rx idle chars currently stored
*/
RxIdleCharsT::Datatype getRxIdleChars() const
{
return rx_idle_chars_.getData();
}
/*!
* \brief Setup the tool communication number of idle chars for the tx channel that will be configured on the robot.
* This will not immediately change values on the robot, it will only be stored inside the ToolCommSetup object.
*
* \param tx_idle_chars must be inside [0.0, 40] or this will throw an exception.
*/
void setTxIdleChars(const TxIdleCharsT::Datatype tx_idle_chars)
{
tx_idle_chars_.setData(tx_idle_chars);
}
/*!
* \brief Return the number of tx idle chars currently stored
*/
TxIdleCharsT::Datatype getTxIdleChars() const
{
return tx_idle_chars_.getData();
}
private:
const std::set<uint32_t> baud_rates_{ 9600, 19200, 38400, 57600, 115200, 10000000, 2000000, 5000000 };
const std::set<uint32_t> baud_rates_allowed_{ 9600, 19200, 38400, 57600, 115200, 10000000, 2000000, 5000000 };
ToolVoltage tool_voltage_;
Parity parity_;

View File

@@ -49,8 +49,13 @@ public:
* \brief Constructs a new UrDriver object.
*
* \param robot_ip IP-address under which the robot is reachable.
* \param script_file URScript file that should be sent to the robot
* \param tool_comm_setup Configuration for using the tool communication
* \param script_file URScript file that should be sent to the robot.
* \param output_recipe_file Filename where the output recipe is stored in.
* \param input_recipe_file Filename where the input recipe is stored in.
* \param handle_program_state Function handle to a callback on program state changes.
* \param tool_comm_setup Configuration for using the tool communication.
* \param calibration_checksum Expected checksum of calibration. Will be matched against the
* calibration reported by the robot.
*/
UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
const std::string& input_recipe_file, std::function<void(bool)> handle_program_state,
@@ -59,7 +64,12 @@ public:
* \brief Constructs a new UrDriver object.
*
* \param robot_ip IP-address under which the robot is reachable.
* \param script_file URScript file that should be sent to the robot
* \param script_file URScript file that should be sent to the robot.
* \param output_recipe_file Filename where the output recipe is stored in.
* \param input_recipe_file Filename where the input recipe is stored in.
* \param handle_program_state Function handle to a callback on program state changes.
* \param calibration_checksum Expected checksum of calibration. Will be matched against the
* calibration reported by the robot.
*/
UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
const std::string& input_recipe_file, std::function<void(bool)> handle_program_state,
@@ -113,10 +123,24 @@ public:
*/
bool stopControl();
/*!
* \brief Starts the watchdog checking if the URCaps program is running on the robot and it is
* ready to receive control commands.
*/
void startWatchdog();
/*!
* \brief Checks if the kinematics information in the used model fits the actual robot.
*
* \param checksum Hash of the used kinematics information
*/
void checkCalibration(const std::string& checksum);
/*!
* \brief Getter for the RTDE writer used to write to the robot's RTDE interface.
*
* \returns The active RTDE writer
*/
rtde_interface::RTDEWriter& getRTDEWriter();
/*!

View File

@@ -28,8 +28,13 @@
#ifndef UR_RTDE_DRIVER_UR_VERSION_INFORMATION_H_INCLUDED
#define UR_RTDE_DRIVER_UR_VERSION_INFORMATION_H_INCLUDED
#include <ur_rtde_driver/types.h>
namespace ur_driver
{
/*!
* \brief Struct containing a robot's version information
*/
struct VersionInformation
{
VersionInformation()
@@ -39,10 +44,10 @@ struct VersionInformation
bugfix = 0;
build = 0;
}
uint32_t major;
uint32_t minor;
uint32_t bugfix;
uint32_t build;
uint32_t major; ///< Major version number
uint32_t minor; ///< Minor version number
uint32_t bugfix; ///< Bugfix version number
uint32_t build; ///< Build number
};
} // namespace ur_driver

View File

@@ -7,6 +7,8 @@
<author>Thomas Timm Andersen</author>
<author>Simon Rasmussen</author>
<author>Felix Mauch</author>
<author>Lea Steffen</author>
<author>Tristan Schnell</author>
<maintainer email="mauch@fzi.de">Felix Mauch</maintainer>
<license>Apache 2.0</license>
<license>BSD 2-clause</license>
@@ -45,7 +47,7 @@
<exec_depend>velocity_controllers</exec_depend>
<export>
<rosdoc config="rosdoc.yaml" />
<rosdoc config="doc/rosdoc.yaml" />
</export>
</package>

View File

@@ -41,7 +41,7 @@ ToolCommSetup::ToolCommSetup()
void ToolCommSetup::setBaudRate(const uint32_t baud_rate)
{
if (baud_rates_.find(baud_rate) != baud_rates_.end())
if (baud_rates_allowed_.find(baud_rate) != baud_rates_allowed_.end())
{
baud_rate_ = baud_rate;
}