Skip to content

Commit

Permalink
Add a tray to the turtlebot4 (#6)
Browse files Browse the repository at this point in the history
* Use composition for ros_gz and Gazebo in Nav2 launch files

* Reimplements the turtlebot4 launch file from nav2_bringup in order to
use composition for ros_gz and Gazebo. Hopefully, some of this will be
upstreamed to Nav2.

* This also updates the step size to 0.004 to speed up simulation

Signed-off-by: Addisu Z. Taddese <[email protected]>

* Add a tray to the turtlebot4

Signed-off-by: Addisu Z. Taddese <[email protected]>

---------

Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey authored Sep 21, 2024
1 parent 0aa7607 commit cdc7932
Show file tree
Hide file tree
Showing 4 changed files with 40 additions and 1 deletion.
1 change: 1 addition & 0 deletions ionic_demo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ install(DIRECTORY configs DESTINATION share/${PROJECT_NAME})
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
install(DIRECTORY maps DESTINATION share/${PROJECT_NAME})
install(DIRECTORY worlds DESTINATION share/${PROJECT_NAME})
install(DIRECTORY models DESTINATION share/${PROJECT_NAME})

ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in")

Expand Down
1 change: 1 addition & 0 deletions ionic_demo/hooks/ionic_demo.dsv.in
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;share/@PROJECT_NAME@/worlds/
prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;share/@PROJECT_NAME@/models/
2 changes: 1 addition & 1 deletion ionic_demo/launch/tb4_spawn_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ def generate_launch_description():

# Launch configuration variables specific to simulation
robot_name = 'ionic_tb4'
robot_sdf = xacro.process(desc_dir / 'urdf' / 'standard' / 'turtlebot4.urdf.xacro')
robot_sdf = xacro.process(ionic_demo_dir / 'models' / 'ionic_tb4.urdf.xacro')

remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]

Expand Down
37 changes: 37 additions & 0 deletions ionic_demo/models/ionic_tb4.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
<?xml version="1.0" ?>
<robot name="ionic_tb4" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find nav2_minimal_tb4_description)/urdf/standard/turtlebot4.urdf.xacro" />
<joint name="extend_tower" type="fixed">
<parent link="tower_sensor_plate"/>
<child link="tray"/>
<origin xyz="0 0 0.5"/>
</joint>
<link name="tray">
<visual>
<geometry>
<cylinder length="0.01" radius="0.137"/>
</geometry>
<material name="wood">
<color rgba="0.631373 0.4 0.184314 1.0"/>
</material>
</visual>
<visual>
<origin xyz="0 0 -0.25"/>
<geometry>
<cylinder length="0.5" radius="0.02"/>
</geometry>
<material name="dark_grey">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.01" radius="0.137"/>
</geometry>
</collision>
<inertial>
<mass value="0.332"/>
<inertia ixx="0.00092982299" ixy="0.0" ixz="0.0" iyy="0.00083033498" iyz="0.0" izz="0.00175985947"/>
</inertial>
</link>
</robot>

0 comments on commit cdc7932

Please sign in to comment.