@@ -28,35 +28,35 @@ controller_manager:
2828speed_scaling_state_broadcaster :
2929 ros__parameters :
3030 state_publish_rate : 100.0
31- tf_prefix : " "
31+ tf_prefix : " $(var tf_prefix) "
3232
3333io_and_status_controller :
3434 ros__parameters :
35- tf_prefix : " "
35+ tf_prefix : " $(var tf_prefix) "
3636
3737force_torque_sensor_broadcaster :
3838 ros__parameters :
39- sensor_name : tcp_fts_sensor
39+ sensor_name : $(var tf_prefix) tcp_fts_sensor
4040 state_interface_names :
4141 - force.x
4242 - force.y
4343 - force.z
4444 - torque.x
4545 - torque.y
4646 - torque.z
47- frame_id : tool0
47+ frame_id : $(var tf_prefix) tool0
4848 topic_name : ft_data
4949
5050
5151joint_trajectory_controller :
5252 ros__parameters :
5353 joints :
54- - shoulder_pan_joint
55- - shoulder_lift_joint
56- - elbow_joint
57- - wrist_1_joint
58- - wrist_2_joint
59- - wrist_3_joint
54+ - $(var tf_prefix) shoulder_pan_joint
55+ - $(var tf_prefix) shoulder_lift_joint
56+ - $(var tf_prefix) elbow_joint
57+ - $(var tf_prefix) wrist_1_joint
58+ - $(var tf_prefix) wrist_2_joint
59+ - $(var tf_prefix) wrist_3_joint
6060 command_interfaces :
6161 - position
6262 state_interfaces :
@@ -68,23 +68,23 @@ joint_trajectory_controller:
6868 constraints :
6969 stopped_velocity_tolerance : 0.2
7070 goal_time : 0.0
71- shoulder_pan_joint : { trajectory: 0.2, goal: 0.1 }
72- shoulder_lift_joint : { trajectory: 0.2, goal: 0.1 }
73- elbow_joint : { trajectory: 0.2, goal: 0.1 }
74- wrist_1_joint : { trajectory: 0.2, goal: 0.1 }
75- wrist_2_joint : { trajectory: 0.2, goal: 0.1 }
76- wrist_3_joint : { trajectory: 0.2, goal: 0.1 }
71+ $(var tf_prefix) shoulder_pan_joint : { trajectory: 0.2, goal: 0.1 }
72+ $(var tf_prefix) shoulder_lift_joint : { trajectory: 0.2, goal: 0.1 }
73+ $(var tf_prefix) elbow_joint : { trajectory: 0.2, goal: 0.1 }
74+ $(var tf_prefix) wrist_1_joint : { trajectory: 0.2, goal: 0.1 }
75+ $(var tf_prefix) wrist_2_joint : { trajectory: 0.2, goal: 0.1 }
76+ $(var tf_prefix) wrist_3_joint : { trajectory: 0.2, goal: 0.1 }
7777
7878
7979scaled_joint_trajectory_controller :
8080 ros__parameters :
8181 joints :
82- - shoulder_pan_joint
83- - shoulder_lift_joint
84- - elbow_joint
85- - wrist_1_joint
86- - wrist_2_joint
87- - wrist_3_joint
82+ - $(var tf_prefix) shoulder_pan_joint
83+ - $(var tf_prefix) shoulder_lift_joint
84+ - $(var tf_prefix) elbow_joint
85+ - $(var tf_prefix) wrist_1_joint
86+ - $(var tf_prefix) wrist_2_joint
87+ - $(var tf_prefix) wrist_3_joint
8888 command_interfaces :
8989 - position
9090 state_interfaces :
@@ -96,31 +96,31 @@ scaled_joint_trajectory_controller:
9696 constraints :
9797 stopped_velocity_tolerance : 0.2
9898 goal_time : 0.0
99- shoulder_pan_joint : { trajectory: 0.2, goal: 0.1 }
100- shoulder_lift_joint : { trajectory: 0.2, goal: 0.1 }
101- elbow_joint : { trajectory: 0.2, goal: 0.1 }
102- wrist_1_joint : { trajectory: 0.2, goal: 0.1 }
103- wrist_2_joint : { trajectory: 0.2, goal: 0.1 }
104- wrist_3_joint : { trajectory: 0.2, goal: 0.1 }
105- speed_scaling_interface_name : speed_scaling/speed_scaling_factor
99+ $(var tf_prefix) shoulder_pan_joint : { trajectory: 0.2, goal: 0.1 }
100+ $(var tf_prefix) shoulder_lift_joint : { trajectory: 0.2, goal: 0.1 }
101+ $(var tf_prefix) elbow_joint : { trajectory: 0.2, goal: 0.1 }
102+ $(var tf_prefix) wrist_1_joint : { trajectory: 0.2, goal: 0.1 }
103+ $(var tf_prefix) wrist_2_joint : { trajectory: 0.2, goal: 0.1 }
104+ $(var tf_prefix) wrist_3_joint : { trajectory: 0.2, goal: 0.1 }
105+ speed_scaling_interface_name : $(var tf_prefix) speed_scaling/speed_scaling_factor
106106
107107forward_velocity_controller :
108108 ros__parameters :
109109 joints :
110- - shoulder_pan_joint
111- - shoulder_lift_joint
112- - elbow_joint
113- - wrist_1_joint
114- - wrist_2_joint
115- - wrist_3_joint
110+ - $(var tf_prefix) shoulder_pan_joint
111+ - $(var tf_prefix) shoulder_lift_joint
112+ - $(var tf_prefix) elbow_joint
113+ - $(var tf_prefix) wrist_1_joint
114+ - $(var tf_prefix) wrist_2_joint
115+ - $(var tf_prefix) wrist_3_joint
116116 interface_name : velocity
117117
118118forward_position_controller :
119119 ros__parameters :
120120 joints :
121- - shoulder_pan_joint
122- - shoulder_lift_joint
123- - elbow_joint
124- - wrist_1_joint
125- - wrist_2_joint
126- - wrist_3_joint
121+ - $(var tf_prefix) shoulder_pan_joint
122+ - $(var tf_prefix) shoulder_lift_joint
123+ - $(var tf_prefix) elbow_joint
124+ - $(var tf_prefix) wrist_1_joint
125+ - $(var tf_prefix) wrist_2_joint
126+ - $(var tf_prefix) wrist_3_joint
0 commit comments