Skip to content

Commit db56a8d

Browse files
committed
No longer automatically publishes a list of data fields that are already manually published
1 parent 7ca839c commit db56a8d

File tree

1 file changed

+25
-0
lines changed

1 file changed

+25
-0
lines changed

ur_robot_driver/src/ros/hardware_interface.cpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -305,7 +305,32 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
305305
safety_mode_pub_.reset(
306306
new realtime_tools::RealtimePublisher<ur_dashboard_msgs::SafetyMode>(robot_hw_nh, "safety_mode", 1, true));
307307

308+
std::string already_published[] = { "actual_q",
309+
"actual_qd",
310+
"target_speed_fraction",
311+
"speed_scaling",
312+
"runtime_state",
313+
"actual_TCP_force",
314+
"actual_TCP_pose",
315+
"standard_analog_input0",
316+
"standard_analog_input1",
317+
"standard_analog_output0",
318+
"standard_analog_output1",
319+
"tool_mode",
320+
"tool_analog_input0",
321+
"tool_analog_input1",
322+
"tool_output_voltage",
323+
"tool_output_current",
324+
"tool_temperature",
325+
"actual_digital_input_bits",
326+
"actual_digital_output_bits",
327+
"analog_io_types",
328+
"tool_analog_input_types" };
308329
std::vector<std::string> recipe = ur_driver_->getRTDEOutputRecipe();
330+
for (auto s : already_published)
331+
{
332+
recipe.erase(std::remove(recipe.begin(), recipe.end(), s), recipe.end());
333+
}
309334
rtde_data_pub_.reset(new rtde_interface::DataPackagePublisher(recipe, robot_hw_nh));
310335

311336
// Set the speed slider fraction used by the robot's execution. Values should be between 0 and 1.

0 commit comments

Comments
 (0)