@@ -24,35 +24,51 @@ controller_manager:
2424 forward_position_controller :
2525 type : position_controllers/JointGroupPositionController
2626
27+ tcp_pose_broadcaster :
28+ type : pose_broadcaster/PoseBroadcaster
29+
30+ passthrough_trajectory_controller :
31+ type : ur_controllers/PassthroughTrajectoryController
32+
33+ ur_configuration_controller :
34+ type : ur_controllers/URConfigurationController
2735
2836speed_scaling_state_broadcaster :
2937 ros__parameters :
3038 state_publish_rate : 100.0
39+ tf_prefix : " $(var tf_prefix)"
40+
41+ io_and_status_controller :
42+ ros__parameters :
43+ tf_prefix : " $(var tf_prefix)"
3144
45+ ur_configuration_controller :
46+ ros__parameters :
47+ tf_prefix : " $(var tf_prefix)"
3248
3349force_torque_sensor_broadcaster :
3450 ros__parameters :
35- sensor_name : tcp_fts_sensor
51+ sensor_name : $(var tf_prefix) tcp_fts_sensor
3652 state_interface_names :
3753 - force.x
3854 - force.y
3955 - force.z
4056 - torque.x
4157 - torque.y
4258 - torque.z
43- frame_id : tool0
59+ frame_id : $(var tf_prefix) tool0
4460 topic_name : ft_data
4561
4662
4763joint_trajectory_controller :
4864 ros__parameters :
4965 joints :
50- - shoulder_pan_joint
51- - shoulder_lift_joint
52- - elbow_joint
53- - wrist_1_joint
54- - wrist_2_joint
55- - wrist_3_joint
66+ - $(var tf_prefix) shoulder_pan_joint
67+ - $(var tf_prefix) shoulder_lift_joint
68+ - $(var tf_prefix) elbow_joint
69+ - $(var tf_prefix) wrist_1_joint
70+ - $(var tf_prefix) wrist_2_joint
71+ - $(var tf_prefix) wrist_3_joint
5672 command_interfaces :
5773 - position
5874 state_interfaces :
@@ -64,23 +80,23 @@ joint_trajectory_controller:
6480 constraints :
6581 stopped_velocity_tolerance : 0.2
6682 goal_time : 0.0
67- shoulder_pan_joint : { trajectory: 0.2, goal: 0.1 }
68- shoulder_lift_joint : { trajectory: 0.2, goal: 0.1 }
69- elbow_joint : { trajectory: 0.2, goal: 0.1 }
70- wrist_1_joint : { trajectory: 0.2, goal: 0.1 }
71- wrist_2_joint : { trajectory: 0.2, goal: 0.1 }
72- wrist_3_joint : { trajectory: 0.2, goal: 0.1 }
83+ $(var tf_prefix) shoulder_pan_joint : { trajectory: 0.2, goal: 0.1 }
84+ $(var tf_prefix) shoulder_lift_joint : { trajectory: 0.2, goal: 0.1 }
85+ $(var tf_prefix) elbow_joint : { trajectory: 0.2, goal: 0.1 }
86+ $(var tf_prefix) wrist_1_joint : { trajectory: 0.2, goal: 0.1 }
87+ $(var tf_prefix) wrist_2_joint : { trajectory: 0.2, goal: 0.1 }
88+ $(var tf_prefix) wrist_3_joint : { trajectory: 0.2, goal: 0.1 }
7389
7490
7591scaled_joint_trajectory_controller :
7692 ros__parameters :
7793 joints :
78- - shoulder_pan_joint
79- - shoulder_lift_joint
80- - elbow_joint
81- - wrist_1_joint
82- - wrist_2_joint
83- - wrist_3_joint
94+ - $(var tf_prefix) shoulder_pan_joint
95+ - $(var tf_prefix) shoulder_lift_joint
96+ - $(var tf_prefix) elbow_joint
97+ - $(var tf_prefix) wrist_1_joint
98+ - $(var tf_prefix) wrist_2_joint
99+ - $(var tf_prefix) wrist_3_joint
84100 command_interfaces :
85101 - position
86102 state_interfaces :
@@ -92,30 +108,53 @@ scaled_joint_trajectory_controller:
92108 constraints :
93109 stopped_velocity_tolerance : 0.2
94110 goal_time : 0.0
95- shoulder_pan_joint : { trajectory: 0.2, goal: 0.1 }
96- shoulder_lift_joint : { trajectory: 0.2, goal: 0.1 }
97- elbow_joint : { trajectory: 0.2, goal: 0.1 }
98- wrist_1_joint : { trajectory: 0.2, goal: 0.1 }
99- wrist_2_joint : { trajectory: 0.2, goal: 0.1 }
100- wrist_3_joint : { trajectory: 0.2, goal: 0.1 }
111+ $(var tf_prefix)shoulder_pan_joint : { trajectory: 0.2, goal: 0.1 }
112+ $(var tf_prefix)shoulder_lift_joint : { trajectory: 0.2, goal: 0.1 }
113+ $(var tf_prefix)elbow_joint : { trajectory: 0.2, goal: 0.1 }
114+ $(var tf_prefix)wrist_1_joint : { trajectory: 0.2, goal: 0.1 }
115+ $(var tf_prefix)wrist_2_joint : { trajectory: 0.2, goal: 0.1 }
116+ $(var tf_prefix)wrist_3_joint : { trajectory: 0.2, goal: 0.1 }
117+ speed_scaling_interface_name : $(var tf_prefix)speed_scaling/speed_scaling_factor
118+
119+ passthrough_trajectory_controller :
120+ ros__parameters :
121+ tf_prefix : " $(var tf_prefix)"
122+ joints :
123+ - $(var tf_prefix)shoulder_pan_joint
124+ - $(var tf_prefix)shoulder_lift_joint
125+ - $(var tf_prefix)elbow_joint
126+ - $(var tf_prefix)wrist_1_joint
127+ - $(var tf_prefix)wrist_2_joint
128+ - $(var tf_prefix)wrist_3_joint
129+ state_interfaces :
130+ - position
131+ - velocity
132+ speed_scaling_interface_name : $(var tf_prefix)speed_scaling/speed_scaling_factor
101133
102134forward_velocity_controller :
103135 ros__parameters :
104136 joints :
105- - shoulder_pan_joint
106- - shoulder_lift_joint
107- - elbow_joint
108- - wrist_1_joint
109- - wrist_2_joint
110- - wrist_3_joint
137+ - $(var tf_prefix) shoulder_pan_joint
138+ - $(var tf_prefix) shoulder_lift_joint
139+ - $(var tf_prefix) elbow_joint
140+ - $(var tf_prefix) wrist_1_joint
141+ - $(var tf_prefix) wrist_2_joint
142+ - $(var tf_prefix) wrist_3_joint
111143 interface_name : velocity
112144
113145forward_position_controller :
114146 ros__parameters :
115147 joints :
116- - shoulder_pan_joint
117- - shoulder_lift_joint
118- - elbow_joint
119- - wrist_1_joint
120- - wrist_2_joint
121- - wrist_3_joint
148+ - $(var tf_prefix)shoulder_pan_joint
149+ - $(var tf_prefix)shoulder_lift_joint
150+ - $(var tf_prefix)elbow_joint
151+ - $(var tf_prefix)wrist_1_joint
152+ - $(var tf_prefix)wrist_2_joint
153+ - $(var tf_prefix)wrist_3_joint
154+
155+ tcp_pose_broadcaster :
156+ ros__parameters :
157+ frame_id : $(var tf_prefix)base
158+ pose_name : $(var tf_prefix)tcp_pose
159+ tf :
160+ child_frame_id : $(var tf_prefix)tool0_controller
0 commit comments