master.launch

The most important launch within kitcar-gazebo-simulation is the master.launch file located at simulation/src/gazebo_simulation/launch/master.launch. It includes all parts necessary to start the simulation, but also allows to individually modify which parts of the simulation are started.

Example: Start RVIZ with Road’s Groundtruth

One of the simulation’s great strengths is that detailed information of the simulated world is available. The following example shows how to visualize the groundtruth information to get a better understanding of where the car perceives lanes and other information of the road.

Launch

Passing rviz:=true and groundtruth:=true along to the master.launch starts the simulation with an instance of the groundtruth_node and RVIZ.

roslaunch gazebo_simulation master.launch groundtruth:=true rviz:=true

This will open up RVIZ and after starting kitcar-ros detected lines and other objects seen by the car are displayed:


Configurations

There are several other parameters available when launching master.launch. Take a look at the actual launch file for more details:

<?xml version="1.0" encoding="UTF-8"?>
<!-- The simulation master launch file

Use this launch file to start the complete simulation.-->
<launch>
  <!--
       General parameters
  -->
  <!-- Name of the car used. Currently, only dr_drift is supported.-->
  <arg name="car_name" default="dr_drift" />
  <!-- Name of the simulation road and seed used to render the road.-->
  <arg name="road" default="default_road" />
  <arg name="seed" default="__no_value__"/>
  <arg name="force_reload_road" default="false" />
  <!-- Name of the gazebo world.
    By default, the empty base_world is used.
    The "fast_world" can be used to run the simulation as fast as possible.
    -->
  <arg name="world_name" default="base_world" />
  <!-- Indicate whether the simulation should overwrite /clock. -->
  <arg name="use_sim_time" default="true" />

  <!-- Indicate whether the graphical interface should launch. -->
  <arg name="gui" default="true" />
  <!-- Indicate whether rviz is launched. -->
  <arg name="rviz" default="false" />
  <!--
       Indicate which processes are launched.
  -->
  <!-- Indicate whether the car is spawned. -->
  <arg name="include_car" default="true" />
  <!-- Indicate whether the KITcar_brain is started. -->
  <arg name="include_brain" default="false" />
  <!-- Indicate whether KITcar_jetson is started. -->
  <arg name="include_jetson" default="false" />
  <arg name="jetson_debug" default="false" />
  <arg name="jetson_debug_max_rate" default="60" />
  <!-- Indicate whether to include the vehicle simulation or automatic_drive.
       The vehicle simulation is used to simulate vehicle's movement based on KITcar_brain's commands.
       If KITcar_brain is not running, automatic_drive can be used to "drive" the vehicle on the road.
   -->
  <arg name="include_vehicle_simulation" default="false" />
  <arg name="include_automatic_drive" default="true" />
  <arg name="include_mission_mode_plugin" default="false" />
  <!-- Indicate whether to launch the car_state_node. -->
  <arg name="car_state" default="true" />
  <!-- Indicate whether to launch the evaluation pipeline. This includes:
       * simulation_evaluation/speaker_node
       * simulation_evaluation/state_machine_node
       * simulation_evaluation/referee_node -->
  <arg name="evaluate" default="false" />

  <!-- Indicate whether to launch the sign evaluation. -->
  <arg name="evaluate_sign_detection" default="false"/>
  <arg name="sign_evaluation_plots_path" default="$(env KITCAR_REPO_PATH)/kitcar-gazebo-simulation/plots/"/>

  <!-- Indicate whether to launch the groundtruth node. -->
  <arg name="include_groundtruth" default="true" />
  <!-- Indicate whether to include the renderer and object controller. -->
  <arg name="include_renderer" default="true" />
  <arg name="include_object_controller" default="true" />
  <!-- Indicate whether to manually control Gazebo's simulation rate.
       Normally doing this is a bad idea. However, inside of Docker containers Gazebo does not update correctly.
       Setting this argument to true starts the gazebo_rate_control_node. -->
  <arg name="control_sim_rate" default="false" />
  <!-- Only works when using control sim rate! -->
  <arg name="sim_rate_max" default="1000" />
  <arg name="sim_rate_min" default="50" />
  <!-- Indicate whether to launch the label camera which uses the groundtruth to add labels to every camera image.
  -->
  <arg name="label_camera" default="false" />
  <!--
       Vehicle Simulation
  -->
  <!-- Whether the pose or the twist of the vehicle is given to Gazebo. -->
  <arg name="link_pose" default="true" />
  <arg name="link_twist" default="true" />
  <!--
      Camera
  -->
  <!--
      Indicate whether the input image should be transformed using the cycle gan generator.
      Requires a pre-trained generator model and machine_learning pip packages.
   -->
  <arg name="apply_gan" default="false" />
  <arg name="use_wasserstein_gan" default="true" />
  <!-- Indicate whether (colored) input pixels should be preserved when applying the GAN.
      Useful to prevent the network from perturbing traffic signs too much.
   -->
  <arg name="factor_keep_pixels" default="0" />
  <arg name="factor_keep_colored_pixels" default="0" />
  <!--
       Gazebo
  -->
  <arg name="gz_paused" default="false" />
  <arg name="gz_recording" default="false" />
  <arg name="gz_debug" default="false" />
  <arg name="gz_physics" default="ode" />
  <arg name="gz_verbose" default="false" />
  <arg name="gz_respawn" default="false" />
  <arg name="gz_use_clock_frequency" default="false" />
  <arg name="gz_pub_clock_frequency" default="100" />
  <arg name="gz_extra_args" default="" />
  <!--
      Automatic Drive
  -->
  <!--Indicate whether the car should follow a random path on the road.

      This can be especially useful when generating datasets using the simulation.
      The random path allows to maximize variance within the generated images.
  -->
  <arg name="randomize_path" default="false" />
  <!-- Indicate whether the car should always drive parallel to the middle line. -->
  <arg name="align_with_middle_line" default="true" />
  <!-- Indicate whether the car should drive endlessly. -->
  <arg name="automatic_drive_loop" default="true" />
  <!--
       Launch processes
  -->
  <!-- Spawn the car -->
  <include if="$(arg include_car)" file="$(find gazebo_simulation)/launch/spawn_car.launch"/>
  <!-- Launch KITcar_brain -->
  <include if="$(arg include_brain)" file="$(find simulation_brain_link)/launch/brain.launch">
    <arg name="car_name" value="$(arg car_name)" />
  </include>
  <!-- Launch KITcar_jetson -->
  <include if="$(arg include_jetson)" file="$(find simulation_brain_link)/launch/jetson.launch">
    <arg name="debug" value="$(arg jetson_debug)" />
    <arg name="debug_max_rate" value="$(arg jetson_debug_max_rate)" />
  </include>

  <!-- Launch nodes to connect gazebo and kitcar brain -->
  <include file="$(find simulation_brain_link)/launch/vehicle_link.launch">
    <arg name="car_name" value="$(arg car_name)" />
    <arg name="gui" value="$(arg gui)" />
    <arg name="rviz" value="$(arg rviz)" />
    <arg name="set_pose" value="$(arg link_pose)" />
    <arg name="set_twist" value="$(arg link_twist)" />
    <arg name="apply_gan" value="$(arg apply_gan)" />
    <arg name="factor_keep_pixels" value="$(arg factor_keep_pixels)" />
    <arg name="factor_keep_colored_pixels" value="$(arg factor_keep_colored_pixels)" />
    <arg name="use_wasserstein_gan" value="$(arg use_wasserstein_gan)" />
    <arg name="include_vehicle_simulation" value="$(arg include_vehicle_simulation)" />
    <arg name="include_mission_mode_plugin" value="$(arg include_mission_mode_plugin)" />
  </include>
  <!-- Launch automatic drive-->
  <include if="$(arg include_automatic_drive)" file="$(find gazebo_simulation)/launch/automatic_drive.launch">
    <arg name="randomize_path" value="$(arg randomize_path)" />
    <arg name="align_with_middle_line" value="$(arg align_with_middle_line)" />
    <arg name="loop" value="$(arg automatic_drive_loop)" />
  </include>
  <!-- Launch car state -->
  <group if="$(arg car_state)">
    <include file="$(find gazebo_simulation)/launch/car_state_node.launch">
      <arg name="car_name" value="$(arg car_name)" />
      <arg name="rviz" value="$(arg rviz)" />
    </include>
  </group>
  <!-- Launch groundtruth, This includes the groundtruth, the renderer,
  and the object controller. These components, located in the groundtruth_node,
  can create and update the world in Gazebo, place and control obstacles,
  and provide services makeing road lines and other information is easily accessible. -->
  <include file="$(find simulation_groundtruth)/launch/groundtruth_node.launch">
    <arg name="road" value="$(arg road)"/>
    <arg name="seed" value="$(arg seed)"/>
    <arg name="rviz" value="$(arg rviz)"/>
    <arg name="start_groundtruth" default="$(arg include_groundtruth)" />
    <arg name="start_renderer" default="$(arg include_renderer)" />
    <arg name="start_object_controller" default="$(arg include_object_controller)" />
    <arg name="force_reload_road" default="$(arg force_reload_road)" />
  </include>
  <!-- Launch evaluation pipeline -->
  <include if="$(arg evaluate)" file="$(find simulation_evaluation)/launch/evaluation.launch" />
  <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" output="screen" args="-d  $(find gazebo_simulation)/res/simulation.rviz -s $(find gazebo_simulation)/res/kitcar_logo.png" />
  <include if="$(arg evaluate_sign_detection)" file="$(find simulation_evaluation)/launch/sign_evaluation_node.launch">
    <arg name="path" value="$(arg sign_evaluation_plots_path)" />
  </include>
  <!-- Launch Gazebo -->
  <include file="$(find gazebo_simulation)/launch/world.launch">
    <arg name="world_name" value="$(arg world_name)"/>
    <arg name="paused" value="$(arg gz_paused)"/>
    <arg name="use_sim_time" value="$(arg use_sim_time)"/>
    <arg name="gui" value="$(arg gui)"/>
    <arg name="recording" value="$(arg gz_recording)"/>
    <arg name="debug" value="$(arg gz_debug)"/>
    <arg name="physics" default="$(arg gz_physics)"/>
    <arg name="verbose" default="$(arg gz_verbose)"/>
    <arg name="respawn_gazebo" default="$(arg gz_respawn)"/>
    <arg name="use_clock_frequency" default="$(arg gz_use_clock_frequency)"/>
    <arg name="pub_clock_frequency" default="$(arg gz_pub_clock_frequency)"/>
  </include>
  <include if="$(arg control_sim_rate)" file="$(find gazebo_simulation)/launch/gazebo_rate_control_node.launch">
    <arg name="max_update_rate" default="$(arg sim_rate_max)"/>
    <arg name="min_update_rate" default="$(arg sim_rate_min)"/>
  </include>
  <include if="$(arg label_camera)" file="$(find simulation_groundtruth)/launch/label_camera_node.launch" />

</launch>