Skip to content
New issue

Have a question about this project? # for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “#”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? # to your account

Support bumper sensors in Gazebo #99

Merged
merged 10 commits into from
May 9, 2023
Merged
Show file tree
Hide file tree
Changes from all 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
104 changes: 104 additions & 0 deletions create_description/meshes/bumper_1.dae

Large diffs are not rendered by default.

104 changes: 104 additions & 0 deletions create_description/meshes/bumper_2.dae

Large diffs are not rendered by default.

5 changes: 3 additions & 2 deletions create_description/urdf/create_1.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
<?xml version="1.0" ?>
<robot name="create_1" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="create_1"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find create_description)/urdf/create_base.urdf.xacro" />
<xacro:include filename="$(find create_description)/urdf/create_1_gazebo.urdf.xacro" />

<xacro:create_base wheel_separation="0.26" base_diameter="0.3302">
<xacro:create_base wheel_separation="0.26" base_diameter="0.3302" version="1">
<mesh filename="package://create_description/meshes/create_1.dae" />
</xacro:create_base>
</robot>
5 changes: 3 additions & 2 deletions create_description/urdf/create_2.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
<?xml version="1.0" ?>
<robot name="create_2" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="create_2"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find create_description)/urdf/create_base.urdf.xacro" />
<xacro:include filename="$(find create_description)/urdf/create_2_gazebo.urdf.xacro" />

<xacro:create_base wheel_separation="0.235" base_diameter="0.3485">
<xacro:create_base wheel_separation="0.235" base_diameter="0.3485" version="2">
<mesh filename="package://create_description/meshes/create_2.dae" />
</xacro:create_base>
</robot>
224 changes: 126 additions & 98 deletions create_description/urdf/create_base.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,115 +4,115 @@

<xacro:macro name="create_wheel" params="prefix y_offset wheel_radius wheel_width">
<link name="${prefix}_wheel_link">
<inertial>
<origin xyz="0 0 0" />
<mass value="0.01" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.01" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>

<visual>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}" />
</geometry>
</visual>
<visual>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}" />
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}" />
</geometry>
</collision>
</link>

<joint name="${prefix}_wheel_joint" type="continuous">
<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="0 ${y_offset} 0.015" rpy="0 0 0" />
<parent link="base_link" />
<child link="${prefix}_wheel_link" />
<axis xyz="0 1 0" />
</joint>
</xacro:macro>

<xacro:macro name="create_base" params="diffdrive_update_rate:=40 wheel_separation wheel_radius:=0.036 wheel_width:=0.024 wheel_torque:=1.0 wheel_accel:=1.8 mass_kg:=3.5 base_diameter *mesh">
<xacro:macro name="create_base" params="diffdrive_update_rate:=40 wheel_separation wheel_radius:=0.036 wheel_width:=0.024 wheel_torque:=1.0 wheel_accel:=1.8 mass_kg:=3.5 base_diameter version *mesh">
<xacro:include filename="$(find create_description)/urdf/create_base_gazebo.urdf.xacro" />

<link name="base_footprint">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
<material name="Green" />
</visual>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
<material name="Green" />
</visual>

<collision>
<origin xyz="0 0 0.017" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
<collision>
<origin xyz="0 0 0.017" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>

<link name="base_link">
<inertial>
<mass value="2" />
<origin xyz="0 0 0.0" />
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.5" />
</inertial>
<inertial>
<mass value="2" />
<origin xyz="0 0 0.0" />
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.5" />
</inertial>

<visual>
<origin xyz=" 0 0 0.0308" rpy="0 0 0" />
<geometry>
<xacro:insert_block name="mesh" />
</geometry>
</visual>
<visual>
<origin xyz=" 0 0 0.0308" rpy="0 0 0" />
<geometry>
<xacro:insert_block name="mesh" />
</geometry>
</visual>

<collision>
<origin xyz="0.0 0.0 0.0308" rpy="0 0 0" />
<geometry>
<cylinder length="0.0611632" radius="0.16495" />
</geometry>
</collision>
<collision>
<origin xyz="0.0 0.0 0.0308" rpy="0 0 0" />
<geometry>
<cylinder length="0.0611632" radius="0.16495" />
</geometry>
</collision>
</link>

<link name="wall_sensor_link">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
</link>

<link name="left_cliff_sensor_link">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
</link>

<link name="right_cliff_sensor_link">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
</link>

<link name="leftfront_cliff_sensor_link">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01" />
</inertial>
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01" />
</inertial>
</link>

<link name="rightfront_cliff_sensor_link">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
</link>

<joint name="base_footprint_joint" type="fixed">
Expand Down Expand Up @@ -154,12 +154,39 @@
<xacro:create_wheel prefix="left" y_offset="${wheel_separation / 2}" wheel_radius="${wheel_radius}" wheel_width="${wheel_width}"/>
<xacro:create_wheel prefix="right" y_offset="${wheel_separation / -2}" wheel_radius="${wheel_radius}" wheel_width="${wheel_width}"/>

<!-- bumper sensor link -->
<link name="bumper_link">
<collision name="bumper_link_collision">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://create_description/meshes/bumper_${version}.dae"/>
</geometry>
</collision>
</link>

<joint name="bumper_joint" type="fixed">
<origin xyz="-0.0025 0 0" rpy="0 0 0" />
<parent link="base_link" />
<child link="bumper_link" />
<axis xyz="0 0 0" />
</joint>

<!-- omni_ir sensor link -->
<link name="omni_ir_link">
</link>

<joint name="omni_ir_joint" type="fixed">
<origin xyz="${base_diameter/2 - 0.025} 0 0.0775" rpy="0 0 0" />
<parent link="base_link" />
<child link="omni_ir_link" />
<axis xyz="0 0 0" />
</joint>

<!--<link name="rear_wheel_link">
<inertial>
<origin xyz="0 0 0"/>
<mass value="0.001" />
<inertia ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0" izz="0.0001" />
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001" />
</inertial>

<visual>
Expand All @@ -184,25 +211,25 @@
</joint>-->

<link name="front_wheel_link">
<inertial>
<origin xyz="0 0 0" />
<mass value="0.01" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.01" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>

<visual>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<geometry>
<sphere radius="0.018" />
</geometry>
</visual>
<visual>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<geometry>
<sphere radius="0.018" />
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<geometry>
<sphere radius="0.018" />
</geometry>
</collision>
<collision>
<origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
<geometry>
<sphere radius="0.018" />
</geometry>
</collision>
</link>

<!-- fixed because there's no transmission -->
Expand All @@ -220,17 +247,18 @@
<child link="gyro_link" />
</joint>
<link name="gyro_link">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001" />
</inertial>
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001" />
</inertial>
</link>

<!-- Simulation sensors -->
<xacro:sim_create_base/>
<xacro:sim_create_wall_sensor/>
<xacro:sim_create_cliff_sensors/>
<xacro:sim_imu/>
<xacro:sim_bumper/>
</xacro:macro>
</robot>
18 changes: 18 additions & 0 deletions create_description/urdf/create_base_gazebo.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<robotBaseFrame>base_footprint</robotBaseFrame>
<publishWheelJointState>true</publishWheelJointState>
</plugin>

<plugin name="p3d_base_controller" filename="libgazebo_ros_p3d.so">
Expand Down Expand Up @@ -81,6 +82,23 @@
</gazebo>
</xacro:macro>

<xacro:macro name="sim_bumper">
<gazebo reference="bumper_link">
<sensor name="sim_bumper" type="contact">
<alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
<material>Gazebo/Red</material>
<contact>
<collision>base_footprint_fixed_joint_lump__bumper_link_collision_collision_2</collision>
</contact>
<plugin name="gazebo_ros_bumper_controller" filename="libgazebo_ros_bumper.so">
<bumperTopicName>bumper</bumperTopicName>
<frameName>bumper_link</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>

<xacro:macro name="sim_create_wall_sensor">
<gazebo reference="wall_sensor_link">
<sensor type="ray" name="wall_sensor">
Expand Down