diff --git a/README.md b/README.md
index 8a71b4e..c071a22 100644
--- a/README.md
+++ b/README.md
@@ -1,5 +1,5 @@
# Simulation Stack
-This package allows you to simulate Marvin (ARV's 2022-2024 robot) using RViz and Gazebo
+This package allows you to simulate ARV robots using RViz and Gazebo
## Package Dependencies
@@ -23,8 +23,7 @@ The simulation is fairly computation intensive so a GPU is recommended. Note tha
## Installation
1. ```cd``` into ```ws/src```
2. ```git clone https://github.com/umigv/simulation_stack.git```
-3. ```cd simulation_stack```
-4. ```./scripts/setup.bash```
+3. ```./simulation_stack/scripts/setup.bash```
## Running the Stack
@@ -35,36 +34,17 @@ The simulation is fairly computation intensive so a GPU is recommended. Note tha
4. ```source install/setup.bash```
### Launching
-Running ```ros2 launch marvin_simulation display.launch.py``` will open RViz and display the robot model. This launch file is made to quickly check if the robot model is correctly formatted and used internally when developing the stack.
+Running ```ros2 launch simulation_common display.launch.py``` will open RViz and display the robot model. This launch file is made to quickly check if the robot model is correctly formatted and used internally when developing the stack.
-Running ```ros2 launch marvin_simulation simulation.launch.py``` will spawn the robot in Gazebo and visualize sensor outputs in RViz. Any project interfacing with the simulation should use this launch file.
-
-
-## Interfacing with the Stack
-### Topics
-#### Robot
-```/cmd_vel``` (```geometry_msgs/msg/Twist```) - target velocity for the robot to move in
-```/odom``` (```nav_msgs/msg/Odometry```) - an estimation of the robot's position and velocity
-
-#### LiDAR
-```/velodyne_points``` (```sensor_msgs/msg/PointCloud2```) - pointcloud output of the LiDAR
-```/scan``` (```sensor_msgs/msg/LaserScan```) - converted laser scan of the LiDAR pointcloud on the x-y plane
-
-#### Camera
-```/zed/camera_info``` (```sensor_msgs/msg/CameraInfo```) - Information about the camera
-```/zed/depth/camera_info``` (```sensor_msgs/msg/CameraInfo```) - Information about the depth camera
-```/zed/depth/image_raw``` (```sensor_msgs/msg/Image```) - Raw depth image
-```/zed/image_raw``` (```sensor_msgs/msg/Image```) - Raw image
-```/zed/points``` (```sensor_msgs/msg/PointCloud2```) - Point cloud of the camera's depth data (warning: visualizing this in RViz is VERY computationally intensive)
-
-#### IMU
-```/imu_controller/out``` (```sensor_msgs/msg/Imu```) - IMU data
+Running ```ros2 launch simulation_common simulation.launch.py``` will spawn the robot in Gazebo and visualize sensor outputs in RViz. Any project interfacing with the simulation should use this launch file.
### Launch File Arguments
#### display.launch.py
+```model``` (default: ```marvin```) - the model to display (remove simulation_ to get model name)
```joint_gui``` (default: ```True```) - whether to enable joint_state_publisher_gui
#### simulation.launch.py
+```model``` (default: ```marvin```) - the model to simulate (remove simulation_ to get model name)
```headless``` (default: ```False```) - whether to enable RViz. If you have other code that runs their own instance of RViz (ex. Nav2), you should set headless to True
```world``` (default: ```empty```) - Name of the Gazebo world file in the world directory
@@ -79,12 +59,16 @@ Running ```ros2 launch marvin_simulation simulation.launch.py``` will spawn the
### Simulation Stack as a Subpackage
Since multiple subteams may use this stack as a dependency, **do not include this stack directly in another subteam stack either as a package or git submodule**. Having multiple instances in the same package will result in conflicts. Instead, develop with simulation without adding simulation to your repostitory, and include this project as a submodule in the main stack.
+
## Sample Image


+
## Learning more
-Visit the [wiki](https://github.com/umigv/simulation_stack/wiki) to learn about how to set up robot models for simulation
+Visit the [wiki](https://github.com/umigv/simulation_stack/wiki) to learn about how to set up robot models for simulation
+Go into the folder of individual robots to see the topics that is outputted
+
## Possible Issues
### symbol lookup error: ... undefined symbol: __libc_pthread_init, version GLIBC_PRIVATE
@@ -101,4 +85,4 @@ This error is caused by [snap variables leaking into terminal variables](https:/
## Credits
Jason Ning and Kari Naga on the sensors team, who created the original URDF files and the Gazebo World in the [marvin](https://github.com/umigv/marvin/tree/main/urdf) repository.
-[UTRA ART](https://github.com/UTRA-ART) for their [full IGVC course world](https://github.com/UTRA-ART/Caffeine/tree/master/worlds/). Any file or folder containing IGVC is under the original [Apache 2.0 license](https://github.com/umigv/simulation_stack/blob/igvc_course/marvin_simulation/world/LICENSE)
+[UTRA ART](https://github.com/UTRA-ART) for their [full IGVC course world](https://github.com/UTRA-ART/Caffeine/tree/master/worlds/). Any file or folder containing IGVC is under the original [Apache 2.0 license](https://github.com/umigv/simulation_stack/blob/igvc_course/simulation_common/world/LICENSE)
diff --git a/marvin_simulation/urdf/marvin.xacro b/marvin_simulation/urdf/marvin.xacro
deleted file mode 100644
index 215a616..0000000
--- a/marvin_simulation/urdf/marvin.xacro
+++ /dev/null
@@ -1,90 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- true
- 10
-
-
-
- /gps
- ~/out:=data
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/marvin_simulation/urdf/plugins.xacro b/marvin_simulation/urdf/plugins.xacro
deleted file mode 100644
index 6b8cacf..0000000
--- a/marvin_simulation/urdf/plugins.xacro
+++ /dev/null
@@ -1,30 +0,0 @@
-
-
-
-
-
- 100.0
- base_link
- cmd_vel
-
- left_wheel_joint
- right_wheel_joint
- ${track_width}
- ${2 * wheel_radius}
- true
- true
-
- 1.8
- 30
-
- encoder
- odom
- odom
- true
- true
-
- false
- na
-
-
-
\ No newline at end of file
diff --git a/scripts/setup.bash b/scripts/setup.bash
index 88ac132..be90d5f 100755
--- a/scripts/setup.bash
+++ b/scripts/setup.bash
@@ -19,6 +19,6 @@ colcon build --symlink-install
source install/setup.bash)
# Install IGVC World Models
-bash marvin_simulation/world/igvc_models/install_models.sh)
+bash simulation_common/world/igvc_models/install_models.sh)
echo "Setup successful!"
diff --git a/marvin_simulation/CMakeLists.txt b/simulation_common/CMakeLists.txt
similarity index 93%
rename from marvin_simulation/CMakeLists.txt
rename to simulation_common/CMakeLists.txt
index 840f8c0..c3afba0 100644
--- a/marvin_simulation/CMakeLists.txt
+++ b/simulation_common/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.8)
-project(marvin_simulation)
+project(simulation_common)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
@@ -12,7 +12,7 @@ find_package(ament_cmake REQUIRED)
# find_package( REQUIRED)
install(
- DIRECTORY launch rviz urdf world
+ DIRECTORY launch urdf rviz world
DESTINATION share/${PROJECT_NAME}
)
diff --git a/marvin_simulation/launch/display.launch.py b/simulation_common/launch/display.launch.py
similarity index 71%
rename from marvin_simulation/launch/display.launch.py
rename to simulation_common/launch/display.launch.py
index 4689ba3..1d44ea8 100644
--- a/marvin_simulation/launch/display.launch.py
+++ b/simulation_common/launch/display.launch.py
@@ -2,15 +2,13 @@
import launch
import launch_ros
from launch.actions import DeclareLaunchArgument
-from launch.substitutions import Command, LaunchConfiguration
+from launch.substitutions import Command, LaunchConfiguration, PathJoinSubstitution
+from launch_ros.substitutions import FindPackageShare
import os
-def generate_launch_description():
- # Constants
- package_directory = get_package_share_directory('marvin_simulation')
- model = os.path.join(package_directory, 'urdf', 'marvin.xacro')
- rviz_config = os.path.join(package_directory, 'rviz', 'display.rviz')
+DEFAULT_MODEL_NAME = 'marvin'
+def generate_launch_description():
# Arguments
enable_joint_publisher_launch_arg = DeclareLaunchArgument(
name='joint_gui',
@@ -18,11 +16,26 @@ def generate_launch_description():
description='Flag to enable joint_state_publisher_gui'
)
+ model_launch_arg = DeclareLaunchArgument(
+ name = 'model',
+ default_value = DEFAULT_MODEL_NAME,
+ description = 'name of the robot model'
+ )
+
+ # Constants
+ package_directory = get_package_share_directory('simulation_common')
+ rviz_config = os.path.join(package_directory, 'rviz', 'display.rviz')
+ xacro_file_path = PathJoinSubstitution([
+ FindPackageShare(["simulation_", LaunchConfiguration('model')]),
+ 'urdf',
+ 'model.xacro'
+ ])
+
# Robot Node
robot_state_publisher_node = launch_ros.actions.Node(
package='robot_state_publisher',
executable='robot_state_publisher',
- parameters=[{'robot_description': Command(['xacro ', model])}]
+ parameters=[{'robot_description': Command(['xacro ', xacro_file_path])}]
)
# Wheel Node
@@ -52,6 +65,7 @@ def generate_launch_description():
#Launch Description
return launch.LaunchDescription([
enable_joint_publisher_launch_arg,
+ model_launch_arg,
joint_state_publisher_node,
joint_state_publisher_gui_node,
robot_state_publisher_node,
diff --git a/marvin_simulation/launch/simulation.launch.py b/simulation_common/launch/simulation.launch.py
similarity index 74%
rename from marvin_simulation/launch/simulation.launch.py
rename to simulation_common/launch/simulation.launch.py
index 7927c6c..442606c 100644
--- a/marvin_simulation/launch/simulation.launch.py
+++ b/simulation_common/launch/simulation.launch.py
@@ -2,22 +2,19 @@
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument, ExecuteProcess
-from launch.substitutions import Command, LaunchConfiguration
+from launch.substitutions import Command, LaunchConfiguration, PathJoinSubstitution
+from launch_ros.substitutions import FindPackageShare
from launch.conditions import UnlessCondition
import os
-def generate_launch_description():
- # Constants
- package_directory = get_package_share_directory('marvin_simulation')
- cwd = os.path.join(package_directory, 'launch')
- model = os.path.join(package_directory, 'urdf', 'marvin.xacro')
- rviz_config = os.path.join(package_directory, 'rviz', 'simulation.rviz')
- default_world_name = 'empty'
+DEFAULT_MODEL_NAME = 'marvin'
+DEFAULT_WORLD_NAME = 'empty'
+def generate_launch_description():
# Arguments
world_launch_arg = DeclareLaunchArgument(
name='world',
- default_value=default_world_name,
+ default_value = DEFAULT_WORLD_NAME,
description='Name of world file in the world directory'
)
@@ -27,13 +24,29 @@ def generate_launch_description():
description='Show RViz and Gazebo'
)
+ model_launch_arg = DeclareLaunchArgument(
+ name = 'model',
+ default_value = DEFAULT_MODEL_NAME,
+ description = 'name of the robot model'
+ )
+
+ # Variables
+ package_directory = get_package_share_directory('simulation_common')
+ cwd = os.path.join(package_directory, 'launch')
+ rviz_config = os.path.join(package_directory, 'rviz', 'simulation.rviz')
+ xacro_file_path = PathJoinSubstitution([
+ FindPackageShare(["simulation_", LaunchConfiguration('model')]),
+ 'urdf',
+ 'model.xacro'
+ ])
+
# Robot node
robot_state_publisher_node = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
- parameters=[{'robot_description': Command(['xacro ', model]),
- 'use_sim_time': True}]
+ parameters=[{'robot_description': Command(['xacro ', xacro_file_path]),
+ 'use_sim_time': True}]
)
# Gazebo node
@@ -57,7 +70,7 @@ def generate_launch_description():
package='gazebo_ros',
executable='spawn_entity.py',
arguments=['-topic', 'robot_description',
- '-entity', 'marvin'],
+ '-entity', LaunchConfiguration('model')],
output='screen'
)
@@ -90,6 +103,7 @@ def generate_launch_description():
return LaunchDescription([
world_launch_arg,
headless_launch_arg,
+ model_launch_arg,
robot_state_publisher_node,
gazebo_server,
gazebo_client,
diff --git a/common_xacro/package.xml b/simulation_common/package.xml
similarity index 89%
rename from common_xacro/package.xml
rename to simulation_common/package.xml
index 524fadf..a83b090 100644
--- a/common_xacro/package.xml
+++ b/simulation_common/package.xml
@@ -1,9 +1,9 @@
- common_xacro
+ simulation_common
1.0.0
- ARV Common Xacro Files
+ ARV Simulation Common Files
Ryan Liao
MIT
diff --git a/marvin_simulation/rviz/display.rviz b/simulation_common/rviz/display.rviz
similarity index 100%
rename from marvin_simulation/rviz/display.rviz
rename to simulation_common/rviz/display.rviz
diff --git a/marvin_simulation/rviz/simulation.rviz b/simulation_common/rviz/simulation.rviz
similarity index 100%
rename from marvin_simulation/rviz/simulation.rviz
rename to simulation_common/rviz/simulation.rviz
diff --git a/common_xacro/urdf/physics/inertia.xacro b/simulation_common/urdf/physics/inertia.xacro
similarity index 100%
rename from common_xacro/urdf/physics/inertia.xacro
rename to simulation_common/urdf/physics/inertia.xacro
diff --git a/common_xacro/urdf/sensor/depth_camera.xacro b/simulation_common/urdf/sensor/depth_camera.xacro
similarity index 88%
rename from common_xacro/urdf/sensor/depth_camera.xacro
rename to simulation_common/urdf/sensor/depth_camera.xacro
index 2ff1f5a..ffbd623 100644
--- a/common_xacro/urdf/sensor/depth_camera.xacro
+++ b/simulation_common/urdf/sensor/depth_camera.xacro
@@ -6,16 +6,18 @@
-
-
-
-
-
+
-
+
+
+
+
+
+
+
diff --git a/common_xacro/urdf/sensor/imu.xacro b/simulation_common/urdf/sensor/imu.xacro
similarity index 77%
rename from common_xacro/urdf/sensor/imu.xacro
rename to simulation_common/urdf/sensor/imu.xacro
index 086fd2e..7eaaf4b 100644
--- a/common_xacro/urdf/sensor/imu.xacro
+++ b/simulation_common/urdf/sensor/imu.xacro
@@ -6,32 +6,34 @@
-
-
-
-
-
+
-
+
+
+
+
+
+
+
-
+
-
-
-
-
+
+
+
+
-
+
@@ -51,8 +53,8 @@
-
-
+
+
diff --git a/common_xacro/urdf/wheel/caster.xacro b/simulation_common/urdf/wheel/caster.xacro
similarity index 84%
rename from common_xacro/urdf/wheel/caster.xacro
rename to simulation_common/urdf/wheel/caster.xacro
index ea4a932..8bfb55d 100644
--- a/common_xacro/urdf/wheel/caster.xacro
+++ b/simulation_common/urdf/wheel/caster.xacro
@@ -5,14 +5,16 @@
-
-
-
+
-
+
+
+
+
+
diff --git a/common_xacro/urdf/wheel/wheel.xacro b/simulation_common/urdf/wheel/wheel.xacro
similarity index 84%
rename from common_xacro/urdf/wheel/wheel.xacro
rename to simulation_common/urdf/wheel/wheel.xacro
index 59feb64..f8c4d98 100644
--- a/common_xacro/urdf/wheel/wheel.xacro
+++ b/simulation_common/urdf/wheel/wheel.xacro
@@ -5,15 +5,17 @@
-
-
-
-
+
-
+
+
+
+
+
+
diff --git a/marvin_simulation/world/CHANGES.md b/simulation_common/world/CHANGES.md
similarity index 100%
rename from marvin_simulation/world/CHANGES.md
rename to simulation_common/world/CHANGES.md
diff --git a/marvin_simulation/world/LICENSE b/simulation_common/world/LICENSE
similarity index 100%
rename from marvin_simulation/world/LICENSE
rename to simulation_common/world/LICENSE
diff --git a/marvin_simulation/world/basic_obstacles.world b/simulation_common/world/basic_obstacles.world
similarity index 100%
rename from marvin_simulation/world/basic_obstacles.world
rename to simulation_common/world/basic_obstacles.world
diff --git a/marvin_simulation/world/empty.world b/simulation_common/world/empty.world
similarity index 100%
rename from marvin_simulation/world/empty.world
rename to simulation_common/world/empty.world
diff --git a/marvin_simulation/world/igvc.world b/simulation_common/world/igvc.world
similarity index 100%
rename from marvin_simulation/world/igvc.world
rename to simulation_common/world/igvc.world
diff --git a/marvin_simulation/world/igvc_flat.world b/simulation_common/world/igvc_flat.world
similarity index 100%
rename from marvin_simulation/world/igvc_flat.world
rename to simulation_common/world/igvc_flat.world
diff --git a/marvin_simulation/world/igvc_flatV2.world b/simulation_common/world/igvc_flatV2.world
similarity index 100%
rename from marvin_simulation/world/igvc_flatV2.world
rename to simulation_common/world/igvc_flatV2.world
diff --git a/marvin_simulation/world/igvc_flat_wall.world b/simulation_common/world/igvc_flat_wall.world
similarity index 100%
rename from marvin_simulation/world/igvc_flat_wall.world
rename to simulation_common/world/igvc_flat_wall.world
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/materials/textures/Construction_Barrel_Diffuse.png b/simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/materials/textures/Construction_Barrel_Diffuse.png
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/materials/textures/Construction_Barrel_Diffuse.png
rename to simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/materials/textures/Construction_Barrel_Diffuse.png
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/materials/textures/Construction_Barrel_Spec.png b/simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/materials/textures/Construction_Barrel_Spec.png
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/materials/textures/Construction_Barrel_Spec.png
rename to simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/materials/textures/Construction_Barrel_Spec.png
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/meshes/construction_barrel.dae b/simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/meshes/construction_barrel.dae
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/meshes/construction_barrel.dae
rename to simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/meshes/construction_barrel.dae
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/model-1_3.sdf b/simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/model-1_3.sdf
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/model-1_3.sdf
rename to simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/model-1_3.sdf
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/model-1_4.sdf b/simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/model-1_4.sdf
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/model-1_4.sdf
rename to simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/model-1_4.sdf
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/model.config b/simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/model.config
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/model.config
rename to simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/model.config
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/model.sdf b/simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/model.sdf
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/construction_barrel/model.sdf
rename to simulation_common/world/igvc_models/igvc_basic_ground/construction_barrel/model.sdf
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/scripts/grass_plane.material b/simulation_common/world/igvc_models/igvc_basic_ground/materials/scripts/grass_plane.material
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/scripts/grass_plane.material
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/scripts/grass_plane.material
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_grass.material b/simulation_common/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_grass.material
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_grass.material
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_grass.material
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_pavement.material b/simulation_common/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_pavement.material
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_pavement.material
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_pavement.material
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_pavement_old.material b/simulation_common/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_pavement_old.material
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_pavement_old.material
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/scripts/igvc_pavement_old.material
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/scripts/pavement_plane.material b/simulation_common/world/igvc_models/igvc_basic_ground/materials/scripts/pavement_plane.material
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/scripts/pavement_plane.material
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/scripts/pavement_plane.material
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass.png b/simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass.png
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass.png
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass.png
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass_large.png b/simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass_large.png
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass_large.png
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass_large.png
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass_original.png b/simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass_original.png
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass_original.png
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_grass_original.png
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavement.png b/simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavement.png
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavement.png
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavement.png
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavementV2.png b/simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavementV2.png
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavementV2.png
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavementV2.png
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavement_original.png b/simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavement_original.png
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavement_original.png
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/IGVC_pavement_original.png
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/grass.png b/simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/grass.png
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/grass.png
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/grass.png
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/grey.PNG b/simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/grey.PNG
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/materials/textures/grey.PNG
rename to simulation_common/world/igvc_models/igvc_basic_ground/materials/textures/grey.PNG
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/model.config b/simulation_common/world/igvc_models/igvc_basic_ground/model.config
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/model.config
rename to simulation_common/world/igvc_models/igvc_basic_ground/model.config
diff --git a/marvin_simulation/world/igvc_models/igvc_basic_ground/model.sdf b/simulation_common/world/igvc_models/igvc_basic_ground/model.sdf
similarity index 100%
rename from marvin_simulation/world/igvc_models/igvc_basic_ground/model.sdf
rename to simulation_common/world/igvc_models/igvc_basic_ground/model.sdf
diff --git a/marvin_simulation/world/igvc_models/install_models.sh b/simulation_common/world/igvc_models/install_models.sh
similarity index 100%
rename from marvin_simulation/world/igvc_models/install_models.sh
rename to simulation_common/world/igvc_models/install_models.sh
diff --git a/marvin_simulation/world/igvc_wall.world b/simulation_common/world/igvc_wall.world
similarity index 100%
rename from marvin_simulation/world/igvc_wall.world
rename to simulation_common/world/igvc_wall.world
diff --git a/common_xacro/CMakeLists.txt b/simulation_marvin/CMakeLists.txt
similarity index 97%
rename from common_xacro/CMakeLists.txt
rename to simulation_marvin/CMakeLists.txt
index b51d6a0..3ed73e2 100644
--- a/common_xacro/CMakeLists.txt
+++ b/simulation_marvin/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.8)
-project(common_xacro)
+project(simulation_marvin)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
diff --git a/marvin_simulation/package.xml b/simulation_marvin/package.xml
similarity index 87%
rename from marvin_simulation/package.xml
rename to simulation_marvin/package.xml
index 97899ed..c7d83a2 100644
--- a/marvin_simulation/package.xml
+++ b/simulation_marvin/package.xml
@@ -1,9 +1,9 @@
- marvin_simulation
+ simulation_marvin
1.0.0
- Simulation model for ARV's 2022-2024 robot "Marvin"
+ Simulation model for ARV's 2024 robot "Marvin"
Ryan Liao
MIT
diff --git a/simulation_marvin/readme.md b/simulation_marvin/readme.md
new file mode 100644
index 0000000..cb5bfac
--- /dev/null
+++ b/simulation_marvin/readme.md
@@ -0,0 +1,21 @@
+## Marvin
+ARV's robot used in IGVC 2024
+
+## Topics
+### Robot
+```/cmd_vel``` (```geometry_msgs/msg/Twist```) - target velocity for the robot to move in
+```/odom``` (```nav_msgs/msg/Odometry```) - an estimation of the robot's position and velocity
+
+### LiDAR
+```/velodyne_points``` (```sensor_msgs/msg/PointCloud2```) - pointcloud output of the LiDAR
+```/scan``` (```sensor_msgs/msg/LaserScan```) - converted laser scan of the LiDAR pointcloud on the x-y plane
+
+### Camera
+```/zed/camera_info``` (```sensor_msgs/msg/CameraInfo```) - Information about the camera
+```/zed/depth/camera_info``` (```sensor_msgs/msg/CameraInfo```) - Information about the depth camera
+```/zed/depth/image_raw``` (```sensor_msgs/msg/Image```) - Raw depth image
+```/zed/image_raw``` (```sensor_msgs/msg/Image```) - Raw image
+```/zed/points``` (```sensor_msgs/msg/PointCloud2```) - Point cloud of the camera's depth data (warning: visualizing this in RViz is VERY computationally intensive)
+
+### IMU
+```/imu_controller/out``` (```sensor_msgs/msg/Imu```) - IMU data
\ No newline at end of file
diff --git a/marvin_simulation/urdf/chassis.xacro b/simulation_marvin/urdf/chassis.xacro
similarity index 94%
rename from marvin_simulation/urdf/chassis.xacro
rename to simulation_marvin/urdf/chassis.xacro
index 205f443..db49bd3 100644
--- a/marvin_simulation/urdf/chassis.xacro
+++ b/simulation_marvin/urdf/chassis.xacro
@@ -2,8 +2,8 @@
-
-
+
+
diff --git a/marvin_simulation/urdf/constants.xacro b/simulation_marvin/urdf/constants.xacro
similarity index 50%
rename from marvin_simulation/urdf/constants.xacro
rename to simulation_marvin/urdf/constants.xacro
index a05e997..9b379cb 100644
--- a/marvin_simulation/urdf/constants.xacro
+++ b/simulation_marvin/urdf/constants.xacro
@@ -2,56 +2,43 @@
-
-
-
-
+
+
+
+
-
-
+
+
-
-
+
+
-
-
+
+
-
-
-
+
+
+
-
-
-
-
+
+
+
+
-
-
-
+
+
-
-
-
-
+
+
-
+
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/simulation_marvin/urdf/model.xacro b/simulation_marvin/urdf/model.xacro
new file mode 100644
index 0000000..1aeba1f
--- /dev/null
+++ b/simulation_marvin/urdf/model.xacro
@@ -0,0 +1,115 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ true
+ 10
+
+
+
+ /gps
+ ~/out:=data
+
+
+
+
+
+
+
+
+
+ 100.0
+ base_link
+ cmd_vel
+
+ left_wheel_joint
+ right_wheel_joint
+ ${2 * wheel_x_offset}
+ ${2 * 6.1875 * 0.0254}
+ true
+ true
+
+ 1.8
+ 30
+
+ encoder
+ odom
+ odom
+ true
+ true
+
+ false
+ na
+
+
+
\ No newline at end of file