Skip to content

Commit 64ab483

Browse files
Use Robot_hw_nh node handle for joints. (UniversalRobots#227)
modified hardware interface to look for joints parameter under the robot_hw node handle
1 parent 2e44f86 commit 64ab483

File tree

7 files changed

+8
-8
lines changed

7 files changed

+8
-8
lines changed

ur_robot_driver/config/ur10_controllers.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ hardware_control_loop:
33
loop_hz: &loop_hz 125
44

55
# Settings for ros_control hardware interface
6-
hardware_interface:
6+
ur_hardware_interface:
77
joints: &robot_joints
88
- shoulder_pan_joint
99
- shoulder_lift_joint

ur_robot_driver/config/ur10e_controllers.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ hardware_control_loop:
33
loop_hz: &loop_hz 500
44

55
# Settings for ros_control hardware interface
6-
hardware_interface:
6+
ur_hardware_interface:
77
joints: &robot_joints
88
- shoulder_pan_joint
99
- shoulder_lift_joint

ur_robot_driver/config/ur3_controllers.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ hardware_control_loop:
33
loop_hz: &loop_hz 125
44

55
# Settings for ros_control hardware interface
6-
hardware_interface:
6+
ur_hardware_interface:
77
joints: &robot_joints
88
- shoulder_pan_joint
99
- shoulder_lift_joint

ur_robot_driver/config/ur3e_controllers.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ hardware_control_loop:
33
loop_hz: &loop_hz 500
44

55
# Settings for ros_control hardware interface
6-
hardware_interface:
6+
ur_hardware_interface:
77
joints: &robot_joints
88
- shoulder_pan_joint
99
- shoulder_lift_joint

ur_robot_driver/config/ur5_controllers.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ hardware_control_loop:
33
loop_hz: &loop_hz 125
44

55
# Settings for ros_control hardware interface
6-
hardware_interface:
6+
ur_hardware_interface:
77
joints: &robot_joints
88
- shoulder_pan_joint
99
- shoulder_lift_joint

ur_robot_driver/config/ur5e_controllers.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ hardware_control_loop:
33
loop_hz: &loop_hz 500
44

55
# Settings for ros_control hardware interface
6-
hardware_interface:
6+
ur_hardware_interface:
77
joints: &robot_joints
88
- shoulder_pan_joint
99
- shoulder_lift_joint

ur_robot_driver/src/ros/hardware_interface.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -284,9 +284,9 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
284284
command_sub_ = robot_hw_nh.subscribe("script_command", 1, &HardwareInterface::commandCallback, this);
285285

286286
// Names of the joints. Usually, this is given in the controller config file.
287-
if (!root_nh.getParam("hardware_interface/joints", joint_names_))
287+
if (!robot_hw_nh.getParam("joints", joint_names_))
288288
{
289-
ROS_ERROR_STREAM("Cannot find required parameter " << root_nh.resolveName("hardware_interface/joints")
289+
ROS_ERROR_STREAM("Cannot find required parameter " << robot_hw_nh.resolveName("joints")
290290
<< " on the parameter server.");
291291
throw std::runtime_error("Cannot find required parameter "
292292
"'controller_joint_names' on the parameter server.");

0 commit comments

Comments
 (0)