Skip to content
Draft
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
40 changes: 12 additions & 28 deletions README.md
Original file line number Diff line number Diff line change
@@ -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
Expand All @@ -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
Expand All @@ -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

Expand All @@ -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
![image](https://github.com/umigv/simulation_stack/assets/71594512/d06b174b-d1e1-4ed9-87ef-9c0c3b0abce3)
![image](https://github.com/umigv/simulation_stack/assets/71594512/9130685b-c081-4591-942f-6b38e1be852f)


## 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
Expand All @@ -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)
90 changes: 0 additions & 90 deletions marvin_simulation/urdf/marvin.xacro

This file was deleted.

30 changes: 0 additions & 30 deletions marvin_simulation/urdf/plugins.xacro

This file was deleted.

2 changes: 1 addition & 1 deletion scripts/setup.bash
Original file line number Diff line number Diff line change
Expand Up @@ -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!"
Original file line number Diff line number Diff line change
@@ -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)
Expand All @@ -12,7 +12,7 @@ find_package(ament_cmake REQUIRED)
# find_package(<dependency> REQUIRED)

install(
DIRECTORY launch rviz urdf world
DIRECTORY launch urdf rviz world
DESTINATION share/${PROJECT_NAME}
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,27 +2,40 @@
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',
default_value='True',
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
Expand Down Expand Up @@ -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,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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'
)

Expand All @@ -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
Expand All @@ -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'
)

Expand Down Expand Up @@ -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,
Expand Down
4 changes: 2 additions & 2 deletions common_xacro/package.xml → simulation_common/package.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>common_xacro</name>
<name>simulation_common</name>
<version>1.0.0</version>
<description>ARV Common Xacro Files</description>
<description>ARV Simulation Common Files</description>
<maintainer email="[email protected]">Ryan Liao</maintainer>
<license>MIT</license>

Expand Down
Loading