This package allows you to simulate Marvin (ARV's 2022-2024 robot) using RViz and Gazebo
WARNING - this step recreates your docker container, which resets everything except files within the ws
folder. Make sure your files are within ws
or backed up.
The simulation is fairly computation intensive so a GPU is recommended. Note that the ARV docker image is not able to access the computer's GPU so performance can still be low. Running Linux natively (ex. through dual booting) is recommended for optimal performance.
cd
into ws/src
git clone https://github.com/umigv/simulation_stack.git
cd simulation_stack
./scripts/setup.bash
cd
into ws
source /opt/ros/humble/setup.bash
colcon build --symlink-install
source install/setup.bash
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 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.
/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
/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
/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_controller/out
(sensor_msgs/msg/Imu
) - IMU data
joint_gui
(default: True
) - whether to enable joint_state_publisher_gui
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
empty
- empty worlds
basic_obstacles
- small world with basic obstacles like traffic cones and shelves
igvc
- standard IGVC world with lane lines and ramps
igvc_flat
- flat IGVC world with no ramps
igvc_wall
- standard IGVC world with walls representing lane lines
igvc_flat_wall
- flat IGVC world with walls and no ramps
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.
Visit the wiki to learn about how to set up robot models for simulation
This error is caused by the VSCode snap package setting GTK_PATH, which is then used by the VSCode integrated terminal. There are two solutions:
unset GTK_PATH
This error is caused by snap variables leaking into terminal variables. There are two solutions:
Jason Ning and Kari Naga on the sensors team, who created the original URDF files and the Gazebo World in the marvin repository.
UTRA ART for their full IGVC course world. Any file or folder containing IGVC is under the original Apache 2.0 license