fix: urdf for gazebo simulation

This commit is contained in:
Ilya Uraev 2025-04-29 11:50:41 +03:00
parent fc4f80fdfb
commit 4b99d62ebe
5 changed files with 130 additions and 11 deletions

View file

@ -22,5 +22,6 @@
<export>
<build_type>ament_cmake</build_type>
<gazebo_ros gazebo_model_path="${prefix}/../"/>
</export>
</package>

View file

@ -0,0 +1,89 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="dh_ag95_gripper_ros2_control"
params="name prefix com_port:=/dev/ttyUSB0 hardware mock_sensor_commands:=false">
<ros2_control name="${name}" type="system">
<hardware>
<xacro:if value="${hardware=='mock'}">
<!-- Mock hardware -->
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
<param name="state_following_offset">0.0</param>
</xacro:if>
<xacro:if value="${hardware=='real'}">
<!-- Real hardware -->
<plugin>dh_gripper_driver/DHGripperHardwareInterface</plugin>
<!-- Parameters for the DHGripperHardwareInterface -->
<!-- <param name="gripper_closed_position">0.93</param>
<param name="gripper_connect_port">${com_port}</param>
<param name="gripper_id">1</param>
<param name="gripper_model">AG95_MB</param>
<param name="gripper_baudrate">115200</param>
<param name="gripper_speed_multiplier">1.0</param>
<param name="gripper_force_multiplier">0.5</param> -->
<param name="gripper_closed_position">0.93</param>
<param name="COM_port">${com_port}</param>
<param name="gripper_speed_multiplier">1.0</param>
<param name="gripper_force_multiplier">0.5</param>
</xacro:if>
<xacro:if value="${hardware=='gazebo'}">
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</xacro:if>
</hardware>
<!-- Joint interfaces -->
<joint name="${prefix}left_outer_knuckle_joint">
<command_interface name="position">
<param name="min">0</param>
<param name="max">0.93</param>
</command_interface>
<state_interface name="position">
<param name="initial_value">0</param>
</state_interface>
<state_interface name="velocity" />
</joint>
<xacro:if value="${hardware=='gazebo' or hardware=='real'}">
<joint name="${prefix}right_outer_knuckle_joint">
<param name="mimic">${prefix}left_outer_knuckle_joint</param>
<param name="multiplier">1</param>
<!-- <command_interface name="position" /> -->
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
<joint name="${prefix}left_inner_knuckle_joint">
<param name="mimic">${prefix}left_outer_knuckle_joint</param>
<param name="multiplier">1</param>
<!-- <command_interface name="position" /> -->
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
<joint name="${prefix}right_inner_knuckle_joint">
<param name="mimic">${prefix}left_outer_knuckle_joint</param>
<param name="multiplier">1</param>
<!-- <command_interface name="position" /> -->
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
<joint name="${prefix}left_finger_joint">
<param name="mimic">${prefix}left_outer_knuckle_joint</param>
<param name="multiplier">1</param>
<!-- <command_interface name="position" /> -->
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
<joint name="${prefix}right_finger_joint">
<param name="mimic">${prefix}left_outer_knuckle_joint</param>
<param name="multiplier">1</param>
<!-- <command_interface name="position" /> -->
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
</xacro:if>
</ros2_control>
</xacro:macro>
</robot>

View file

@ -4,18 +4,16 @@
<!-- parameters -->
<xacro:arg name="prefix" default=""/>
<xacro:arg name="com_port" default="/dev/ttyUSB0"/>
<xacro:arg name="use_mock_hardware" default="false"/>
<xacro:arg name="hardware" default="gazebo"/>
<xacro:arg name="mock_sensor_commands" default="false"/>
<!-- import main macro -->
<xacro:include filename="$(find dh_ag95_description)/urdf/dh_ag95_macro.xacro" />
<xacro:include filename="$(find dh_gripper_driver)/urdf/dh_ag95.ros2_control.xacro" />
<xacro:include filename="$(find dh_ag95_description)/urdf/dh_ag95.ros2_control.xacro" />
<!-- gripper -->
<xacro:dh_ag95_gripper
prefix=""
parent="world">
<origin xyz="0 0 0.1" rpy="0 0 0" />
<xacro:dh_ag95_gripper prefix="$(arg prefix)" parent="world">
<origin xyz="0 0 0.0" rpy="0 0 0" />
</xacro:dh_ag95_gripper>
<!-- ros2_control -->
@ -23,10 +21,10 @@
name="dh_ag95_gripper"
prefix="$(arg prefix)"
com_port="$(arg com_port)"
use_mock_hardware="$(arg use_mock_hardware)"
hardware="$(arg hardware)"
mock_sensor_commands="$(arg mock_sensor_commands)"
/>
<link name="world" />
</robot>
</robot>

View file

@ -0,0 +1,31 @@
<?xml version="1.0"?>
<robot name="dh_ag95_gripper" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="dh_ag95_gripper" params="prefix parent *origin com_port:='/dev/ttyUSB0' hardware:=^ mock_sensor_commands:=false">
<!-- parameters -->
<!-- <xacro:arg name="prefix" default=""/> -->
<!-- <xacro:arg name="com_port" default="/dev/ttyUSB0"/> -->
<!-- <xacro:arg name="hardware" default="gazebo"/> -->
<!-- <xacro:property name="mock_sensor_commands" value="false" /> -->
<!-- import main macro -->
<xacro:include filename="$(find dh_ag95_description)/urdf/dh_ag95_macro.xacro" />
<xacro:include filename="$(find dh_ag95_description)/urdf/dh_ag95.ros2_control.xacro" />
<!-- gripper -->
<xacro:dh_ag95_gripper prefix="${prefix}" parent="${parent}">
<xacro:insert_block name="origin" />
</xacro:dh_ag95_gripper>
<!-- ros2_control -->
<xacro:dh_ag95_gripper_ros2_control
name="dh_ag95_gripper"
prefix="${prefix}"
com_port="${com_port}"
hardware="${hardware}"
mock_sensor_commands="${mock_sensor_commands}"
/>
</xacro:macro>
</robot>

View file

@ -190,7 +190,7 @@
<pose> -0.020673 0 0.007524 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>false</use_parent_model_frame>
<!-- <use_parent_model_frame>false</use_parent_model_frame> -->
</axis>
<parent>${prefix}${fingerprefix}_inner_knuckle</parent>
<child>${prefix}${fingerprefix}_finger</child>
@ -210,7 +210,7 @@
<xacro:finger_joint prefix="${prefix}" fingerprefix="${fingerprefix}" />
<xacro:inner_knuckle_joint prefix="${prefix}" fingerprefix="${fingerprefix}"
reflect="${reflect}" />
<xacro:inner_knuckle_to_finger_joint prefix="${prefix}" fingerprefix="${fingerprefix}" />
<!-- <xacro:inner_knuckle_to_finger_joint prefix="${prefix}" fingerprefix="${fingerprefix}" /> -->
<xacro:finger_pad_joint prefix="${prefix}" fingerprefix="${fingerprefix}" />
</xacro:macro>
@ -327,4 +327,4 @@
</xacro:macro>
</robot>
</robot>