Running the Demo - osrf/mbzirc GitHub Wiki

Follow the instructions in the README.md to install the simulator.

This tutorial shows basic instructions on how to launch a simulation world, spawn vehicles into the environment, send commands to the vehicles, and retrieve sensor data from them.

Launching the Simple Demo world

  1. Source the setup file if the simulator is built from source.

    cd ~/mbzirc_ws
    source install/setup.bash
  2. Launch simple demo world. The first time a world is launched, the simulator will download 3D models from the mbzirc collection on Fuel so make sure you have internet access. The downloaded resources are stored in a local cache directory: <HOME>/.ignition/fuel/fuel.ignitionrobotics.org/openrobotics/models

    ros2 launch mbzirc_ros competition_local.launch.py ign_args:="-v 4 -r simple_demo.sdf"

    simple_demo

Spawning UAVs

There are two multirotor UAVs available: A quadrotor and a hexrotor. You can launch the simulation and spawn these UAVs individually or you can let the simulator take care of spawning all the vehicles for you, see the Configure Platforms via YAML documentation. For the rest of this tutorial we will show how to spawn the vehicles individually via cmd line.

  1. In a separate terminal, spawn a quadrotor UAV

    # remember to source the setup.bash
    source install/setup.bash
    
    ros2 launch mbzirc_ign spawn.launch.py name:=quadrotor_1 world:=simple_demo model:=mbzirc_quadrotor type:=uav x:=1 y:=2 z:=1.05 R:=0 P:=0 Y:=0 slot0:=mbzirc_hd_camera slot1:=mbzirc_rgbd_camera

    Note 1: The name of the vehicle, specified via the name arg, must be unique and it can not contain characters other than alphanumerics

    Note 2: You will see some red error messages like the ones belwo. These are safe to ignore.

    [ign gazebo-1] Error:   Could not find the 'robot' element in the xml file
    [ign gazebo-1]          at line 80 in /tmp/binarydeb/ros-galactic-urdfdom-2.3.5/urdf_parser/src/model.cpp
    [ign gazebo-1] Error [parser_urdf.cc:3227] Unable to call parseURDF on robot model
    [ign gazebo-1] Error [parser.cc:848] parse as old deprecated model file failed.
    [ign gazebo-1] [GUI] [Err] [Model.hh:73] Unable to unserialize sdf::Model    
    

    simple_demo

    To spawn a hexrotor change the model:=mbzirc_quadrotor argument to model:=mbzirc_hexrotor and be sure to give it a unique name

  2. In another terminal, you can take a look at the ROS2 topics available

    ros2 topic list

    You will see the topics printed out in the console:

    /clock
    /mbzirc/phase
    /mbzirc/run_clock
    /mbzirc/score
    /parameter_events
    /quadrotor_1/air_pressure
    /quadrotor_1/cmd_vel
    /quadrotor_1/imu/data
    /quadrotor_1/magnetic_field
    /quadrotor_1/mbzirc/target/stream/report
    /quadrotor_1/mbzirc/target/stream/start
    /quadrotor_1/output/camera_info
    /quadrotor_1/pose
    /quadrotor_1/pose_static
    /quadrotor_1/rx
    /quadrotor_1/slot0/camera_info
    /quadrotor_1/slot0/image_raw
    /quadrotor_1/slot0/optical/camera_info
    /quadrotor_1/slot0/optical/image_raw
    /quadrotor_1/slot1/camera_info
    /quadrotor_1/slot1/depth
    /quadrotor_1/slot1/image_raw
    /quadrotor_1/slot1/optical/camera_info
    /quadrotor_1/slot1/optical/depth
    /quadrotor_1/slot1/optical/image_raw
    /quadrotor_1/slot1/points
    /quadrotor_1/tx
    /rosout
    /tf
    /tf_static
    
    
  3. Make sure data are published, e.g. try echoing the IMU topic

    ros2 topic echo /quadrotor_1/imu/data

    Here is a sample output of the IMU data:

    ---
    header:
      stamp:
        sec: 201
        nanosec: 260000000
      frame_id: quadrotor_1/base_link/imu_sensor
    orientation:
      x: 1.4501223094714753e-16
      y: -2.7930139195879006e-11
      z: -1.3878542264038845e-17
      w: 1.0
    orientation_covariance:
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    angular_velocity:
      x: -0.00825
      y: 0.01225
      z: -0.0025
    angular_velocity_covariance:
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    linear_acceleration:
      x: 0.05
      y: 0.015
      z: 9.75
    linear_acceleration_covariance:
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    - 0.0
    ---
    
  4. Launch rqt_image_view to see the front (slot 0) camera stream from the UAV

    ros2 run rqt_image_view rqt_image_view

    Select the /quadrotor_1/slot0/image_raw topic from the drop down list

    rqt_image_view

  5. Launch rviz too see point cloud data from the rear (slot 1) RGBD camera

    ros2 run rviz2 rviz2

    Set Fixed Frame in the left panel to /quadrotor_1/base_link

    Click on Add button below the left panel, select the By topic tab and choose the /quadrotor_1/slot1/points > PointCloud2 topic to see colored point clouds in the 3D view.

    rviz2

  6. Publish a twist command with linear +z velocity to make the UAV take off

    ros2 topic pub --once /quadrotor_1/cmd_vel geometry_msgs/msg/Twist '{linear: {x: 0.0,y: 0.0, z: 0.5}, angular: {x: 0.0, y: 0.0, z: 0.0}}'
  7. Publish zero velocity twist command to make the UAV hover in the air

    ros2 topic pub --once /quadrotor_1/cmd_vel geometry_msgs/msg/Twist '{linear: {x: 0.0,y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}'
  8. View the TF tree

    # this generates frames.pdf
    ros2 run tf2_tools view_frames
    
    # view the TF tree using your favorite PDF viewer, e.g.
    evince frames.pdf

    quadrotor TF

Spawning a USV

  1. In a separate terminal, spawn a USV

    # remember to source the setup.bash
    source install/setup.bash
    
    ros2 launch mbzirc_ign spawn.launch.py name:=usv world:=simple_demo model:=usv type:=usv x:=15 y:=0 z:=0.3 R:=0 P:=0 Y:=0

    simple_demo

  2. To move the propeller

    ros2 topic pub --once /usv/left/thrust/cmd_thrust std_msgs/msg/Float64 'data: 15'
    ros2 topic pub --once /usv/right/thrust/cmd_thrust std_msgs/msg/Float64 'data: 15'
  3. To rotate the thruster

    ros2 topic pub --once /usv/left/thrust/joint/cmd_pos std_msgs/msg/Float64 'data: -1'
    ros2 topic pub --once /usv/right/thrust/joint/cmd_pos std_msgs/msg/Float64 'data: 1'
⚠️ **GitHub.com Fallback** ⚠️