|
1 | 1 | <?xml version="1.0"?> |
| 2 | + |
2 | 3 | <robot xmlns:xacro="http://wiki.ros.org/xacro"> |
3 | 4 | <xacro:macro name="ur_joint_control_description" params=" |
4 | 5 | tf_prefix |
5 | 6 | initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)} |
6 | 7 | "> |
7 | 8 | <joint name="${tf_prefix}shoulder_pan_joint"> |
8 | | - <command_interface name="position"> |
9 | | - <param name="min">{-2*pi}</param> |
10 | | - <param name="max">{2*pi}</param> |
11 | | - </command_interface> |
12 | | - <command_interface name="velocity"> |
13 | | - <param name="min">-3.15</param> |
14 | | - <param name="max">3.15</param> |
15 | | - </command_interface> |
| 9 | + <command_interface name="position"/> |
| 10 | + <command_interface name="velocity"/> |
16 | 11 | <state_interface name="position"> |
17 | 12 | <!-- initial position for the mock system and simulation --> |
18 | 13 | <param name="initial_value">${initial_positions['shoulder_pan_joint']}</param> |
|
25 | 20 | </state_interface> |
26 | 21 | </joint> |
27 | 22 | <joint name="${tf_prefix}shoulder_lift_joint"> |
28 | | - <command_interface name="position"> |
29 | | - <param name="min">{-2*pi}</param> |
30 | | - <param name="max">{2*pi}</param> |
31 | | - </command_interface> |
32 | | - <command_interface name="velocity"> |
33 | | - <param name="min">-3.15</param> |
34 | | - <param name="max">3.15</param> |
35 | | - </command_interface> |
| 23 | + <command_interface name="position"/> |
| 24 | + <command_interface name="velocity"/> |
36 | 25 | <state_interface name="position"> |
37 | 26 | <!-- initial position for the mock system and simulation --> |
38 | 27 | <param name="initial_value">${initial_positions['shoulder_lift_joint']}</param> |
|
45 | 34 | </state_interface> |
46 | 35 | </joint> |
47 | 36 | <joint name="${tf_prefix}elbow_joint"> |
48 | | - <command_interface name="position"> |
49 | | - <param name="min">{-pi}</param> |
50 | | - <param name="max">{pi}</param> |
51 | | - </command_interface> |
52 | | - <command_interface name="velocity"> |
53 | | - <param name="min">-3.15</param> |
54 | | - <param name="max">3.15</param> |
55 | | - </command_interface> |
| 37 | + <command_interface name="position"/> |
| 38 | + <command_interface name="velocity"/> |
56 | 39 | <state_interface name="position"> |
57 | 40 | <!-- initial position for the mock system and simulation --> |
58 | 41 | <param name="initial_value">${initial_positions['elbow_joint']}</param> |
|
65 | 48 | </state_interface> |
66 | 49 | </joint> |
67 | 50 | <joint name="${tf_prefix}wrist_1_joint"> |
68 | | - <command_interface name="position"> |
69 | | - <param name="min">{-2*pi}</param> |
70 | | - <param name="max">{2*pi}</param> |
71 | | - </command_interface> |
72 | | - <command_interface name="velocity"> |
73 | | - <param name="min">-3.2</param> |
74 | | - <param name="max">3.2</param> |
75 | | - </command_interface> |
| 51 | + <command_interface name="position"/> |
| 52 | + <command_interface name="velocity"/> |
76 | 53 | <state_interface name="position"> |
77 | 54 | <!-- initial position for the mock system and simulation --> |
78 | 55 | <param name="initial_value">${initial_positions['wrist_1_joint']}</param> |
|
85 | 62 | </state_interface> |
86 | 63 | </joint> |
87 | 64 | <joint name="${tf_prefix}wrist_2_joint"> |
88 | | - <command_interface name="position"> |
89 | | - <param name="min">{-2*pi}</param> |
90 | | - <param name="max">{2*pi}</param> |
91 | | - </command_interface> |
92 | | - <command_interface name="velocity"> |
93 | | - <param name="min">-3.2</param> |
94 | | - <param name="max">3.2</param> |
95 | | - </command_interface> |
| 65 | + <command_interface name="position"/> |
| 66 | + <command_interface name="velocity"/> |
96 | 67 | <state_interface name="position"> |
97 | 68 | <!-- initial position for the mock system and simulation --> |
98 | 69 | <param name="initial_value">${initial_positions['wrist_2_joint']}</param> |
|
105 | 76 | </state_interface> |
106 | 77 | </joint> |
107 | 78 | <joint name="${tf_prefix}wrist_3_joint"> |
108 | | - <command_interface name="position"> |
109 | | - <param name="min">{-2*pi}</param> |
110 | | - <param name="max">{2*pi}</param> |
111 | | - </command_interface> |
112 | | - <command_interface name="velocity"> |
113 | | - <param name="min">-3.2</param> |
114 | | - <param name="max">3.2</param> |
115 | | - </command_interface> |
| 79 | + <command_interface name="position"/> |
| 80 | + <command_interface name="velocity"/> |
116 | 81 | <state_interface name="position"> |
117 | 82 | <!-- initial position for the mock system and simulation --> |
118 | 83 | <param name="initial_value">${initial_positions['wrist_3_joint']}</param> |
|
0 commit comments