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

Use Robot_hw_nh node handle for joints. #227

Merged
merged 2 commits into from Aug 19, 2020
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.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 1 addition & 1 deletion ur_robot_driver/config/ur10_controllers.yaml
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
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
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
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
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
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
Expand Up @@ -278,9 +278,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