Skip to content

Commit 0a6b2ef

Browse files
authored
Start dashboard client in driver only when software version < 10 (#759)
PolyScope X doesn't have the dashboard server, so we should disable starting the dashboard client with the driver there.
1 parent 4441347 commit 0a6b2ef

File tree

1 file changed

+9
-3
lines changed

1 file changed

+9
-3
lines changed

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -286,9 +286,6 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
286286
// endeffector might be inaccurate. See the "ur_calibration" package on help how to generate your
287287
// own hash matching your actual robot.
288288
std::string calibration_checksum = robot_hw_nh.param<std::string>("kinematics/hash", "");
289-
ROS_INFO_STREAM("Initializing dashboard client");
290-
ros::NodeHandle dashboard_nh(robot_hw_nh, "dashboard");
291-
dashboard_client_.reset(new DashboardClientROS(dashboard_nh, robot_ip_));
292289
ROS_INFO_STREAM("Initializing urdriver");
293290
try
294291
{
@@ -328,6 +325,15 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
328325
ur_driver_->registerTrajectoryDoneCallback(
329326
std::bind(&HardwareInterface::passthroughTrajectoryDoneCb, this, std::placeholders::_1));
330327

328+
// Export version information to state interfaces
329+
urcl::VersionInformation version_info = ur_driver_->getVersion();
330+
if (version_info.major < 10)
331+
{
332+
ROS_INFO_STREAM("Initializing dashboard client");
333+
ros::NodeHandle dashboard_nh(robot_hw_nh, "dashboard");
334+
dashboard_client_.reset(new DashboardClientROS(dashboard_nh, robot_ip_));
335+
}
336+
331337
// Send arbitrary script commands to this topic. Note: On e-Series the robot has to be in
332338
// remote-control mode.
333339
//

0 commit comments

Comments
 (0)