Simulator
Overview
OpenMowerROS2 incorporates a Gazebo simulator and ros_gz integration.
TIP
If you are not familiar with Gazebo, please refer to Gazebo tutorials.
WARNING
This project uses Gazebo Fortress. Formerly known as Ignition Fortress.
Getting started
Run the following command to start the simulator:
bash
ros2 launch openmower sim.launch.py
ros2 launch openmower sim.launch.py
If run inside devcontainer, Gazebo GUI will be displayed in a VNC web client. You can access it by opening http://localhost:12345
in your browser.
TIP
Learn more about VNC client.
It's possible to run the simulator with GUI on external host machine. I haven't done it myself since GUI is unstable on MacOS.
Current state
- ✅ Robot model
- ✅ ros2_control controller
- ✅ GPS sensor
- ✅ IMU sensor
- ✅ can of Coke
- 🚧 Emulate OpenMowerROS2 firmware
World definition
xml
<?xml version="1.0" ?>
<sdf version="1.8">
<world name="empty">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="libignition-gazebo-physics-system.so"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="libignition-gazebo-user-commands-system.so"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="libignition-gazebo-scene-broadcaster-system.so"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin
filename="libignition-gazebo-navsat-system"
name="ignition::gazebo::systems::NavSat">
</plugin>
<plugin filename="libignition-gazebo-imu-system.so"
name="ignition::gazebo::systems::Imu">
</plugin>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<world_frame_orientation>ENU</world_frame_orientation>
<latitude_deg>-22.9</latitude_deg>
<longitude_deg>-43.2</longitude_deg>
<elevation>0</elevation>
<heading_deg>0</heading_deg>
</spherical_coordinates>
<!--light-->
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>
<include>
<uri>
https://fuel.gazebosim.org/1.0/OpenRobotics/models/Coke
</uri>
</include>
<include>
<uri>
https://fuel.gazebosim.org/1.0/hexarotor/models/grasspatch
</uri>
</include>
</world>
</sdf>
<?xml version="1.0" ?>
<sdf version="1.8">
<world name="empty">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="libignition-gazebo-physics-system.so"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="libignition-gazebo-user-commands-system.so"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="libignition-gazebo-scene-broadcaster-system.so"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin
filename="libignition-gazebo-navsat-system"
name="ignition::gazebo::systems::NavSat">
</plugin>
<plugin filename="libignition-gazebo-imu-system.so"
name="ignition::gazebo::systems::Imu">
</plugin>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<world_frame_orientation>ENU</world_frame_orientation>
<latitude_deg>-22.9</latitude_deg>
<longitude_deg>-43.2</longitude_deg>
<elevation>0</elevation>
<heading_deg>0</heading_deg>
</spherical_coordinates>
<!--light-->
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>
<include>
<uri>
https://fuel.gazebosim.org/1.0/OpenRobotics/models/Coke
</uri>
</include>
<include>
<uri>
https://fuel.gazebosim.org/1.0/hexarotor/models/grasspatch
</uri>
</include>
</world>
</sdf>