diff --git a/ur_rtde_driver/include/ur_rtde_driver/comm/tcp_socket.h b/ur_rtde_driver/include/ur_rtde_driver/comm/tcp_socket.h index c52b1d3..4a84747 100644 --- a/ur_rtde_driver/include/ur_rtde_driver/comm/tcp_socket.h +++ b/ur_rtde_driver/include/ur_rtde_driver/comm/tcp_socket.h @@ -78,7 +78,7 @@ public: * * \returns The IP address of the local machine. */ - std::string getIP(); + std::string getIP() const; /*! * \brief Reads one byte from the socket diff --git a/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_client.h b/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_client.h index f85be7b..34336d3 100644 --- a/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_client.h +++ b/ur_rtde_driver/include/ur_rtde_driver/rtde/rtde_client.h @@ -67,6 +67,13 @@ public: 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: comm::URStream stream_; std::vector recipe_; diff --git a/ur_rtde_driver/src/comm/tcp_socket.cpp b/ur_rtde_driver/src/comm/tcp_socket.cpp index 78dc9b9..3bc19f8 100644 --- a/ur_rtde_driver/src/comm/tcp_socket.cpp +++ b/ur_rtde_driver/src/comm/tcp_socket.cpp @@ -125,7 +125,7 @@ void TCPSocket::close() socket_fd_ = -1; } -std::string TCPSocket::getIP() +std::string TCPSocket::getIP() const { sockaddr_in name; socklen_t len = sizeof(name); diff --git a/ur_rtde_driver/src/rtde/rtde_client.cpp b/ur_rtde_driver/src/rtde/rtde_client.cpp index d9e512b..16a61c6 100644 --- a/ur_rtde_driver/src/rtde/rtde_client.cpp +++ b/ur_rtde_driver/src/rtde/rtde_client.cpp @@ -132,5 +132,10 @@ bool RTDEClient::getDataPackage(std::unique_ptr>& { return pipeline_.getLatestProduct(data_package, timeout); } + +std::string RTDEClient::getIP() const +{ + return stream_.getIP(); +} } // namespace rtde_interface } // namespace ur_driver diff --git a/ur_rtde_driver/src/ur/ur_driver.cpp b/ur_rtde_driver/src/ur/ur_driver.cpp index 14ec780..6be03ad 100644 --- a/ur_rtde_driver/src/ur/ur_driver.cpp +++ b/ur_rtde_driver/src/ur/ur_driver.cpp @@ -31,7 +31,6 @@ //---------------------------------------------------------------------- #include "ur_rtde_driver/ur/ur_driver.h" -#include "ur_rtde_driver/primary/package_header.h" #include "ur_rtde_driver/exceptions.h" #include @@ -65,11 +64,7 @@ ur_driver::UrDriver::UrDriver(const std::string& robot_ip, const std::string& sc rtde_frequency_ = rtde_client_->getMaxFrequency(); servoj_time_ = 1.0 / rtde_frequency_; - // Open Stream to get own IP - // TODO: Open Primary interface to query version and calibration - comm::URStream stream(robot_ip, 30001); - stream.connect(); - std::string local_ip = stream.getIP(); + std::string local_ip = rtde_client_->getIP(); uint32_t reverse_port = 50001; // TODO: Make this a parameter uint32_t script_sender_port = 50002; // TODO: Make this a parameter