Skip to content
Open
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
3 changes: 3 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
{
"ros.distro": "humble"
}
1 change: 1 addition & 0 deletions docker/bashrc
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,4 @@ source /opt/ros/humble/setup.bash
source /${DOCKERUSER}/ros2_ws/install/local_setup.bash
source /${DOCKERUSER}/ros2_libs_ws/install/local_setup.bash
alias cb='colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Debug'
export USERNAME='default'
61 changes: 60 additions & 1 deletion spesbot_description/urdf/mobile_base.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,17 @@
filename="package://spesbot_description/urdf/meshes/mobile_base.stl" />
</geometry>
</visual>
<collision>
<geometry>
<origin xyz="-0.15 0 0" rpy="0 0 0" />
<box size="0.4 0.3 0.02" />
</geometry>
</collision>
<inertial>
<mass value="5.0" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1" />
</inertial>
</link>
<joint name="left_motor" type="continuous">
<parent link="base_link" />
Expand All @@ -22,6 +33,17 @@
filename="package://spesbot_description/urdf/meshes/wheel.stl" />
</geometry>
</visual>
<collision>
<origin xyz="0 0.03 0" rpy="1.5707 0 0" />
<geometry>
<cylinder radius="0.085" length="0.03"/>
</geometry>
</collision>
<inertial>
<mass value="2.0" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
</inertial>
</link>
<joint name="right_motor" type="continuous">
<parent link="base_link" />
Expand All @@ -37,6 +59,17 @@
</geometry>
<origin xyz="0 0 0" rpy="0 0 3.14159" />
</visual>
<collision>
<origin xyz="0 -0.03 0" rpy="1.5707 0 0" />
<geometry>
<cylinder radius="0.085" length="0.03"/>
</geometry>
</collision>
<inertial>
<mass value="2.0" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
</inertial>
</link>
<joint name="caster_steering_joint" type="continuous">
<parent link="base_link" />
Expand All @@ -51,6 +84,17 @@
filename="package://spesbot_description/urdf/meshes/caster_holder.stl" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder radius="0.03" length="0.01"/>
</geometry>
</collision>
<inertial>
<mass value="0.3" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
</inertial>
</link>
<joint name="caster_wheel_joint" type="continuous">
<parent link="caster_holder_link" />
Expand All @@ -65,6 +109,21 @@
filename="package://spesbot_description/urdf/meshes/caster_wheel.stl" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="1.5707 0 0" />
<geometry>
<cylinder radius="0.033" length="0.03"/>
</geometry>
</collision>
<inertial>
<mass value="2.0" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
</inertial>
</link>

<gazebo reference="caster_wheel_link">
<material>Gazebo/Black</material>
</gazebo>
</xacro:macro>
</robot>
</robot>
7 changes: 7 additions & 0 deletions spesbot_webots/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# SpesBot Webots Simulation

Regenerate the Webots model:
```bash
pip3 install urdf2webots
xacro ${HOME}/ros2_ws/src/spesbot/spesbot_description/urdf/spesbot.xacro | python3 -m urdf2webots.importer --output=${HOME}/ros2_ws/src/spesbot/spesbot_webots/data/protos/SpesBot.proto --tool-slot=base_link
```
Loading