Skip to content
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -42,12 +42,13 @@ For estabilishg a connection with [robotiq_hande_driver](https://github.com/AGH-
parent="tool0"
grip_pos_min="0.0"
grip_pos_max="0.025"
tty="/tmp/ttyUR"
tty_port="/tmp/ttyUR"
baudrate="115200"
parity="N"
data_bits="8"
stop_bit="1"
slave_id="9"
frequency_hz="10"
use_fake_hardware="false"
/>
```
Expand Down
11 changes: 9 additions & 2 deletions urdf/robotiq_hande_gripper.ros2_control.xacro
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="robotiq_hande_ros2_control" params="name prefix grip_pos_min grip_pos_max tty baudrate parity data_bits stop_bit slave_id use_fake_hardware">
<xacro:macro name="robotiq_hande_ros2_control" params="name prefix grip_pos_min grip_pos_max tty_port baudrate parity data_bits stop_bit slave_id frequency_hz create_socat_tty ip_adress port use_fake_hardware">
<ros2_control name="${name}" type="system">
<hardware>
<xacro:if value="${use_fake_hardware}">
Expand All @@ -11,12 +11,19 @@
<plugin>robotiq_hande_driver/RobotiqHandeHardwareInterface</plugin>
<param name="grip_pos_min">${grip_pos_min}</param>
<param name="grip_pos_max">${grip_pos_max}</param>
<param name="tty">${tty}</param>

<param name="tty_port">${tty_port}</param>
<param name="baudrate">${baudrate}</param>
<param name="parity">${parity}</param>
<param name="data_bits">${data_bits}</param>
<param name="stop_bit">${stop_bit}</param>
<param name="slave_id">${slave_id}</param>
<param name="frequency_hz">${frequency_hz}</param>

<param name="create_socat_tty">${create_socat_tty}</param>
<param name="ip_adress">${ip_adress}</param>
<param name="port">${port}</param>

</xacro:unless>
</hardware>

Expand Down
14 changes: 12 additions & 2 deletions urdf/robotiq_hande_gripper.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,18 @@
<xacro:arg name="parent" default="tool0"/>
<xacro:arg name="grip_pos_min" default="0"/>
<xacro:arg name="grip_pos_max" default="0.025"/>
<xacro:arg name="tty" default="/tmp/ttyUR"/>
<xacro:arg name="tty_port" default="/tmp/ttyUR"/>
<xacro:arg name="baudrate" default="115200"/>
<xacro:arg name="parity" default="N"/>
<xacro:arg name="data_bits" default="8"/>
<xacro:arg name="stop_bit" default="1"/>
<xacro:arg name="slave_id" default="9"/>
<xacro:arg name="frequency_hz" default="10"/>

<xacro:arg name="create_socat_tty" default="false"/>
<xacro:arg name="ip_adress" default="192.168.100.10"/>
<xacro:arg name="port" default="54321"/>

<xacro:arg name="use_fake_hardware" default="true"/>

<xacro:include filename="$(find robotiq_hande_description)/urdf/robotiq_hande_gripper.xacro"/>
Expand All @@ -20,12 +26,16 @@
parent="$(arg parent)"
grip_pos_min="$(arg grip_pos_min)"
grip_pos_max="$(arg grip_pos_max)"
tty="$(arg tty)"
tty_port="$(arg tty_port)"
baudrate="$(arg baudrate)"
parity="$(arg parity)"
data_bits="$(arg data_bits)"
stop_bit="$(arg stop_bit)"
slave_id="$(arg slave_id)"
frequency_hz="$(arg frequency_hz)"
create_socat_tty="$(arg create_socat_tty)"
ip_adress="$(arg ip_adress)"
port="$(arg port)"
use_fake_hardware="$(arg use_fake_hardware)"
/>
</robot>
12 changes: 10 additions & 2 deletions urdf/robotiq_hande_gripper.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,17 @@
parent
grip_pos_min
grip_pos_max
tty
tty_port
baudrate
parity
data_bits
stop_bit
slave_id
use_fake_hardware
frequency_hz:=10
create_socat_tty:=false
ip_adress:=192.168.100.10
port:=54321
coupler_mass:=0.119
xyz:='0 0 0'
rpy:='0 0 0'"
Expand All @@ -31,12 +35,16 @@
prefix="${prefix}"
grip_pos_min="${grip_pos_min}"
grip_pos_max="${grip_pos_max}"
tty="${tty}"
tty_port="${tty_port}"
baudrate="${baudrate}"
parity="${parity}"
data_bits="${data_bits}"
stop_bit="${stop_bit}"
slave_id="${slave_id}"
frequency_hz="${frequency_hz}"
create_socat_tty="${create_socat_tty}"
ip_adress="${ip_adress}"
port="${port}"
use_fake_hardware="${use_fake_hardware}"
/>

Expand Down
Loading