-
Notifications
You must be signed in to change notification settings - Fork 4
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
feat(turtlebot3_ws): Publish camera rgb through OmniGraph
Note that the `turtlebot3_burger_isaacsim.urdf.xacro` file is based on `turtlebot3_burger.urdf` Refs: - https://github.com/isaac-sim/urdf-importer-extension/blob/b161d55f4bcabe266b8db6707b5c2768aedcde21/source/extensions/omni.importer.urdf/data/urdf/tests/test_sensor.urdf#L52-L58 - https://github.com/isaac-sim/urdf-importer-extension/blob/b161d55f4bcabe266b8db6707b5c2768aedcde21/source/extensions/omni.importer.urdf/data/urdf/tests/test_advanced.urdf#L148-L154
- Loading branch information
Showing
5 changed files
with
242 additions
and
2 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,5 @@ | ||
#!/bin/bash | ||
|
||
cd /home/ros2-essentials/turtlebot3_ws/src/turtlebot3/turtlebot3_description/urdf | ||
# Ref: https://docs.ros.org/en/humble/Tutorials/Intermediate/URDF/Using-Xacro-to-Clean-Up-a-URDF-File.html | ||
xacro turtlebot3_burger_isaacsim.urdf.xacro > /home/ros2-essentials/turtlebot3_ws/src/turtlebot3/turtlebot3_description/urdf/turtlebot3_burger_isaacsim.urdf |
204 changes: 204 additions & 0 deletions
204
...ebot3_ws/src/turtlebot3/turtlebot3_description/urdf/turtlebot3_burger_isaacsim.urdf.xacro
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,204 @@ | ||
<?xml version="1.0" ?> | ||
<robot name="turtlebot3_burger" | ||
xmlns:xacro="http://ros.org/wiki/xacro"> | ||
<!-- <xacro:include filename="$(find turtlebot3_description)/urdf/common_properties.urdf"/> --> | ||
|
||
<!-- Init colour --> | ||
<material name="black"> | ||
<color rgba="0.0 0.0 0.0 1.0"/> | ||
</material> | ||
|
||
<material name="dark"> | ||
<color rgba="0.3 0.3 0.3 1.0"/> | ||
</material> | ||
|
||
<material name="light_black"> | ||
<color rgba="0.4 0.4 0.4 1.0"/> | ||
</material> | ||
|
||
<material name="blue"> | ||
<color rgba="0.0 0.0 0.8 1.0"/> | ||
</material> | ||
|
||
<material name="green"> | ||
<color rgba="0.0 0.8 0.0 1.0"/> | ||
</material> | ||
|
||
<material name="grey"> | ||
<color rgba="0.5 0.5 0.5 1.0"/> | ||
</material> | ||
|
||
<material name="orange"> | ||
<color rgba="1.0 0.4235 0.0392 1.0"/> | ||
</material> | ||
|
||
<material name="brown"> | ||
<color rgba="0.8706 0.8118 0.7647 1.0"/> | ||
</material> | ||
|
||
<material name="red"> | ||
<color rgba="0.8 0.0 0.0 1.0"/> | ||
</material> | ||
|
||
<material name="white"> | ||
<color rgba="1.0 1.0 1.0 1.0"/> | ||
</material> | ||
|
||
<link name="base_footprint"/> | ||
|
||
<joint name="base_joint" type="fixed"> | ||
<parent link="base_footprint"/> | ||
<child link="base_link"/> | ||
<origin xyz="0.0 0.0 0.010" rpy="0 0 0"/> | ||
</joint> | ||
|
||
<link name="base_link"> | ||
<visual> | ||
<origin xyz="-0.032 0 0.0" rpy="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://turtlebot3_description/meshes/bases/burger_base.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="light_black"/> | ||
</visual> | ||
|
||
<collision> | ||
<origin xyz="-0.032 0 0.070" rpy="0 0 0"/> | ||
<geometry> | ||
<box size="0.140 0.140 0.143"/> | ||
</geometry> | ||
</collision> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" rpy="0 0 0"/> | ||
<mass value="8.2573504e-01"/> | ||
<inertia ixx="2.2124416e-03" ixy="-1.2294101e-05" ixz="3.4938785e-05" iyy="2.1193702e-03" iyz="-5.0120904e-06" izz="2.0064271e-03" /> | ||
</inertial> | ||
</link> | ||
|
||
<joint name="wheel_left_joint" type="continuous"> | ||
<parent link="base_link"/> | ||
<child link="wheel_left_link"/> | ||
<origin xyz="0.0 0.08 0.023" rpy="-1.57 0 0"/> | ||
<axis xyz="0 0 1"/> | ||
</joint> | ||
|
||
<link name="wheel_left_link"> | ||
<visual> | ||
<origin xyz="0 0 0" rpy="1.57 0 0"/> | ||
<geometry> | ||
<mesh filename="package://turtlebot3_description/meshes/wheels/left_tire.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="dark"/> | ||
</visual> | ||
|
||
<collision> | ||
<origin xyz="0 0 0" rpy="0 0 0"/> | ||
<geometry> | ||
<cylinder length="0.018" radius="0.033"/> | ||
</geometry> | ||
</collision> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" /> | ||
<mass value="2.8498940e-02" /> | ||
<inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09" iyy="1.1192413e-05" iyz="-1.4400107e-11" izz="2.0712558e-05" /> | ||
</inertial> | ||
</link> | ||
|
||
<joint name="wheel_right_joint" type="continuous"> | ||
<parent link="base_link"/> | ||
<child link="wheel_right_link"/> | ||
<origin xyz="0.0 -0.080 0.023" rpy="-1.57 0 0"/> | ||
<axis xyz="0 0 1"/> | ||
</joint> | ||
|
||
<link name="wheel_right_link"> | ||
<visual> | ||
<origin xyz="0 0 0" rpy="1.57 0 0"/> | ||
<geometry> | ||
<mesh filename="package://turtlebot3_description/meshes/wheels/right_tire.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="dark"/> | ||
</visual> | ||
|
||
<collision> | ||
<origin xyz="0 0 0" rpy="0 0 0"/> | ||
<geometry> | ||
<cylinder length="0.018" radius="0.033"/> | ||
</geometry> | ||
</collision> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" /> | ||
<mass value="2.8498940e-02" /> | ||
<inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09" iyy="1.1192413e-05" iyz="-1.4400107e-11" izz="2.0712558e-05" /> | ||
</inertial> | ||
</link> | ||
|
||
<joint name="caster_back_joint" type="fixed"> | ||
<parent link="base_link"/> | ||
<child link="caster_back_link"/> | ||
<origin xyz="-0.081 0 -0.004" rpy="-1.57 0 0"/> | ||
</joint> | ||
|
||
<link name="caster_back_link"> | ||
<collision> | ||
<origin xyz="0 0.001 0" rpy="0 0 0"/> | ||
<geometry> | ||
<box size="0.030 0.009 0.020"/> | ||
</geometry> | ||
</collision> | ||
|
||
<inertial> | ||
<origin xyz="0 0 0" /> | ||
<mass value="0.005" /> | ||
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" /> | ||
</inertial> | ||
</link> | ||
|
||
<joint name="imu_joint" type="fixed"> | ||
<parent link="base_link"/> | ||
<child link="imu_link"/> | ||
<origin xyz="-0.032 0 0.068" rpy="0 0 0"/> | ||
</joint> | ||
|
||
<link name="imu_link"/> | ||
|
||
<joint name="scan_joint" type="fixed"> | ||
<parent link="base_link"/> | ||
<child link="base_scan"/> | ||
<origin xyz="-0.032 0 0.172" rpy="0 0 0"/> | ||
</joint> | ||
|
||
<link name="base_scan"> | ||
<visual> | ||
<origin xyz="0 0 0.0" rpy="0 0 0"/> | ||
<geometry> | ||
<mesh filename="package://turtlebot3_description/meshes/sensors/lds.stl" scale="0.001 0.001 0.001"/> | ||
</geometry> | ||
<material name="dark"/> | ||
</visual> | ||
|
||
<collision> | ||
<origin xyz="0.015 0 -0.0065" rpy="0 0 0"/> | ||
<geometry> | ||
<cylinder length="0.0315" radius="0.055"/> | ||
</geometry> | ||
</collision> | ||
|
||
<inertial> | ||
<mass value="0.114" /> | ||
<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> | ||
|
||
<sensor name="camera" type="camera" update_rate="30"> | ||
<parent link="base_scan"/> | ||
<origin xyz="0 0 0.03" rpy="${pi/2} 0 ${-pi/2}"/> | ||
<camera> | ||
<image width="640" height="480" hfov="1.5708" format="RGB8" near="0.01" far="50.0"/> | ||
</camera> | ||
</sensor> | ||
|
||
</robot> |