Site icon Wil Selby

Model Dynamics & Sensors

 

Universal Robotic Description Format

Gazebo uses the Universal Robotic Description Format (URDF) which is an XML format for representing a robot model. While URDFs are a useful and standardized format in ROS, they are lacking many features and have not been updated to deal with the evolving needs of robotics. To use a URDF file in Gazebo, some additional simulation-specific tags must be added to work properly with Gazebo. To deal with this issue, a new format called the Simulation Description Format (SDF) was created for use in Gazebo to solve the shortcomings of URDF. SDF is an XML format that describes objects and environments for robot simulators, visualization, and control. SDF Models can range from simple shapes to complex robots and is essentially a collection of links, joints, collision objects, visuals, and plugins. For more details on SDF models, see the tutorial here.

Basic URDF tutorials can be found here for reference and a guide to using URDF models in Gazebo can be found here. Lastly, we will use the Xacro package. Xacro (XML Macros) is an XML macro language. With xacro, you can construct shorter and more readable XML files by using macros that expand to larger XML expressions.

Mesh files are used to visually display the robot model. Gazebo provides a set of simple shapes: box, sphere, and cylinder. Meshes come from a number of places. Google’s 3D warehouse is a good repository of 3D models or you can make your own meshes using a 3D modeler such as Blender or Sketchup. Gazebo requires that mesh files be formatted as STL or Collada, with Collada being the preferred format.

Quadrotor Model Files

The foundation of our quadrotor starts with the multirotor_base.xacro file. This file creates the multirotor base template as well as the rotor template. The “base_link” created here will be used as the common point of reference for the quadrotor. The macro also creates the “base_joint” which fixes the “base_link” to the “base_link_inertia.” The “base_link_inertia” contains the inertia, visual, and collision properties. Here, the mass and inertia variables are used as well as the mesh_file variable. Also, the Gazebo plugin gazebo_multirotor_base_plugin.cpp is referenced. For the motor template, each motor is connected to the quadrotor base with a continuous joint. The collision, visual, and inertia properties are modified and the gazebo_motor_model.cpp Gazebo plugin is referenced. This portion also shows all the motor system properties that can be modified. These properties will be modified to reflect a specific physical system but can also be modified to support different quadrotor orientations by modifying the  direction each motor spins, for example.

The component_snippets.xacro file contains the macros for several simulation related components. The first macro enables logging to a .bag file. Specifically, it calls the gazebo_bag_plugin.cpp which declares which topics should be logged, the log’s filename, and the location to save the log. This plugin can be modified to include additional topics or the traditional rosbag command line tools can be used on an as needed basis as described here. The controller macro includes the gazebo_controller_interface.cpp plugin which relays the desired motor velocities into the Gazebo simulator. Lastly, this file includes the macros to implement several sensors. This includes an IMU, a basic camera, Visual Inertial camera, and odometry sensor. The odometry sensor is used to broadcast the global position of the robot as well the transform between coordinate frames.

The multirotor_base.xacro and component_snippets.xacro files provide the modules necessary to compile a simulated quadrotor that accurately represents a physical system. First, the quadrotor base and rotors are implemented in the kit_c.xacro file. Here, the properties of the physical system measured or estimated for the 3DR Kit C in the Model Verification section are entered. This includes the frame dimensions and the motor model properties. The moments of inertia for both the quadrotor base and an individual rotor are the defined. Finally, using the multirotor_base.xacro macros, the quadrotor base is defined as well as each of the 4 motor and rotor pairs. Here the motor orientation and rotation direction can be modified to support different quadrotor flight configurations such as “X” mode. For consistency, the quadrotor is arranged in the “+” configuration. Lastly, the simulation plugins and sensors defined in the component_snippets.xacro file are added onto the quadrotor frame in the kit_c_base.xacro file. This includes an IMU and an odometry sensor for ground truth measurements as well as the controller and logging macros. It also defines a basic camera and VI camera which can be enabled by the user.

Utilizing Launch Files

Launch files are XML files that describe the nodes that should be run, parameters that should be set, and other attributes of launching a collection of ROS nodes. The roslaunch package contains the roslaunch tools. The roslaunch package enables easily launching multiple ROS nodes locally and remotely via SSH, as well as setting parameters on the Parameter Server by reading in one or more XML configuration files (with the .launch extension) that specify the parameters to set and nodes to launch, as well as the machines that they should be run on. These parameters will be stored on the Parameter Server before any nodes are launched.

Many ROS packages come with launch files, which you can run with:

$ roslaunch package_name file.launch

These launch files usually bring up a set of nodes for the package that provide some aggregate functionality. Examples of the launch files used for this research will be described in the appropriate sections.

Model Verification

A command line tool check_urdf attempts to parse a file as a URDF description, and either prints a description of the resulting kinematic chain, or an error message. The first command creates a urdf file from the xacro file.

rosrun xacro xacro.py kit_c.xacro -o /tmp/kit_c.urdf

Then run the urdf check:

check_urdf kit_c.urdf

The output will state the breakdown of the robot model

robot name is: quad
---------- Successfully Parsed XML ---------------
root Link: base_link has 5 child(ren)
    child(1):  base_link_inertia
    child(2):  rotor_0
    child(3):  rotor_1
    child(4):  rotor_2
    child(5):  rotor_3

This output can be visualized using the command:

urdf_to_graphiz kit_c.urdf

to produce the image below

 

Model Visualization

The quad_rviz.launch file contains the commands to launch the basic nodes required for populating the quadrotor model in the RVIZ simulator. This first node automatically generates the urdf file. This is convenient because it stays up to date and doesn’t use up hard drive space.

<param name="robot_description"
command="$(find xacro)/xacro.py '$(find quad_description)/urdf/kit_c.xacro'"/>

The next portions of the launch file start the joint_state_publisher and robot_state_publisher nodes. The node reads the robot_description parameter, finds all of the non-fixed joints and publishes a JointState message with all those joints defined. The robot_state_publisher node uses the URDF specified by the parameter robot_description and the joint positions from the joint_state_publisher node to calculate the forward kinematics of the robot and publish the results via tf using a kinematic tree model of the robot.

<!-- We do not have a robot connected, so publish fake joint states -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>

<!-- Given the published joint states, publish tf for the robot links -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />

The last command launches RVIZ and loads and RVIZ configuration file. RVIZ lets you load and save different configurations. Different configurations of displays are often useful for different uses of the visualizer.

A configuration contains:

This node launches the quad.rviz node which loads the basic grid and RobotModel tools.

  <!-- Visualisation RVIZ -->
  <node pkg="rviz" type="rviz" name="rviz" args="-d $(find quad_description)/resource/quad.rviz" output="screen"/>

The quadrotor model can be visualized in Rviz by running the command

roslaunch quad_description quad_rviz.launch

which shows the quadrotor in Rviz similar to this

The quadrotor can also be visualized in Gazebo by running the quad_world.launch file. Interacting with Gazebo requires different launch files and nodes compared to RVIZ.

First, the world file is loaded for the simulation. In this example, it is the basic empty_world environment.

  <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" value="$(find quad_gazebo)/worlds/quad_basic.world"/>
    <!-- more default parameters can be changed here -->
  </include>

Next, the 3DR model is spawned into the environment.

  <!-- Spawn 3DR Model -->
   <include file="$(find quad_gazebo)/launch/spawn_quad.launch">
    <arg name="model" value="$(find quad_description)/urdf/kit_c_base.xacro" />
  </include>

This calls the spawn_quad.launch file where some simulation arguments can be set, the xacro model is loaded and the quadrotor’s initial position is defined.

  <arg name="name" default="quad"/>
  <arg name="model" default="$(find quad_description)/urdf/kit_c_base.xacro"/>
  <arg name="tf_prefix" default="$(optenv ROS_NAMESPACE)"/>
  <arg name="x" default="0.0"/>
  <arg name="y" default="0.0"/>
  <arg name="z" default="0.05"/>
  <arg name="roll"  default="0" />
  <arg name="pitch" default="0" />
  <arg name="yaw"   default="3.14" /> <!-- 2.35 -->
  <arg name="enable_logging" default="true"/>
  <arg name="enable_ground_truth" default="true"/>
  <arg name="enable_camera" default="false"/>
  <arg name="enable_VI_sensor" default="false"/>
  <arg name="log_file" default="quad"/>

Next, the quadrotor model is sent to the parameter server and the model is spawned into Gazebo.

  <!-- send the robot XML to param server -->
  <param name="robot_description" command="
    $(find xacro)/xacro.py '$(arg model)'
    enable_logging:=$(arg enable_logging)
    enable_ground_truth:=$(arg enable_ground_truth)
    enable_camera:=$(arg enable_camera)
    enable_VI_sensor:=$(arg enable_VI_sensor)
    log_file:=$(arg log_file)"
  />
  <param name="tf_prefix" type="string" value="$(arg tf_prefix)" />

  <!-- push robot_description to factory and spawn robot in gazebo -->
  <node name="spawn_quad" pkg="gazebo_ros" type="spawn_model"
   args="-param robot_description
         -urdf
         -x $(arg x)
         -y $(arg y)
         -z $(arg z)
	 -R $(arg roll)
	 -P $(arg pitch)
	 -Y $(arg yaw)
         -model $(arg name)"
   respawn="false" output="screen">
  </node>

The quad_world launch file is executed with the following command.

roslaunch quad_gazebo quad_world.launch

which displays the quadrotor model in Gazebo similar to this

 

Additional sensors can be added to the quadrotor platform including a simple RGB camera or a RGBD sensor like the Microsoft Kinect. The first image shows a basic RGB camera mounted on top of the camera as well as a sample output of the camera using the quad_joystick_gps_outdoor_world.launch file.

 

The image below shows a simulated Microsoft Kinect RGBD sensor mounted onto the front arm of the quadrotor. The RGB output is shown alongside the depth image and was taken using the spawn_quad_kinect_kitchen.launch file.

 

[simple-social-share]

Exit mobile version