Skip to content

Commit 0e899f0

Browse files
authored
Update gen3 lite and gripper macros (Kinovarobotics#191)
1 parent 9154884 commit 0e899f0

File tree

3 files changed

+40
-29
lines changed

3 files changed

+40
-29
lines changed

kortex_description/arms/gen3_lite/6dof/urdf/gen3_lite_macro.xacro

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,10 +19,17 @@
1919
session_inactivity_timeout_ms:=6000
2020
connection_inactivity_timeout_ms:=2000
2121
use_internal_bus_gripper_comm:=false
22+
gripper_joint_name
23+
gripper_max_velocity:=100.0
24+
gripper_max_force:=100.0
2225
use_fake_hardware:=false
2326
fake_sensor_commands:=false
2427
sim_gazebo:=false
2528
sim_ignition:=false
29+
sim_isaac:=false
30+
isaac_joint_commands:=/isaac_joint_commands
31+
isaac_joint_states:=/isaac_joint_states
32+
use_external_cable:=false
2633
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)}" >
2734

2835
<!-- ros2 control include -->
@@ -42,6 +49,9 @@
4249
fake_sensor_commands="${fake_sensor_commands}"
4350
sim_gazebo="${sim_gazebo}"
4451
sim_ignition="${sim_ignition}"
52+
sim_isaac="${sim_isaac}"
53+
isaac_joint_commands="${isaac_joint_commands}"
54+
isaac_joint_states="${isaac_joint_states}"
4555
tf_prefix=""
4656
initial_positions="${initial_positions}"
4757
robot_ip="${robot_ip}"
@@ -51,7 +61,10 @@
5161
port_realtime="${port_realtime}"
5262
session_inactivity_timeout_ms="${session_inactivity_timeout_ms}"
5363
connection_inactivity_timeout_ms="${connection_inactivity_timeout_ms}"
54-
use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}" />
64+
use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}"
65+
gripper_max_velocity="${gripper_max_velocity}"
66+
gripper_max_force="${gripper_max_force}"
67+
gripper_joint_name="${gripper_joint_name}"/>
5568

5669
<joint name="${prefix}base_joint" type="fixed">
5770
<xacro:insert_block name="origin" />

kortex_description/arms/gen3_lite/6dof/urdf/kortex.ros2_control.xacro

Lines changed: 16 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,9 @@
88
fake_sensor_commands:=false
99
sim_gazebo:=false
1010
sim_ignition:=false
11+
sim_isaac:=false
12+
isaac_joint_commands:=/isaac_joint_commands
13+
isaac_joint_states:=/isaac_joint_states
1114
use_internal_bus_gripper_comm:=false
1215
tf_prefix
1316
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,7 +20,10 @@
1720
port
1821
port_realtime
1922
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">
2127

2228
<ros2_control name="${name}" type="system">
2329
<hardware>
@@ -27,12 +33,17 @@
2733
<xacro:if value="${sim_ignition}">
2834
<plugin>ign_ros2_control/IgnitionSystem</plugin>
2935
</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>
3041
<xacro:if value="${use_fake_hardware}">
3142
<plugin>fake_components/GenericSystem</plugin>
3243
<param name="fake_sensor_commands">${fake_sensor_commands}</param>
3344
<param name="state_following_offset">0.0</param>
3445
</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}">
3647
<plugin>kortex_driver/KortexMultiInterfaceHardware</plugin>
3748
<param name="robot_ip">${robot_ip}</param>
3849
<param name="username">${username}</param>
@@ -43,18 +54,16 @@
4354
<param name="connection_inactivity_timeout_ms">${connection_inactivity_timeout_ms}</param>
4455
<param name="tf_prefix">"${tf_prefix}"</param>
4556
<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>
4760
</xacro:unless>
4861
</hardware>
4962
<joint name="${prefix}joint_1">
5063
<command_interface name="position">
5164
<param name="min">-2.69</param>
5265
<param name="max">2.69</param>
5366
</command_interface>
54-
<command_interface name="velocity">
55-
<param name="min">-1.6</param>
56-
<param name="max">1.6</param>
57-
</command_interface>
5867
<state_interface name="position">
5968
<param name="initial_value">${initial_positions['joint_1']}</param>
6069
</state_interface>
@@ -66,10 +75,6 @@
6675
<param name="min">-2.69</param>
6776
<param name="max">2.36</param>
6877
</command_interface>
69-
<command_interface name="velocity">
70-
<param name="min">-1.6</param>
71-
<param name="max">1.6</param>
72-
</command_interface>
7378
<state_interface name="position">
7479
<param name="initial_value">${initial_positions['joint_2']}</param>
7580
</state_interface>
@@ -81,10 +86,6 @@
8186
<param name="min">-2.69</param>
8287
<param name="max">2.69</param>
8388
</command_interface>
84-
<command_interface name="velocity">
85-
<param name="min">-1.6</param>
86-
<param name="max">1.6</param>
87-
</command_interface>
8889
<state_interface name="position">
8990
<param name="initial_value">${initial_positions['joint_3']}</param>
9091
</state_interface>
@@ -96,10 +97,6 @@
9697
<param name="min">-2.59</param>
9798
<param name="max">2.59</param>
9899
</command_interface>
99-
<command_interface name="velocity">
100-
<param name="min">-1.6</param>
101-
<param name="max">1.6</param>
102-
</command_interface>
103100
<state_interface name="position">
104101
<param name="initial_value">${initial_positions['joint_4']}</param>
105102
</state_interface>
@@ -111,10 +108,6 @@
111108
<param name="min">-2.57</param>
112109
<param name="max">2.57</param>
113110
</command_interface>
114-
<command_interface name="velocity">
115-
<param name="min">-1.6</param>
116-
<param name="max">1.6</param>
117-
</command_interface>
118111
<state_interface name="position">
119112
<param name="initial_value">${initial_positions['joint_5']}</param>
120113
</state_interface>
@@ -126,10 +119,6 @@
126119
<param name="min">-2.59</param>
127120
<param name="max">2.59</param>
128121
</command_interface>
129-
<command_interface name="velocity">
130-
<param name="min">-3.2</param>
131-
<param name="max">3.2</param>
132-
</command_interface>
133122
<state_interface name="position">
134123
<param name="initial_value">${initial_positions['joint_6']}</param>
135124
</state_interface>

kortex_description/grippers/gen3_lite_2f/urdf/gen3_lite_2f_macro.xacro

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,16 @@
11
<?xml version="1.0"?>
22

33
<robot name="gen3_lite_2f_gripper" xmlns:xacro="http://ros.org/wiki/xacro">
4-
<xacro:macro name="load_gripper" params="parent prefix">
4+
<xacro:macro name="load_gripper" params="
5+
parent
6+
prefix
7+
use_fake_hardware:=false
8+
fake_sensor_commands:=false
9+
sim_ignition:=false
10+
sim_isaac:=false
11+
isaac_joint_commands:=/isaac_joint_commands
12+
isaac_joint_states:=/isaac_joint_states
13+
use_internal_bus_gripper_comm:=true">
514

615
<!-- Tool frame used by the arm -->
716
<link name="${prefix}tool_frame"/>

0 commit comments

Comments
 (0)