Skip to content

Commit

Permalink
Use Robot_hw_nh node handle for joints. (#227)
Browse files Browse the repository at this point in the history
modified hardware interface to look for joints parameter under the robot_hw node handle
  • Loading branch information
CollinAvidano authored Aug 19, 2020
1 parent 2e44f86 commit 64ab483
Show file tree
Hide file tree
Showing 7 changed files with 8 additions and 8 deletions.
2 changes: 1 addition & 1 deletion ur_robot_driver/config/ur10_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ hardware_control_loop:
loop_hz: &loop_hz 125

# Settings for ros_control hardware interface
hardware_interface:
ur_hardware_interface:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
Expand Down
2 changes: 1 addition & 1 deletion ur_robot_driver/config/ur10e_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ hardware_control_loop:
loop_hz: &loop_hz 500

# Settings for ros_control hardware interface
hardware_interface:
ur_hardware_interface:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
Expand Down
2 changes: 1 addition & 1 deletion ur_robot_driver/config/ur3_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ hardware_control_loop:
loop_hz: &loop_hz 125

# Settings for ros_control hardware interface
hardware_interface:
ur_hardware_interface:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
Expand Down
2 changes: 1 addition & 1 deletion ur_robot_driver/config/ur3e_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ hardware_control_loop:
loop_hz: &loop_hz 500

# Settings for ros_control hardware interface
hardware_interface:
ur_hardware_interface:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
Expand Down
2 changes: 1 addition & 1 deletion ur_robot_driver/config/ur5_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ hardware_control_loop:
loop_hz: &loop_hz 125

# Settings for ros_control hardware interface
hardware_interface:
ur_hardware_interface:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
Expand Down
2 changes: 1 addition & 1 deletion ur_robot_driver/config/ur5e_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ hardware_control_loop:
loop_hz: &loop_hz 500

# Settings for ros_control hardware interface
hardware_interface:
ur_hardware_interface:
joints: &robot_joints
- shoulder_pan_joint
- shoulder_lift_joint
Expand Down
4 changes: 2 additions & 2 deletions ur_robot_driver/src/ros/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -284,9 +284,9 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
command_sub_ = robot_hw_nh.subscribe("script_command", 1, &HardwareInterface::commandCallback, this);

// Names of the joints. Usually, this is given in the controller config file.
if (!root_nh.getParam("hardware_interface/joints", joint_names_))
if (!robot_hw_nh.getParam("joints", joint_names_))
{
ROS_ERROR_STREAM("Cannot find required parameter " << root_nh.resolveName("hardware_interface/joints")
ROS_ERROR_STREAM("Cannot find required parameter " << robot_hw_nh.resolveName("joints")
<< " on the parameter server.");
throw std::runtime_error("Cannot find required parameter "
"'controller_joint_names' on the parameter server.");
Expand Down

0 comments on commit 64ab483

Please sign in to comment.