Skip to content
Duane Davis edited this page May 8, 2020 · 33 revisions

Tutorial: DVL Examples (dvl_gazebo ROS Package)

Overview

The ROS dvl_gazebo package provides SDF, URDF, and Xacro files for utilization, testing, and evaluation of the UUV Simulator and Woods Hole Oceanographic Institute (WHOI) Deep Submergence Laboratory environment ROS Doppler Velocity Logger (DVL) plugins. The included exemplar models and plugin parameters utilized by the fully-functional launch files described in this tutorial roughly align with the specifications of the Teledyne Workhorse Navigator 600. Model and world files can be used as is for testing of the DVL model. The Xacro files can be used to add a DVL to an existing robot model.

Xacro files are provided for the following DVLs are provided in addition to the WHN 600 of the executable examples:

  • Nortek DVL 500-300m
  • Nortek DVL 500-6000m
  • Nortek DVL 1000-300m
  • Nortek DVL 1000-4000m
  • Sonardyne Syrinx 600
  • Teledyne Explorer 1000 (Phased Array)
  • Teledyne Explorer 4000 (Piston)

These templates can be utilized in a manner similar to those associated with the Teledyne WHN 600. For the time being, these files utilize the WHN 600 visual model but implement correct collision, mass, and performance characteristics (per the respective vendor-provided data sheets). Updated visual models will be added to the package as the meshes are developed.

UUV Simulator Plugin Utilization

The package contains two launch files that can be run independently (both covered in more detail below) to launch DVL models utilizing the UUV Simulator DVL plugin. These can be executed with the following commands:

roslaunch dvl_gazebo uuvsim_teledyne_whn_standalone.launch

OR

roslaunch dvl_gazebo uuvsim_teledyne_whn.launch

Once Gazebo is up, choosing to "Follow" the teledyne_whn model simplifies the visualization.

In addition, the package contains URDF and SDF models and Xacro macros for use in implementing DVLs in other Gazebo simulations.

uuvsim_teledyne_whn_standalone.launch

Launch and Operation

The uuvsim_teledyne_whn_standalone.launch file instantiates a Gazebo world (by default, the uuv_gazebo_worlds/ocean_waves.world provided by the UUV simulator) containing a single Teledyne DVL attached to a dimensionless link (the DVL is not within the world's camera field of view, but the it is located just below the water's surface near the model's center as depicted below).

/tutorials/images/standalone_whn_startup.png

After approximately 10 seconds, the DVL will begin moving in a descending left-hand turn. It will continue with this pattern until impacting the bottom. During its descent, the DVL sonar beam visualization will indicate its perceived height above the bottom.

/tutorials/images/standalone_whn_running.png

The following launch arguments can be used to modify the execution:

  • gui (default true): set to false to run the simulation without the GUI or rendered scene.
  • paused (default false): set to true to start the simulation with physics paused (can be unpaused and repaused with the /gazebo/pause_physics and /gazebo/unpause_physics services respecively.
  • world_name (default uuv_gazebo_worlds/worlds/ocean_waves.world): used to change the world model that is used when the simulation commences.

ROS Topics

The following ROS topics are relevant:

  • /dvl/dvl/state (std_msgs/Bool): should be true as long as the DVL is active (can be activated and deactivated with the /dvl/dvl/change_state service).
  • /dvl/dvl (uuv_sensor_ros_plugins_msgs/DVL): provides the current DVL-derived linear velocities (relative to the dvl_base_link, which is oriented forward-left-up) and covariance, perceived altitude above the bottom (computed as the average of the 4 individual sonar ranges), and the ranges and other information for the 4 individual DVL sonar beams.
  • /dvl/dvl_twist (geometry_msgs/TwistWithCovarianceStamped): provides the current DVL-derived linear velocities
  • /dvl/dvl_sonar0, /dvl/dvl_sonar0, /dvl/dvl_sonar0, and /dvl/dvl_sonar0 (sensor_msgs/Range): Range and other information for each individual DVL sonar.

ROS Nodes

spawn_whn (gazebo_ros/spawn_model)

The spawn_whn node is used to spawn the standalone WHN600 model in the gazebo world. Once the model has been spawned, this node will terminate.

apply_velocity (dvl_gazebo/simple_motion.py)

The apply_velocity node publishes periodic gazebo_msgs/ModelState messages to the /gazebo/set_model_state topic to control the motion of the DVL model (fixed speed forward at 1 meter per second, down at 0.5 meters per second, and left turn at 0.25 radians per second). The model name and frame to which the new state is relative are provided as ROS parameters (set in the launch file). The frame of relative motion should be the model's base link to ensure correct motion.

joint_state_publisher (joint_state_publisher/joint_state_publisher)

The joint_state_publisher node continually publishes the state of the model's joints to the /joint_states topic as it moves through the world so that they will be available to the robot state publisher.

robot_state_publisher (robot_state_publisher/robot_state_publisher)

The robot_state_publisher node subscribes to the /joint_states topic and publishes transforms to the /tf topic. The DVL plugin uses the transforms associated with the 4 DVL sonar beams in its calculations.

See launch file for additional information regarding parameters and arguments.

uuvsim_teledyne_whn.launch

Launch and Operation

The uuvsim_teledyne_whn.launch file uses macros from a Xacro file to generate a WHN600 DVL model mounted on a simple medium-sized "UUV". The cylindrical UUV is 4 meters in length, 1 meter in diameter, and has a mass or 200 kilograms. As with the standalone DVL example, the model is not within the world's camera field of view, but the it is located just below the water's surface near the model's center as depicted below.

/tutorials/images/mounted_whn_startup.png

After approximately 10 seconds, the UUVwill begin moving in a descending left-hand turn. It will continue with this pattern until impacting the bottom. During its descent, the DVL sonar beam visualization will indicate its perceived height above the bottom.

/tutorials/images/mounted_whn_running.png

Launch arguments, ROS nodes, and relevant ROS topics are the same as with the standalone WHN600 example.

Models and Macros

Teledyne WHN URDF (models/teledyne_whn_urdf/model.urdf)

The teledyne_whn_urdf model is a self-contained implementation of the Teledyne WND600 DVL in URDF format. This model can be directly loaded into the ROS parameter server and added to Gazebo scenes with a gazebo_ros/spawn_model node. The standalone WHN600 model is connected to a dimensionless link so that it points directly down. If this model is to be used as the basis for incorporation into a specific URDF robot model, it can be added to the model by copying everything after the dvl_base_link definition into the robot's URDF file and using the dvl_base_joint to connect the DVL to the robot's base link.

In order for the DVL plugin to work correctly, it must have access to the ROS transforms for the robot link to which it is attached. These may be published by the plugin controlling the robot body or by a combination of joint and robot state publishers (as in the standalone DVL example).

Teledyne WHN (models/teledyne_whn/model.sdf)

The teledyne whn model is a self-contained implementation of the Teledyne WND600 DVL in SDF format. This model can be included in any SDF world and connected to a robot in that world through a joint connecting the model's dvl_link to the robot's base link.

In order for the DVL plugin to work correclty, it must have access to the ROS transforms for the robot link to which it is attached. Because SDF is not compatible with the ROS robot state publisher, the transforms must be published from a different source (most likely from the robot's controller plugin).

NOTE: The DVL plugin for this model has not been tested.

Teledyne WHN Macros (urdf/teledyne_whn.xacro)

The teledyne_whn Xacro file provides a set of macros for the addition of a Teledyne WHN600 DVL to an arbitrary Xacro-generated robot model (see urdf/test_teledyne_whn.xacro for a simple example). Four top-level macros are provided:

  • dvl_macro: provides for the generation of a DVL model with a user-specified namespace, parent link (robot base link), inertial reference frame, and origin relative to the inertial reference frame.
  • dvl_sensor_enu: provides for the generation of a DVL model in an east-north-up inertial reference frame (i.e., the default Gazebo frame) with a user-specified namespace, parent link, and origin relative to the inertial reference frame. The test_teledyne_whn.launch example utilizes this macro.
  • dvl_sensor_ned: provides for the generation of a DVL model in a north-east-down inertial reference frame with a user-specified namespace, parent link, and origin relative to the inertial reference frame. The NED frame must be explicitly defined or included in the world model (see worlds/uuv_dave_ocean_waves_watch_dvl.world).
  • dvl_plugin_macro: provides for the generation of a DVL model with user-specified namespace, suffix (sensor ID), parent link, individual sonar ROS topic names, visual scale, update rate, sensor noise parameters, inertial reference frame, and origin relative to the inertial reference frame. This macro provides the most flexibility and can be used to model most real-world DVLs. The dvl_macro macro is essentially a wrapper for this macro and can be used as an example for its use.

Additional Macro Files

The following Xacro files are provided for the generation of URDF models for different commercially available DVLs. Each provide the same top-level macros as teledyne_whn.xacro and implement sensor characteristics as specified in the vendor-provided datasheets. They can be utilized in the same manner as the macros in teledyne_whn.xacro.

  • Nortek DVL500-300m (urdf/nortek_dvl500_300.xacro)
  • Nortek DVL500-6000m (urdf/nortek_dvl500_6000.xacro)
  • Nortek DVL1000-300m (urdf/nortek_dvl1000_300.xacro)
  • Nortek DVL1000-4000m (urdf/nortek_dvl1000_4000.xacro)
  • Sonardyne Syrinx 600 (urdf/sonardyne_syrinx_600.xacro)
  • Teledyne Explorer 1000 (Phased Array) (urdf/teledyne_explorer_1000.xacro)
  • Teledyne Explorer 4000 (Piston) (urdf/teledyne_explorer_4000.xacro)

NOTE for all models and macros: Gravity has been disabled for all of these models for the time being so that they can be incorporated without additional plugins and controllers.

Clone this wiki locally