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

Use correct naming scheme for variable robot_ip

This commit is contained in:
Felix Mauch
2019-05-20 11:29:14 +02:00
parent 7743c79f6d
commit 0e0bffcdc6
5 changed files with 12 additions and 10 deletions

View File

@@ -51,7 +51,7 @@ class RTDEClient
{
public:
RTDEClient() = delete;
RTDEClient(std::string ROBOT_IP, comm::INotifier& notifier);
RTDEClient(std::string robot_ip, comm::INotifier& notifier);
~RTDEClient() = default;
bool init();
bool start();

View File

@@ -42,9 +42,9 @@ public:
/*!
* \brief Constructs a new UrDriver object.
*
* \param ROBOT_IP IP-address under which the robot is reachable.
* \param robot_ip IP-address under which the robot is reachable.
*/
UrDriver(const std::string& ROBOT_IP);
UrDriver(const std::string& robot_ip);
virtual ~UrDriver() = default;
/*!

View File

@@ -44,10 +44,10 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
{
joint_velocities_ = { { 0, 0, 0, 0, 0, 0 } };
joint_efforts_ = { { 0, 0, 0, 0, 0, 0 } };
std::string ROBOT_IP = robot_hw_nh.param<std::string>("robot_ip", "192.168.56.101");
std::string robot_ip = robot_hw_nh.param<std::string>("robot_ip", "192.168.56.101");
ROS_INFO_STREAM("Initializing urdriver");
ur_driver_.reset(new UrDriver(ROBOT_IP));
ur_driver_.reset(new UrDriver(robot_ip));
if (!root_nh.getParam("hardware_interface/joints", joint_names_))
{

View File

@@ -31,8 +31,8 @@ namespace ur_driver
{
namespace rtde_interface
{
RTDEClient::RTDEClient(std::string ROBOT_IP, comm::INotifier& notifier)
: stream_(ROBOT_IP, UR_RTDE_PORT)
RTDEClient::RTDEClient(std::string robot_ip, comm::INotifier& notifier)
: stream_(robot_ip, UR_RTDE_PORT)
, parser_(readRecipe())
, prod_(stream_, parser_)
, pipeline_(prod_, PIPELINE_NAME, notifier)

View File

@@ -118,11 +118,11 @@ def myProg():
end
)";
ur_driver::UrDriver::UrDriver(const std::string& ROBOT_IP)
ur_driver::UrDriver::UrDriver(const std::string& robot_ip)
: servoj_time_(0.008), servoj_gain_(750), servoj_lookahead_time_(0.03)
{
ROS_INFO_STREAM("Initializing RTDE client");
rtde_client_.reset(new rtde_interface::RTDEClient(ROBOT_IP, notifier_));
rtde_client_.reset(new rtde_interface::RTDEClient(robot_ip, notifier_));
if (!rtde_client_->init())
{
@@ -132,7 +132,9 @@ ur_driver::UrDriver::UrDriver(const std::string& ROBOT_IP)
rtde_frequency_ = rtde_client_->getMaxFrequency();
servoj_time_ = 1.0 / rtde_frequency_;
comm::URStream<rtde_interface::PackageHeader> stream(ROBOT_IP, 30001);
// Open Stream to get own IP
// TODO: Open Primary interface to query version and calibration
comm::URStream<rtde_interface::PackageHeader> stream(robot_ip, 30001);
stream.connect();
std::string local_ip = stream.getIP();