Skip to content

Commit

Permalink
Add description files for potential sim fix
Browse files Browse the repository at this point in the history
  • Loading branch information
MatthijsBurgh committed Jul 18, 2024
1 parent ad5e552 commit 5e19444
Show file tree
Hide file tree
Showing 6 changed files with 520 additions and 1 deletion.
63 changes: 63 additions & 0 deletions hsrb_description/robots/hsrb1s.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
<?xml version="1.0"?>
<robot name="hsrb"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:xacro="http://ros.org/wiki/xacro">

<!-- common xacro -->
<xacro:include filename="$(find hsrb_description)/urdf/common.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/materials.urdf.xacro" />

<!-- links and joints -->
<xacro:include filename="$(find hsrb_description)/urdf/base_v0/base.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/torso_v0/torso.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/head_v0/head.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/arm_v0/arm.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/wrist_v0/wrist.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/hand_v0/hand.urdf.xacro" />

<xacro:arg name="personal_name" default=""/>

<!-- constant -->
<xacro:property name="personal_name" value="$(arg personal_name)"/>
<xacro:property name="robot_name" value="hsrb"/>

<!-- create robot -->
<xacro:hsrb_base prefix="base" robot_namespace="${robot_name}"/>

<xacro:hsrb_torso prefix="torso" parent="base_link" mimic_joint="arm_lift_joint">
<origin xyz="0.0 0.0 0.752" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_torso>

<xacro:hsrb_head prefix="head" parent="torso_lift_link">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_head>

<xacro:hsrb_arm prefix="arm" parent="base_link">
<origin xyz="0.0 0.0 0.340" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_arm>

<xacro:hsrb_wrist prefix="wrist" parent="arm_roll_link" robot_namespace="${robot_name}">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_wrist>

<xacro:hsrb_hand prefix="hand" parent="wrist_roll_link">
<origin xyz="0.012 0.0 0.1405" rpy="0.0 0.0 ${pi}"/>
</xacro:hsrb_hand>

<gazebo>
<plugin name="${robot_name}_ros_control" filename="lib${robot_name}_gazebo_ros_control.so">
<robotNamespace>${robot_name}</robotNamespace>
<legacyModeNS>false</legacyModeNS>
</plugin>

<plugin name="${robot_name}_p3d_ground_truth" filename="libgazebo_ros_p3d.so">
<robotNamespace>${personal_name}/${robot_name}</robotNamespace>
<bodyName>base_footprint</bodyName>
<topicName>odom_ground_truth</topicName>
<frameName>map</frameName>
<updateRate>30</updateRate>
</plugin>
</gazebo>
</robot>
63 changes: 63 additions & 0 deletions hsrb_description/robots/hsrb2s.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
<?xml version="1.0"?>
<robot name="hsrb"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:xacro="http://ros.org/wiki/xacro">

<!-- common xacro -->
<xacro:include filename="$(find hsrb_description)/urdf/common.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/materials.urdf.xacro" />

<!-- links and joints -->
<xacro:include filename="$(find hsrb_description)/urdf/base_v1/base.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/torso_v0/torso.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/head_v0/head.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/arm_v0/arm.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/wrist_v0/wrist.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/hand_v0/hand.urdf.xacro" />

<xacro:arg name="personal_name" default=""/>

<!-- constant -->
<xacro:property name="personal_name" value="$(arg personal_name)"/>
<xacro:property name="robot_name" value="hsrb"/>

<!-- create robot -->
<xacro:hsrb_base prefix="base" robot_namespace="${robot_name}"/>

<xacro:hsrb_torso prefix="torso" parent="base_link" mimic_joint="arm_lift_joint">
<origin xyz="0.0 0.0 0.752" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_torso>

<xacro:hsrb_head prefix="head" parent="torso_lift_link">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_head>

<xacro:hsrb_arm prefix="arm" parent="base_link">
<origin xyz="0.0 0.0 0.340" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_arm>

<xacro:hsrb_wrist prefix="wrist" parent="arm_roll_link" robot_namespace="${robot_name}">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_wrist>

<xacro:hsrb_hand prefix="hand" parent="wrist_roll_link">
<origin xyz="0.012 0.0 0.1405" rpy="0.0 0.0 ${pi}"/>
</xacro:hsrb_hand>

<gazebo>
<plugin name="${robot_name}_ros_control" filename="lib${robot_name}_gazebo_ros_control.so">
<robotNamespace>${personal_name}/${robot_name}</robotNamespace>
<legacyModeNS>false</legacyModeNS>
</plugin>

<plugin name="${robot_name}_p3d_ground_truth" filename="libgazebo_ros_p3d.so">
<robotNamespace>${personal_name}/${robot_name}</robotNamespace>
<bodyName>base_footprint</bodyName>
<topicName>odom_ground_truth</topicName>
<frameName>map</frameName>
<updateRate>30</updateRate>
</plugin>
</gazebo>
</robot>
63 changes: 63 additions & 0 deletions hsrb_description/robots/hsrb3s.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
<?xml version="1.0"?>
<robot name="hsrb"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:xacro="http://ros.org/wiki/xacro">

<!-- common xacro -->
<xacro:include filename="$(find hsrb_description)/urdf/common.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/materials.urdf.xacro" />

<!-- links and joints -->
<xacro:include filename="$(find hsrb_description)/urdf/base_v1/base.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/torso_v0/torso.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/head_v1/head.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/arm_v0/arm.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/wrist_v0/wrist.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/hand_v0/hand.urdf.xacro" />

<xacro:arg name="personal_name" default=""/>

<!-- constant -->
<xacro:property name="personal_name" value="$(arg personal_name)"/>
<xacro:property name="robot_name" value="hsrb"/>

<!-- create robot -->
<xacro:hsrb_base prefix="base" robot_namespace="${robot_name}"/>

<xacro:hsrb_torso prefix="torso" parent="base_link" mimic_joint="arm_lift_joint">
<origin xyz="0.0 0.0 0.752" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_torso>

<xacro:hsrb_head prefix="head" parent="torso_lift_link">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_head>

<xacro:hsrb_arm prefix="arm" parent="base_link">
<origin xyz="0.0 0.0 0.340" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_arm>

<xacro:hsrb_wrist prefix="wrist" parent="arm_roll_link" robot_namespace="${robot_name}">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_wrist>

<xacro:hsrb_hand prefix="hand" parent="wrist_roll_link">
<origin xyz="0.012 0.0 0.1405" rpy="0.0 0.0 ${pi}"/>
</xacro:hsrb_hand>

<gazebo>
<plugin name="${robot_name}_ros_control" filename="lib${robot_name}_gazebo_ros_control.so">
<robotNamespace>${personal_name}/${robot_name}</robotNamespace>
<legacyModeNS>false</legacyModeNS>
</plugin>

<plugin name="${robot_name}_p3d_ground_truth" filename="libgazebo_ros_p3d.so">
<robotNamespace>${personal_name}/${robot_name}</robotNamespace>
<bodyName>base_footprint</bodyName>
<topicName>odom_ground_truth</topicName>
<frameName>map</frameName>
<updateRate>30</updateRate>
</plugin>
</gazebo>
</robot>
66 changes: 66 additions & 0 deletions hsrb_description/robots/hsrb4s.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
<?xml version="1.0"?>
<robot name="hsrb"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:xacro="http://ros.org/wiki/xacro">

<!-- common xacro -->
<xacro:include filename="$(find hsrb_description)/urdf/common.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/materials.urdf.xacro" />

<!-- links and joints -->
<xacro:include filename="$(find hero_bringup)/hsrb_description/urdf/base_v2/base.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/torso_v0/torso.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/head_v2/head.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/arm_v0/arm.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/wrist_v0/wrist.urdf.xacro" />
<xacro:include filename="$(find hsrb_description)/urdf/hand_v0/hand.urdf.xacro" />

<xacro:arg name="personal_name" default=""/>
<xacro:arg name="ground_truth_xyz_offset" default="0.0\ 0.0\ 0.0"/>
<xacro:arg name="ground_truth_rpy_offset" default="0.0\ 0.0\ 0.0"/>

<!-- constant -->
<xacro:property name="personal_name" value="$(arg personal_name)"/>
<xacro:property name="robot_name" value="hsrb"/>

<!-- create robot -->
<xacro:hsrb_base prefix="base" personal_name="${personal_name}" robot_namespace="${robot_name}" robot_name="${robot_name}"/>

<xacro:hsrb_torso prefix="torso" parent="base_link" mimic_joint="arm_lift_joint">
<origin xyz="0.0 0.0 0.752" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_torso>

<xacro:hsrb_head prefix="head" parent="torso_lift_link">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_head>

<xacro:hsrb_arm prefix="arm" parent="base_link">
<origin xyz="0.0 0.0 0.340" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_arm>

<xacro:hsrb_wrist prefix="wrist" parent="arm_roll_link" robot_namespace="${robot_name}">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</xacro:hsrb_wrist>

<xacro:hsrb_hand prefix="hand" parent="wrist_roll_link">
<origin xyz="0.012 0.0 0.1405" rpy="0.0 0.0 ${pi}"/>
</xacro:hsrb_hand>

<gazebo>
<plugin name="${robot_name}_ros_control" filename="lib${robot_name}_gazebo_ros_control.so">
<robotNamespace>${personal_name}/${robot_name}</robotNamespace>
<legacyModeNS>false</legacyModeNS>
</plugin>
<plugin name="${robot_name}_p3d_ground_truth" filename="lib${robot_name}_gazebo_ros_p3d.so">
<robotNamespace>${personal_name}/${robot_name}</robotNamespace>
<bodyName>base_footprint</bodyName>
<topicName>odom_ground_truth</topicName>
<frameName>map</frameName>
<updateRate>30</updateRate>
<xyzOffset>$(arg ground_truth_xyz_offset)</xyzOffset>
<rpyOffset>$(arg ground_truth_rpy_offset)</rpyOffset>
</plugin>
</gazebo>
</robot>
2 changes: 1 addition & 1 deletion hsrb_description/robots/upload_hsrb.launch
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@

<group ns="$(arg namespace)">
<param name="robot_description"
command="$(find xacro)/xacro --inorder $(find hsrb_description)/robots/$(arg robot_model).urdf.xacro gazebo_visualization_enabled:=$(arg visualization) implicit_damping:=$(arg implicit_damping) ground_truth_xyz_offset:=$(arg ground_truth_xyz_offset) ground_truth_rpy_offset:=$(arg ground_truth_rpy_offset)" />
command="$(find xacro)/xacro --inorder $(find hero_bringup)/hsrb_description/robots/$(arg robot_model).urdf.xacro gazebo_visualization_enabled:=$(arg visualization) implicit_damping:=$(arg implicit_damping) ground_truth_xyz_offset:=$(arg ground_truth_xyz_offset) ground_truth_rpy_offset:=$(arg ground_truth_rpy_offset)" />
<param name="robot_collision_pair" textfile="$(find hsrb_description)/robots/collision_pair_hsrb.xml" />
</group>
</launch>
Loading

0 comments on commit 5e19444

Please sign in to comment.