|
1 | 1 | # Simulation Stack |
2 | | -This package allows you to simulate Marvin (ARV's 2022-2024 robot) using RViz and Gazebo |
| 2 | +This package allows you to simulate ARV robots using RViz and Gazebo |
3 | 3 |
|
4 | 4 |
|
5 | 5 | ## Package Dependencies |
@@ -35,36 +35,17 @@ The simulation is fairly computation intensive so a GPU is recommended. Note tha |
35 | 35 | 4. ```source install/setup.bash``` |
36 | 36 |
|
37 | 37 | ### Launching |
38 | | -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. |
| 38 | +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. |
39 | 39 |
|
40 | | -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. |
41 | | - |
42 | | - |
43 | | -## Interfacing with the Stack |
44 | | -### Topics |
45 | | -#### Robot |
46 | | -```/cmd_vel``` (```geometry_msgs/msg/Twist```) - target velocity for the robot to move in |
47 | | -```/odom``` (```nav_msgs/msg/Odometry```) - an estimation of the robot's position and velocity |
48 | | - |
49 | | -#### LiDAR |
50 | | -```/velodyne_points``` (```sensor_msgs/msg/PointCloud2```) - pointcloud output of the LiDAR |
51 | | -```/scan``` (```sensor_msgs/msg/LaserScan```) - converted laser scan of the LiDAR pointcloud on the x-y plane |
52 | | - |
53 | | -#### Camera |
54 | | -```/zed/camera_info``` (```sensor_msgs/msg/CameraInfo```) - Information about the camera |
55 | | -```/zed/depth/camera_info``` (```sensor_msgs/msg/CameraInfo```) - Information about the depth camera |
56 | | -```/zed/depth/image_raw``` (```sensor_msgs/msg/Image```) - Raw depth image |
57 | | -```/zed/image_raw``` (```sensor_msgs/msg/Image```) - Raw image |
58 | | -```/zed/points``` (```sensor_msgs/msg/PointCloud2```) - Point cloud of the camera's depth data (warning: visualizing this in RViz is VERY computationally intensive) |
59 | | - |
60 | | -#### IMU |
61 | | -```/imu_controller/out``` (```sensor_msgs/msg/Imu```) - IMU data |
| 40 | +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. |
62 | 41 |
|
63 | 42 | ### Launch File Arguments |
64 | 43 | #### display.launch.py |
| 44 | +```model``` (default: ```marvin```) - the model to display (remove simulation_ to get model name) |
65 | 45 | ```joint_gui``` (default: ```True```) - whether to enable joint_state_publisher_gui |
66 | 46 |
|
67 | 47 | #### simulation.launch.py |
| 48 | +```model``` (default: ```marvin```) - the model to simulate (remove simulation_ to get model name) |
68 | 49 | ```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 |
69 | 50 | ```world``` (default: ```empty```) - Name of the Gazebo world file in the world directory |
70 | 51 |
|
@@ -101,4 +82,4 @@ This error is caused by [snap variables leaking into terminal variables](https:/ |
101 | 82 | ## Credits |
102 | 83 | 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. |
103 | 84 |
|
104 | | -[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) |
| 85 | +[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) |
0 commit comments