Skip to content
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
120 changes: 120 additions & 0 deletions src/description/models/terrain_world/meshes/terrain.dae

Large diffs are not rendered by default.

10 changes: 10 additions & 0 deletions src/description/models/terrain_world/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<?xml version="1.0"?>
<model>
<name>terrain_world</name>
<version>1.0</version>
<sdf version="1.7">model.sdf</sdf>
<author>
<name>Rishav Nair</name>
</author>
<description>Terrain imported from Blender (.glb)</description>
</model>
34 changes: 34 additions & 0 deletions src/description/models/terrain_world/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
<?xml version="1.0"?>
<sdf version="1.7">
<model name="terrain_world">
<static>true</static>
<link name="terrain_world_link">
<visual name="terrain_world_visual">
<geometry>
<mesh>
<uri>model://terrain_world/meshes/terrain.dae</uri>
</mesh>
</geometry>
<!-- <material>
<script>
<uri>model://terrain/meshes/scripts</uri>
<name>RepeatedSand/Diffuse</name>
</script>
</material> -->
<material>
<ambient>0.85 0.76 0.52 1</ambient>
<diffuse>0.85 0.76 0.52 1</diffuse>
<specular>0.0 0.0 0.0 1</specular>
</material>

</visual>
<collision name="terrain_world_collision">
<geometry>
<mesh>
<uri>model://terrain_world/meshes/terrain.dae</uri>
</mesh>
</geometry>
</collision>
</link>
</model>
</sdf>
2 changes: 1 addition & 1 deletion src/description/urdf/athena_drive.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -52,4 +52,4 @@
</xacro:unless>


</robot>
</robot>
8 changes: 4 additions & 4 deletions src/description/urdf/athena_drive_description.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@
<parent link="swerve_mount_1_link" />
<child link="steer_1_link" />
<axis xyz="0 1 0" />
<limit lower="0" upper="6.2832" effort="200" velocity="3" />
<limit lower="-3.1416" upper="3.1416" effort="200" velocity="3" />
</joint>

<link name="wheel_bracket_1_link">
Expand Down Expand Up @@ -237,7 +237,7 @@
<parent link="swerve_mount_4_link" />
<child link="steer_4_link" />
<axis xyz="0 1 0" />
<limit lower="0" upper="6.2832" effort="200" velocity="3" />
<limit lower="-3.1416" upper="3.1416" effort="200" velocity="3" />
</joint>

<link name="wheel_bracket_4_link">
Expand Down Expand Up @@ -389,7 +389,7 @@
<parent link="swerve_mount_2_link" />
<child link="steer_2_link" />
<axis xyz="0 1 0" />
<limit lower="0" upper="6.2832" effort="200" velocity="3" />
<limit lower="-3.1416" upper="3.1416" effort="200" velocity="3" />
</joint>

<link name="wheel_bracket_2_link">
Expand Down Expand Up @@ -510,7 +510,7 @@
<parent link="swerve_mount_3_link" />
<child link="steer_3_link" />
<axis xyz="0 1 0" />
<limit lower="0" upper="6.28318530718" effort="200" velocity="3" />
<limit lower="-3.1416" upper="3.1416" effort="200" velocity="3" />
</joint>

<link name="wheel_bracket_3_link">
Expand Down
32 changes: 32 additions & 0 deletions src/description/worlds/terrain_world.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
<?xml version="1.0" ?>
<sdf version="1.7">
<world name="default">
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<world_frame_orientation>ENU</world_frame_orientation>

<latitude_deg>38.42391162772634</latitude_deg>
<longitude_deg>-110.78490558433397</longitude_deg>

<elevation>0.0</elevation>

<heading_deg>0.0</heading_deg>
</spherical_coordinates>
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>
<include>
<uri>model://terrain_world</uri>
</include>
</world>
</sdf>
8 changes: 7 additions & 1 deletion src/simulation/launch/bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,11 @@
default_value='empty.sdf',
description='Gazebo world file to load'
),
DeclareLaunchArgument(
'world_name',
default_value='default',
description='Name of the world inside Gazebo'
),
]

def generate_launch_description():
Expand Down Expand Up @@ -54,7 +59,8 @@ def generate_launch_description():
launch_arguments=[
('namespace', LaunchConfiguration('namespace')),
('rviz', LaunchConfiguration('rviz')),
('use_sim_time', LaunchConfiguration('use_sim_time'))
('use_sim_time', LaunchConfiguration('use_sim_time')),
('world_name', LaunchConfiguration('world_name'))
]
)

Expand Down