Skip to content

3D Underwater Lidar

M1chaelM edited this page Aug 13, 2020 · 18 revisions

Overview

This tutorial will launch a basic tank environment with a 3D lidar sensor mounted to a pedestal and a hovering cylindrical target.

  • The sensor uses the GPURaySensor, configured to emulate the properties of 3D at Depth's SL3 underwater lidar.
  • The sensor itself covers a fixed field of view but it attached to a stand that can pan and tilt.

Prerequisites

This tutorial assumes you have previously [installed the DAVE repositories](roslaunch nps_uw_sensors_gazebo uw_lidar_standalone.launch).

Launch and run the simulation

  • To launch the environment, run:
roslaunch nps_uw_sensors_gazebo uw_lidar_standalone.launch
  • If all goes well Gazebo should launch into a simulation environment that looks like this:

  • Note that by default, the simulation is paused and no lidar rays are displayed.
  • Click the play icon to unpause.
  • The lidar rays will display and the sensor will pan to face the target cylinder.
  • The end result will look like this:

Properties

The 3D underwater Lidar sensor has the following properties by default:

  • The lidar sensor covers a 30° x 30° sector.
  • It uses 145 simulated rays in each horizontal and vertical axis.
  • The resolution is set to 0.1 to produce 10 data points per ray, resulting in a point cloud of 1450 x 1450 points.
  • The default range is set to a maximum of 20 meters

ROS topics

The sensor outputs point cloud data to the following ROS topic:

/nps_gazebo_ros_uw/pulse_lidar/points

The plugin also publishes the following topics which are used to control the sensor stand (see Controlling pan and tilt, below):

/nps_gazebo_ros_static_lidar_robot/lidar_pan_cmd
/nps_gazebo_ros_static_lidar_robot/lidar_tilt_cmd

Visualizing with rviz

A basic rviz configuration for visualizing the plugin point cloud data is saved under nps_uw_sensors_gazebo/rviz/uw_lidar.rviz. To bring up rviz with this configuration:

  1. Navigate to the root of your catkin workspace. For example:
    cd ~/uuv_ws/
    
  2. Launch the simulation in Gazebo:
    roslaunch nps_uw_sensors_gazebo uw_lidar_standalone.launch
    
  3. Unpause the simulation to begin generating point cloud data.
  4. In a separate terminal, launch RViz using the uw_lidar.rviz configuration file. From the root of your catkin workspace, run:
    rosrun rviz rviz -d src/nps_uw_sensors_gazebo/rviz/uw_lidar.rviz
    

If successful, RViz should launch a separate window that looks something like this:

Controlling pan and tilt

  • The lidar sensor is configured to scan a fixed 30° x 30° 3D field of view.
  • The sensor stand is capable of 350° panning motion and 60° tilt, which extends the total reachable view to 360° x 90°.
  • The sensor stand position is controlled through the GazeboRosPulseLidar plugin, and can be set in two ways:
    • Statically, from the uw_lidar_basic.world file. (Useful for setting the initial target position).
    • Dynamically, by publishing the desired coordinate to the pan or tilt ros topics. (Useful for controlling the motion of the stand.)

Setting the initial position from the world file

The initial pan and tilt position for the sensor stand, can be set using the <pan_position> and <tilt_position> elements of the GazeboRosPulseLidar plugin element in uw_lidar_basic.world. The relevant lines are:

<plugin name="pulse_lidar_control" filename="libgazebo_ros_pulse_lidar_plugin.so" >
  <pan_position>-1.57079632679</pan_position>
  <tilt_position>0</tilt_position>
</plugin>
  • Both values are given in radians.
    • The pan range is -35π/36 to 35π/36.
    • The tilt range is -π/6 to π/6.
    • By default, the pan position is set to -π/2, and the tilt is set to 0.
  • The pan and tilt positions are controlled by PIDs, so the specified position is treated as a target position.
  • The sensor stand will move toward the target position as soon as the simulation begins to run.
  • Changing the values in the world file will cause the sensor stand to move toward the target positions indicated by the new values.

Setting the position dynamically

Once the simulation is running, the target pan and tilt positions of the sensor stand can be updated dynamically by publishing the desired target value to their respective ros topics.

For example, to cause the stand to pan to 60° (π/3), open a new terminal and run:

rostopic pub /nps_gazebo_ros_static_lidar_robot/lidar_pan_cmd std_msgs/Float32 -- 1.0471975512

Similarly, to cause the sensor to tilt up 10° (π/18), run:

rostopic pub /nps_gazebo_ros_static_lidar_robot/lidar_tilt_cmd std_msgs/Float32 -- 0.17453292519

Note: target position vs actual position

The basic testing environment provided in this tutorial does not simulate the effect of being submerged in water, and no friction terms have been specified. Since the sensor is relatively massive, PIDs used to control it's position will not achieve their target perfectly for all angles. This holds particularly in the case of angles at the high and low end of the tilt range, since the controller is fighting gravity. Future improvements are planned to resolve this issue and enhance the fidelity of the simulation, but these are currently on hold until we have a working underwater demonstration.

Clone this wiki locally