Skip to content

Gazebo Simulation Setup

Xu Liu edited this page Apr 5, 2022 · 50 revisions

Note: Our code stack is developed and tested in our customized Unity-based simulator, which provides photo-realistic sensor data for our perception algorithms (stereo VIO, semantic SLAM, etc.). For the purpose of allowing the general public to use our stack without much effort, we provide the support for the Gazebo simulator, where the perception-related modules are simplified (e.g., using ground-truth UAV poses).

1. Building and installing the autonomy stack:

Build from source

Using Docker

Important parameter files you should modify according to your purpose:

~/catkin_ws/src/kr_autonomous_flight/autonomy_core/control/control_launch/config/tracker_params_mp.yaml

~/catkin_ws/src/kr_autonomous_flight/autonomy_core/map_plan/map_plan_launch/config/mapper.yaml

~/catkin_ws/src/kr_autonomous_flight/autonomy_sim/gazebo_sim/gazebo_utils/launch/full_sim.launch

2. Running experiments:

You can just follow our video tutorials, which show the full process of running experiments in the simulator:

https://drive.google.com/drive/folders/1_u_9vhmQYLvpo80egivIvrqPKD28iv4K?usp=sharing

Step 1: Launch the experiment:

  • If you built from source:

    source ~/catkin_ws/devel/setup.bash
    roslaunch gazebo_utils full_sim.launch
    
  • If you used Docker:

    cd ~/catkin_ws/src/kr_autonomous_flight
    ./autonomy_sim/docker/run.sh
    roslaunch gazebo_utils full_sim.launch
    

Step 2: Take off:

Then, click motors on after the robot gets commands (keep your eye on the commands in rqt GUI window, in the beginning, they are all 0, but when the robot gets commands, they will have decimal places, e.g., 0.0). Wait for several seconds, click take off in rqt GUI, and you should see the UAV take off.

Troubleshooting

If the robot does not take off. You don't have to relaunch. Instead, you can try clicking the rqt GUI again in the following order: motors off -> motors on -> take off If the robot still does not take off, kill the ROS master and relaunch.

Step 3: Send waypoints:

After the robot takes off, you can click the Waypoint Nav button on the top of RVIZ, drag it to where you want in the map, and click again to place the waypoint. Next, click Publish Waypoints on the lower-left panel of RVIZ. Finally, click Execute waypoint mission in the rqt GUI.

You can save your waypoints (using the "save waypoints" bottom in our RVIZ window) as YAML file. Next time when you want to execute the same mission, you can load the waypoints you saved, as the example shown here. The waypoint.yaml file should have x, y, z position information, and in the following format:

- position: [40.03, -70.81, 5.00]
- position: [-86.49, -68.23, 5.00]

3. Customize your experiments:

Change the take-off position (optional):

Open this file ~/catkin_ws/src/kr_autonomous_flight/autonomy_sim/gazebo_sim/gazebo_utils/launch/full_sim.launch, and change the x, y, and z positions:

<arg name="x" default="-10"/>
<arg name="y" default="-10"/>
<arg name="z" default="1.0"/>     

Other example robots and environments that we provide: https://github.com/KumarRobotics/mrsl_quadrotor

Using your own environment:

Open this file: ~/catkin_ws/src/mrsl_quadrotor/mrsl_quadrotor_launch/launch/gazebo.launch, and change the value of "world_name" in the following line

<arg name="world_name" value="$(find mrsl_quadrotor_description)/worlds/$(arg world).world"/>

to point to the Gazebo world file of your own, i.e.,

<arg name="world_name" value="PATH_TO_YOUR_WORLD_FILE/YOUR_FILE_NAME.world"/>

Further customization:

You can also make further changes, e.g. use different robots, refer to the following files for details: ~/catkin_ws/src/kr_autonomous_flight/autonomy_sim/gazebo_sim/gazebo_utils/launch/simulation.launch ~/catkin_ws/src/mrsl_quadrotor/mrsl_quadrotor_launch/launch/spawn.launch ~/catkin_ws/src/mrsl_quadrotor/mrsl_quadrotor_launch/launch/gazebo.launch

Be careful: only the default robot falcon4_os1_XXX have well-tuned gains, once you change the robot, you need to re-tune controller gains, by changing the following file ~/catkin_ws/src/kr_autonomous_flight/autonomy_sim/gazebo_sim/gazebo_utils/config/falcon4_os1_so3_gains.yaml

The explanation of the parameters in the controller gains YAML file can be found here: https://github.com/KumarRobotics/kr_autonomous_flight/wiki/Position-controller-gains-and-parameters-(so3_control)

4. Running with multiple robots:

Use different frame_prefix for different robots in this file. Refer to this document for more instructions.

Clone this wiki locally