Skip to content

Commit

Permalink
Update gen3 lite and gripper macros (#191)
Browse files Browse the repository at this point in the history
  • Loading branch information
dyackzan authored Nov 28, 2023
1 parent 9154884 commit 0e899f0
Show file tree
Hide file tree
Showing 3 changed files with 40 additions and 29 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,17 @@
session_inactivity_timeout_ms:=6000
connection_inactivity_timeout_ms:=2000
use_internal_bus_gripper_comm:=false
gripper_joint_name
gripper_max_velocity:=100.0
gripper_max_force:=100.0
use_fake_hardware:=false
fake_sensor_commands:=false
sim_gazebo:=false
sim_ignition:=false
sim_isaac:=false
isaac_joint_commands:=/isaac_joint_commands
isaac_joint_states:=/isaac_joint_states
use_external_cable:=false
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)}" >

<!-- ros2 control include -->
Expand All @@ -42,6 +49,9 @@
fake_sensor_commands="${fake_sensor_commands}"
sim_gazebo="${sim_gazebo}"
sim_ignition="${sim_ignition}"
sim_isaac="${sim_isaac}"
isaac_joint_commands="${isaac_joint_commands}"
isaac_joint_states="${isaac_joint_states}"
tf_prefix=""
initial_positions="${initial_positions}"
robot_ip="${robot_ip}"
Expand All @@ -51,7 +61,10 @@
port_realtime="${port_realtime}"
session_inactivity_timeout_ms="${session_inactivity_timeout_ms}"
connection_inactivity_timeout_ms="${connection_inactivity_timeout_ms}"
use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}" />
use_internal_bus_gripper_comm="${use_internal_bus_gripper_comm}"
gripper_max_velocity="${gripper_max_velocity}"
gripper_max_force="${gripper_max_force}"
gripper_joint_name="${gripper_joint_name}"/>

<joint name="${prefix}base_joint" type="fixed">
<xacro:insert_block name="origin" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,9 @@
fake_sensor_commands:=false
sim_gazebo:=false
sim_ignition:=false
sim_isaac:=false
isaac_joint_commands:=/isaac_joint_commands
isaac_joint_states:=/isaac_joint_states
use_internal_bus_gripper_comm:=false
tf_prefix
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)}
Expand All @@ -17,7 +20,10 @@
port
port_realtime
session_inactivity_timeout_ms
connection_inactivity_timeout_ms">
connection_inactivity_timeout_ms
gripper_joint_name
gripper_max_velocity:=100.0
gripper_max_force:=100.0">

<ros2_control name="${name}" type="system">
<hardware>
Expand All @@ -27,12 +33,17 @@
<xacro:if value="${sim_ignition}">
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</xacro:if>
<xacro:if value="${sim_isaac}">
<plugin>topic_based_ros2_control/TopicBasedSystem</plugin>
<param name="joint_commands_topic">${isaac_joint_commands}</param>
<param name="joint_states_topic">${isaac_joint_states}</param>
</xacro:if>
<xacro:if value="${use_fake_hardware}">
<plugin>fake_components/GenericSystem</plugin>
<param name="fake_sensor_commands">${fake_sensor_commands}</param>
<param name="state_following_offset">0.0</param>
</xacro:if>
<xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition}">
<xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition or sim_isaac}">
<plugin>kortex_driver/KortexMultiInterfaceHardware</plugin>
<param name="robot_ip">${robot_ip}</param>
<param name="username">${username}</param>
Expand All @@ -43,18 +54,16 @@
<param name="connection_inactivity_timeout_ms">${connection_inactivity_timeout_ms}</param>
<param name="tf_prefix">"${tf_prefix}"</param>
<param name="use_internal_bus_gripper_comm">${use_internal_bus_gripper_comm}</param>
<param name="gripper_joint_name">${prefix}right_finger_bottom_joint</param>
<param name="gripper_joint_name">${gripper_joint_name}</param>
<param name="gripper_max_velocity">${gripper_max_velocity}</param>
<param name="gripper_max_force">${gripper_max_force}</param>
</xacro:unless>
</hardware>
<joint name="${prefix}joint_1">
<command_interface name="position">
<param name="min">-2.69</param>
<param name="max">2.69</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1.6</param>
<param name="max">1.6</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_1']}</param>
</state_interface>
Expand All @@ -66,10 +75,6 @@
<param name="min">-2.69</param>
<param name="max">2.36</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1.6</param>
<param name="max">1.6</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_2']}</param>
</state_interface>
Expand All @@ -81,10 +86,6 @@
<param name="min">-2.69</param>
<param name="max">2.69</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1.6</param>
<param name="max">1.6</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_3']}</param>
</state_interface>
Expand All @@ -96,10 +97,6 @@
<param name="min">-2.59</param>
<param name="max">2.59</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1.6</param>
<param name="max">1.6</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_4']}</param>
</state_interface>
Expand All @@ -111,10 +108,6 @@
<param name="min">-2.57</param>
<param name="max">2.57</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1.6</param>
<param name="max">1.6</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_5']}</param>
</state_interface>
Expand All @@ -126,10 +119,6 @@
<param name="min">-2.59</param>
<param name="max">2.59</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.2</param>
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">${initial_positions['joint_6']}</param>
</state_interface>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,16 @@
<?xml version="1.0"?>

<robot name="gen3_lite_2f_gripper" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="load_gripper" params="parent prefix">
<xacro:macro name="load_gripper" params="
parent
prefix
use_fake_hardware:=false
fake_sensor_commands:=false
sim_ignition:=false
sim_isaac:=false
isaac_joint_commands:=/isaac_joint_commands
isaac_joint_states:=/isaac_joint_states
use_internal_bus_gripper_comm:=true">

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

0 comments on commit 0e899f0

Please sign in to comment.