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

use rtde interface to query control pc's IP

This commit is contained in:
Felix Mauch
2019-07-16 11:21:09 +02:00
parent 7dd9bc0c55
commit 4a953be4a4
5 changed files with 15 additions and 8 deletions

View File

@@ -78,7 +78,7 @@ public:
* *
* \returns The IP address of the local machine. * \returns The IP address of the local machine.
*/ */
std::string getIP(); std::string getIP() const;
/*! /*!
* \brief Reads one byte from the socket * \brief Reads one byte from the socket

View File

@@ -67,6 +67,13 @@ public:
return urcontrol_version_; return urcontrol_version_;
} }
/*!
* \brief Returns the IP address (of the machine running this driver) used for the socket connection.
*
* \returns The IP address as a string (e.g. "192.168.0.1")
*/
std::string getIP() const;
private: private:
comm::URStream<PackageHeader> stream_; comm::URStream<PackageHeader> stream_;
std::vector<std::string> recipe_; std::vector<std::string> recipe_;

View File

@@ -125,7 +125,7 @@ void TCPSocket::close()
socket_fd_ = -1; socket_fd_ = -1;
} }
std::string TCPSocket::getIP() std::string TCPSocket::getIP() const
{ {
sockaddr_in name; sockaddr_in name;
socklen_t len = sizeof(name); socklen_t len = sizeof(name);

View File

@@ -132,5 +132,10 @@ bool RTDEClient::getDataPackage(std::unique_ptr<comm::URPackage<PackageHeader>>&
{ {
return pipeline_.getLatestProduct(data_package, timeout); return pipeline_.getLatestProduct(data_package, timeout);
} }
std::string RTDEClient::getIP() const
{
return stream_.getIP();
}
} // namespace rtde_interface } // namespace rtde_interface
} // namespace ur_driver } // namespace ur_driver

View File

@@ -31,7 +31,6 @@
//---------------------------------------------------------------------- //----------------------------------------------------------------------
#include "ur_rtde_driver/ur/ur_driver.h" #include "ur_rtde_driver/ur/ur_driver.h"
#include "ur_rtde_driver/primary/package_header.h"
#include "ur_rtde_driver/exceptions.h" #include "ur_rtde_driver/exceptions.h"
#include <memory> #include <memory>
@@ -65,11 +64,7 @@ ur_driver::UrDriver::UrDriver(const std::string& robot_ip, const std::string& sc
rtde_frequency_ = rtde_client_->getMaxFrequency(); rtde_frequency_ = rtde_client_->getMaxFrequency();
servoj_time_ = 1.0 / rtde_frequency_; servoj_time_ = 1.0 / rtde_frequency_;
// Open Stream to get own IP std::string local_ip = rtde_client_->getIP();
// TODO: Open Primary interface to query version and calibration
comm::URStream<primary_interface::PackageHeader> stream(robot_ip, 30001);
stream.connect();
std::string local_ip = stream.getIP();
uint32_t reverse_port = 50001; // TODO: Make this a parameter uint32_t reverse_port = 50001; // TODO: Make this a parameter
uint32_t script_sender_port = 50002; // TODO: Make this a parameter uint32_t script_sender_port = 50002; // TODO: Make this a parameter