Skip to content

Commit

Permalink
Update docs
Browse files Browse the repository at this point in the history
  • Loading branch information
Ryan4253 committed Feb 5, 2025
1 parent e4ac408 commit 22c9578
Show file tree
Hide file tree
Showing 2 changed files with 33 additions and 28 deletions.
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 simulation_marvin 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 simulation_marvin 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 simulation_marvin 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/simulation_marvin/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)
21 changes: 21 additions & 0 deletions simulation_marvin/readme.md
Original file line number Diff line number Diff line change
@@ -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

0 comments on commit 22c9578

Please sign in to comment.