Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add prefix to wrench hw interface #217

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions ur_robot_driver/doc/ROS_INTERFACE.md
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,10 @@ Controllers that are initally loaded, but not started.

tf_prefix used for the robot.

##### wrench_frame_id (default: "wrench")

Parameter to set the id of the wrench frame, required if using multiple robots

##### tool_baud_rate (default: "115200")

Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true.
Expand Down
6 changes: 5 additions & 1 deletion ur_robot_driver/src/ros/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
joint_velocities_ = { { 0, 0, 0, 0, 0, 0 } };
joint_efforts_ = { { 0, 0, 0, 0, 0, 0 } };
std::string script_filename;
std::string wrench_frame_id;
std::string output_recipe_filename;
std::string input_recipe_filename;

Expand All @@ -89,6 +90,9 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
// to publish correct frame names for frames reported by the robot directly.
robot_hw_nh.param<std::string>("tf_prefix", tf_prefix_, "");

// Optional parameter to change the id of the wrench frame
robot_hw_nh.param<std::string>("wrench_frame_id", wrench_frame_id, "wrench");

// Path to the urscript code that will be sent to the robot.
if (!robot_hw_nh.getParam("script_file", script_filename))
{
Expand Down Expand Up @@ -309,7 +313,7 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
ur_controllers::SpeedScalingHandle("speed_scaling_factor", &speed_scaling_combined_));

fts_interface_.registerHandle(hardware_interface::ForceTorqueSensorHandle(
"wrench", tf_prefix_ + "tool0_controller", fts_measurements_.begin(), fts_measurements_.begin() + 3));
wrench_frame_id, tf_prefix_ + "tool0_controller", fts_measurements_.begin(), fts_measurements_.begin() + 3));

robot_status_interface_.registerHandle(industrial_robot_status_interface::IndustrialRobotStatusHandle(
"industrial_robot_status_handle", robot_status_resource_));
Expand Down