Skip to content

Commit b169ea4

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

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
@@ -298,7 +298,32 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
298298
safety_mode_pub_.reset(
299299
new realtime_tools::RealtimePublisher<ur_dashboard_msgs::SafetyMode>(robot_hw_nh, "safety_mode", 1, true));
300300

301+
std::string already_published[] = { "actual_q",
302+
"actual_qd",
303+
"target_speed_fraction",
304+
"speed_scaling",
305+
"runtime_state",
306+
"actual_TCP_force",
307+
"actual_TCP_pose",
308+
"standard_analog_input0",
309+
"standard_analog_input1",
310+
"standard_analog_output0",
311+
"standard_analog_output1",
312+
"tool_mode",
313+
"tool_analog_input0",
314+
"tool_analog_input1",
315+
"tool_output_voltage",
316+
"tool_output_current",
317+
"tool_temperature",
318+
"actual_digital_input_bits",
319+
"actual_digital_output_bits",
320+
"analog_io_types",
321+
"tool_analog_input_types" };
301322
std::vector<std::string> recipe = ur_driver_->getRTDEOutputRecipe();
323+
for (auto s : already_published)
324+
{
325+
recipe.erase(std::remove(recipe.begin(), recipe.end(), s), recipe.end());
326+
}
302327
rtde_data_pub_.reset(new rtde_interface::DataPackagePublisher(recipe, robot_hw_nh));
303328

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

0 commit comments

Comments
 (0)