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

implemented full rtde handshake to initialize constant publishing to

data packages by the robot
This commit is contained in:
Tristan Schnell
2019-04-11 13:58:34 +02:00
parent 8975957b5f
commit 2eea2bf8fc
2 changed files with 37 additions and 12 deletions

View File

@@ -36,6 +36,8 @@
#include "ur_rtde_driver/comm/producer.h"
#include "ur_rtde_driver/rtde/data_package.h"
#include "ur_rtde_driver/rtde/request_protocol_version.h"
#include "ur_rtde_driver/rtde/control_package_setup_outputs.h"
#include "ur_rtde_driver/rtde/control_package_start.h"
static const int UR_RTDE_PORT = 30004;
static const std::string PIPELINE_NAME = "RTDE Data Pipeline";
@@ -50,6 +52,8 @@ public:
RTDEClient() = delete;
RTDEClient(std::string ROBOT_IP, comm::INotifier& notifier);
~RTDEClient() = default;
bool init();
bool start();
bool getDataPackage(std::unique_ptr<comm::URPackage<PackageHeader>>& data_package, std::chrono::milliseconds timeout);
private:
@@ -57,6 +61,8 @@ private:
RTDEParser parser_;
comm::URProducer<PackageHeader> prod_;
comm::Pipeline<PackageHeader> pipeline_;
std::vector<std::string> readRecipe();
};
} // namespace rtde_interface