feat: add table and initial position params
This commit is contained in:
parent
c82466ed4a
commit
a10ded747a
3 changed files with 130 additions and 13 deletions
|
@ -11,6 +11,7 @@
|
|||
<xacro:include filename="$(find dh_ag95_description)/urdf/dh_ag95_macro.urdf.xacro" />
|
||||
<xacro:include filename="$(find dh_ag145_description)/urdf/dh_ag145_macro.urdf.xacro" />
|
||||
<xacro:include filename="$(find aubo_description)/urdf/sensors.xacro" />
|
||||
<xacro:include filename="$(find simple_gz_gripper)/urdf/simple_gripper_macro.xacro"/>
|
||||
|
||||
<xacro:property name="hardware" value="$(arg hardware)"/>
|
||||
<xacro:property name="robot_ip" value="$(arg robot_ip)"/>
|
||||
|
@ -242,11 +243,12 @@
|
|||
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
|
||||
</joint>
|
||||
|
||||
<!-- <xacro:if value="${with_gripper=='true'}"> -->
|
||||
<xacro:dh_ag145_gripper prefix="" parent="wrist3_Link">
|
||||
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
|
||||
</xacro:dh_ag145_gripper>
|
||||
<!-- </xacro:if> -->
|
||||
<!-- <xacro:dh_ag145_gripper prefix="" parent="wrist3_Link"> -->
|
||||
<!-- <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> -->
|
||||
<!-- </xacro:dh_ag145_gripper> -->
|
||||
<xacro:simple_parallel_gripper prefix="" parent="wrist3_Link">
|
||||
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 1.57" />
|
||||
</xacro:simple_parallel_gripper>
|
||||
|
||||
|
||||
<xacro:rgbd parent="wrist3_Link" tf_prefix="">
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
<ros2_control name="aubo_hardware_interface" type="system">
|
||||
<hardware>
|
||||
<xacro:if value="${hardware=='gazebo'}">
|
||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||
</xacro:if>
|
||||
<xacro:if value="${hardware=='mock'}">
|
||||
<plugin>mock_components/GenericSystem</plugin>
|
||||
|
@ -19,7 +19,9 @@
|
|||
<command_interface name="position" />
|
||||
<command_interface name="velocity" />
|
||||
|
||||
<state_interface name="position" />
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">0.0</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
|
||||
|
@ -28,7 +30,14 @@
|
|||
<command_interface name="position" />
|
||||
<command_interface name="velocity" />
|
||||
|
||||
<state_interface name="position" />
|
||||
<xacro:if value="${hardware=='gazebo'}">
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">0.5</param>
|
||||
</state_interface>
|
||||
</xacro:if>
|
||||
<xacro:if value="${hardware=='real' or hardware=='mock'}">
|
||||
<state_interface name="position" />
|
||||
</xacro:if>
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
|
||||
|
@ -37,7 +46,14 @@
|
|||
<command_interface name="position" />
|
||||
<command_interface name="velocity" />
|
||||
|
||||
<state_interface name="position" />
|
||||
<xacro:if value="${hardware=='gazebo'}">
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">1.75</param>
|
||||
</state_interface>
|
||||
</xacro:if>
|
||||
<xacro:if value="${hardware=='real' or hardware=='mock'}">
|
||||
<state_interface name="position" />
|
||||
</xacro:if>
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
|
||||
|
@ -45,7 +61,14 @@
|
|||
<command_interface name="position" />
|
||||
<command_interface name="velocity" />
|
||||
|
||||
<state_interface name="position" />
|
||||
<xacro:if value="${hardware=='gazebo'}">
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">0.0</param>
|
||||
</state_interface>
|
||||
</xacro:if>
|
||||
<xacro:if value="${hardware=='real' or hardware=='mock'}">
|
||||
<state_interface name="position" />
|
||||
</xacro:if>
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
|
||||
|
@ -53,7 +76,14 @@
|
|||
<command_interface name="position" />
|
||||
<command_interface name="velocity" />
|
||||
|
||||
<state_interface name="position" />
|
||||
<xacro:if value="${hardware=='gazebo'}">
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">1.57</param>
|
||||
</state_interface>
|
||||
</xacro:if>
|
||||
<xacro:if value="${hardware=='real' or hardware=='mock'}">
|
||||
<state_interface name="position" />
|
||||
</xacro:if>
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
|
||||
|
@ -61,7 +91,14 @@
|
|||
<command_interface name="position" />
|
||||
<command_interface name="velocity" />
|
||||
|
||||
<state_interface name="position" />
|
||||
<xacro:if value="${hardware=='gazebo'}">
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">0.0</param>
|
||||
</state_interface>
|
||||
</xacro:if>
|
||||
<xacro:if value="${hardware=='real' or hardware=='mock'}">
|
||||
<state_interface name="position" />
|
||||
</xacro:if>
|
||||
<state_interface name="velocity" />
|
||||
</joint>
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue