|
| 1 | +<?xml version="1.0"?> |
| 2 | +<robot xmlns:xacro="http://wiki.ros.org/xacro"> |
| 3 | + <xacro:macro name="ur_joint_control_description" params=" |
| 4 | + tf_prefix |
| 5 | + 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 | + <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> |
| 16 | + <state_interface name="position"> |
| 17 | + <!-- initial position for the mock system and simulation --> |
| 18 | + <param name="initial_value">${initial_positions['shoulder_pan_joint']}</param> |
| 19 | + </state_interface> |
| 20 | + <state_interface name="velocity"> |
| 21 | + <param name="initial_value">0.0</param> |
| 22 | + </state_interface> |
| 23 | + <state_interface name="effort"> |
| 24 | + <param name="initial_value">0.0</param> |
| 25 | + </state_interface> |
| 26 | + </joint> |
| 27 | + <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> |
| 36 | + <state_interface name="position"> |
| 37 | + <!-- initial position for the mock system and simulation --> |
| 38 | + <param name="initial_value">${initial_positions['shoulder_lift_joint']}</param> |
| 39 | + </state_interface> |
| 40 | + <state_interface name="velocity"> |
| 41 | + <param name="initial_value">0.0</param> |
| 42 | + </state_interface> |
| 43 | + <state_interface name="effort"> |
| 44 | + <param name="initial_value">0.0</param> |
| 45 | + </state_interface> |
| 46 | + </joint> |
| 47 | + <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> |
| 56 | + <state_interface name="position"> |
| 57 | + <!-- initial position for the mock system and simulation --> |
| 58 | + <param name="initial_value">${initial_positions['elbow_joint']}</param> |
| 59 | + </state_interface> |
| 60 | + <state_interface name="velocity"> |
| 61 | + <param name="initial_value">0.0</param> |
| 62 | + </state_interface> |
| 63 | + <state_interface name="effort"> |
| 64 | + <param name="initial_value">0.0</param> |
| 65 | + </state_interface> |
| 66 | + </joint> |
| 67 | + <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> |
| 76 | + <state_interface name="position"> |
| 77 | + <!-- initial position for the mock system and simulation --> |
| 78 | + <param name="initial_value">${initial_positions['wrist_1_joint']}</param> |
| 79 | + </state_interface> |
| 80 | + <state_interface name="velocity"> |
| 81 | + <param name="initial_value">0.0</param> |
| 82 | + </state_interface> |
| 83 | + <state_interface name="effort"> |
| 84 | + <param name="initial_value">0.0</param> |
| 85 | + </state_interface> |
| 86 | + </joint> |
| 87 | + <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> |
| 96 | + <state_interface name="position"> |
| 97 | + <!-- initial position for the mock system and simulation --> |
| 98 | + <param name="initial_value">${initial_positions['wrist_2_joint']}</param> |
| 99 | + </state_interface> |
| 100 | + <state_interface name="velocity"> |
| 101 | + <param name="initial_value">0.0</param> |
| 102 | + </state_interface> |
| 103 | + <state_interface name="effort"> |
| 104 | + <param name="initial_value">0.0</param> |
| 105 | + </state_interface> |
| 106 | + </joint> |
| 107 | + <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> |
| 116 | + <state_interface name="position"> |
| 117 | + <!-- initial position for the mock system and simulation --> |
| 118 | + <param name="initial_value">${initial_positions['wrist_3_joint']}</param> |
| 119 | + </state_interface> |
| 120 | + <state_interface name="velocity"> |
| 121 | + <param name="initial_value">0.0</param> |
| 122 | + </state_interface> |
| 123 | + <state_interface name="effort"> |
| 124 | + <param name="initial_value">0.0</param> |
| 125 | + </state_interface> |
| 126 | + </joint> |
| 127 | + </xacro:macro> |
| 128 | +</robot> |
0 commit comments