|
8 | 8 | fake_sensor_commands:=false
|
9 | 9 | sim_gazebo:=false
|
10 | 10 | sim_ignition:=false
|
| 11 | + sim_isaac:=false |
| 12 | + isaac_joint_commands:=/isaac_joint_commands |
| 13 | + isaac_joint_states:=/isaac_joint_states |
11 | 14 | use_internal_bus_gripper_comm:=false
|
12 | 15 | tf_prefix
|
13 | 16 | initial_positions:=${dict(joint_1=0.0,joint_2=0.0,joint_3=0.0,joint_4=0.0,joint_5=0.0,joint_6=0.0)}
|
|
17 | 20 | port
|
18 | 21 | port_realtime
|
19 | 22 | session_inactivity_timeout_ms
|
20 |
| - connection_inactivity_timeout_ms"> |
| 23 | + connection_inactivity_timeout_ms |
| 24 | + gripper_joint_name |
| 25 | + gripper_max_velocity:=100.0 |
| 26 | + gripper_max_force:=100.0"> |
21 | 27 |
|
22 | 28 | <ros2_control name="${name}" type="system">
|
23 | 29 | <hardware>
|
|
27 | 33 | <xacro:if value="${sim_ignition}">
|
28 | 34 | <plugin>ign_ros2_control/IgnitionSystem</plugin>
|
29 | 35 | </xacro:if>
|
| 36 | + <xacro:if value="${sim_isaac}"> |
| 37 | + <plugin>topic_based_ros2_control/TopicBasedSystem</plugin> |
| 38 | + <param name="joint_commands_topic">${isaac_joint_commands}</param> |
| 39 | + <param name="joint_states_topic">${isaac_joint_states}</param> |
| 40 | + </xacro:if> |
30 | 41 | <xacro:if value="${use_fake_hardware}">
|
31 | 42 | <plugin>fake_components/GenericSystem</plugin>
|
32 | 43 | <param name="fake_sensor_commands">${fake_sensor_commands}</param>
|
33 | 44 | <param name="state_following_offset">0.0</param>
|
34 | 45 | </xacro:if>
|
35 |
| - <xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition}"> |
| 46 | + <xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition or sim_isaac}"> |
36 | 47 | <plugin>kortex_driver/KortexMultiInterfaceHardware</plugin>
|
37 | 48 | <param name="robot_ip">${robot_ip}</param>
|
38 | 49 | <param name="username">${username}</param>
|
|
43 | 54 | <param name="connection_inactivity_timeout_ms">${connection_inactivity_timeout_ms}</param>
|
44 | 55 | <param name="tf_prefix">"${tf_prefix}"</param>
|
45 | 56 | <param name="use_internal_bus_gripper_comm">${use_internal_bus_gripper_comm}</param>
|
46 |
| - <param name="gripper_joint_name">${prefix}right_finger_bottom_joint</param> |
| 57 | + <param name="gripper_joint_name">${gripper_joint_name}</param> |
| 58 | + <param name="gripper_max_velocity">${gripper_max_velocity}</param> |
| 59 | + <param name="gripper_max_force">${gripper_max_force}</param> |
47 | 60 | </xacro:unless>
|
48 | 61 | </hardware>
|
49 | 62 | <joint name="${prefix}joint_1">
|
50 | 63 | <command_interface name="position">
|
51 | 64 | <param name="min">-2.69</param>
|
52 | 65 | <param name="max">2.69</param>
|
53 | 66 | </command_interface>
|
54 |
| - <command_interface name="velocity"> |
55 |
| - <param name="min">-1.6</param> |
56 |
| - <param name="max">1.6</param> |
57 |
| - </command_interface> |
58 | 67 | <state_interface name="position">
|
59 | 68 | <param name="initial_value">${initial_positions['joint_1']}</param>
|
60 | 69 | </state_interface>
|
|
66 | 75 | <param name="min">-2.69</param>
|
67 | 76 | <param name="max">2.36</param>
|
68 | 77 | </command_interface>
|
69 |
| - <command_interface name="velocity"> |
70 |
| - <param name="min">-1.6</param> |
71 |
| - <param name="max">1.6</param> |
72 |
| - </command_interface> |
73 | 78 | <state_interface name="position">
|
74 | 79 | <param name="initial_value">${initial_positions['joint_2']}</param>
|
75 | 80 | </state_interface>
|
|
81 | 86 | <param name="min">-2.69</param>
|
82 | 87 | <param name="max">2.69</param>
|
83 | 88 | </command_interface>
|
84 |
| - <command_interface name="velocity"> |
85 |
| - <param name="min">-1.6</param> |
86 |
| - <param name="max">1.6</param> |
87 |
| - </command_interface> |
88 | 89 | <state_interface name="position">
|
89 | 90 | <param name="initial_value">${initial_positions['joint_3']}</param>
|
90 | 91 | </state_interface>
|
|
96 | 97 | <param name="min">-2.59</param>
|
97 | 98 | <param name="max">2.59</param>
|
98 | 99 | </command_interface>
|
99 |
| - <command_interface name="velocity"> |
100 |
| - <param name="min">-1.6</param> |
101 |
| - <param name="max">1.6</param> |
102 |
| - </command_interface> |
103 | 100 | <state_interface name="position">
|
104 | 101 | <param name="initial_value">${initial_positions['joint_4']}</param>
|
105 | 102 | </state_interface>
|
|
111 | 108 | <param name="min">-2.57</param>
|
112 | 109 | <param name="max">2.57</param>
|
113 | 110 | </command_interface>
|
114 |
| - <command_interface name="velocity"> |
115 |
| - <param name="min">-1.6</param> |
116 |
| - <param name="max">1.6</param> |
117 |
| - </command_interface> |
118 | 111 | <state_interface name="position">
|
119 | 112 | <param name="initial_value">${initial_positions['joint_5']}</param>
|
120 | 113 | </state_interface>
|
|
126 | 119 | <param name="min">-2.59</param>
|
127 | 120 | <param name="max">2.59</param>
|
128 | 121 | </command_interface>
|
129 |
| - <command_interface name="velocity"> |
130 |
| - <param name="min">-3.2</param> |
131 |
| - <param name="max">3.2</param> |
132 |
| - </command_interface> |
133 | 122 | <state_interface name="position">
|
134 | 123 | <param name="initial_value">${initial_positions['joint_6']}</param>
|
135 | 124 | </state_interface>
|
|
0 commit comments