mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
rtde_driver: don't unnecessarily repeat joint names.
Use an anchor for the list and aliases where needed.
This commit is contained in:
@@ -4,7 +4,7 @@ hardware_control_loop:
|
||||
|
||||
# Settings for ros_control hardware interface
|
||||
hardware_interface:
|
||||
joints:
|
||||
joints: &robot_joints
|
||||
- shoulder_pan_joint
|
||||
- shoulder_lift_joint
|
||||
- elbow_joint
|
||||
@@ -31,13 +31,7 @@ speed_scaling_state_controller:
|
||||
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
|
||||
scaled_pos_traj_controller:
|
||||
type: position_controllers/ScaledJointTrajectoryController
|
||||
joints:
|
||||
- shoulder_pan_joint
|
||||
- shoulder_lift_joint
|
||||
- elbow_joint
|
||||
- wrist_1_joint
|
||||
- wrist_2_joint
|
||||
- wrist_3_joint
|
||||
joints: *robot_joints
|
||||
constraints:
|
||||
goal_time: 0.6
|
||||
stopped_velocity_tolerance: 0.05
|
||||
@@ -53,13 +47,7 @@ scaled_pos_traj_controller:
|
||||
|
||||
pos_traj_controller:
|
||||
type: position_controllers/JointTrajectoryController
|
||||
joints:
|
||||
- shoulder_pan_joint
|
||||
- shoulder_lift_joint
|
||||
- elbow_joint
|
||||
- wrist_1_joint
|
||||
- wrist_2_joint
|
||||
- wrist_3_joint
|
||||
joints: *robot_joints
|
||||
constraints:
|
||||
goal_time: 0.6
|
||||
stopped_velocity_tolerance: 0.05
|
||||
|
||||
Reference in New Issue
Block a user