Configuring and creating scenes
UWSim scenes
UWSim scenes are XML-formatted documents stored by default on the data/scenes folder. A set of example scenes is included. These are:
- g500ARM5.xml: A 3D model of the G500 vehicle with the ARM5 manipulator.
- cirs.xml: a virtual reproduction of the CIRS[1] installations (University of Girona). It is a water tank of 8x16 meters, and maximum depth of 5m, with a 2D poster printed at the bottom. The scenario contains a G500 robot with an ARM5 arm. The G500 robot has two onboard cameras.
- shipwreck.xml: a scenario consisting of a shipwreck, and two G500 vehicles with an ARM5 arm.
The XML file describes the general scenario, and simulation parameters. However, robots are described with an URDF [2] file. An scene XML file may make a reference to an URDF file for including a robot into the scene.
You can create new scenes by writing a XML file according to the XML syntax described in the following section. Then, to make UWSim load your scene, simply run it with the --configfile option, e.g:
rosrun UWSim UWSim --configfile path/to/yourScene.xml
XML syntax
Let's explain the main XML tags with the cirs.xml example:
<?xml version="1.0"?>
<!DOCTYPE UWSimScene SYSTEM "UWSimScene.dtd" >
<UWSimScene>
<oceanState>
<windx> 0.04 </windx>
<windy> 0.04 </windy>
<windSpeed> 12 </windSpeed>
<depth> 1000 </depth>
<reflectionDamping> 0.35 </reflectionDamping>
<waveScale> 1e-7 </waveScale>
<isNotChoppy> 0 </isNotChoppy>
<choppyFactor> 2.5 </choppyFactor>
<crestFoamHeight> 2.2 </crestFoamHeight>
<oceanSurfaceHeight> 0 </oceanSurfaceHeight>
<fog>
<density> 0.1 </density>
<color>
<r>0</r>
<g>0.05</g>
<b>0.3</b>
</color>
</fog>
<color>
<r>0.0</r>
<g>0.05</g>
<b>0.3</b>
</color>
<attenuation>
<r>0.015</r>
<g>0.0075 </g>
<b> 0.005 </b>
</attenuation>
</oceanState>
<simParams>
<disableShaders> 0 </disableShaders>
<resw> 800 </resw>
<resh> 600 </resh>
<offsetp>
<x>0</x>
<y>0</y>
<z>0</z>
</offsetp>
<offsetr>
<x> 3.14</x>
<y> 0</y>
<z> -1.57 </z>
</offsetr>
</simParams>
<camera>
<freeMotion> 1 </freeMotion>
<objectToTrack>girona500/base_link</objectToTrack>
<fov> 60 </fov>
<aspectRatio> 1.33 </aspectRatio>
<near> 1 </near>
<far> 10000 </far>
<position>
<x>-5</x>
<y>-5 </y>
<z>8 </z>
</position>
<lookAt>
<x>0</x>
<y>0 </y>
<z>0 </z>
</lookAt>
</camera>
<vehicle>
<name>girona500</name>
<file>data/scenes/g500ARM5.urdf</file>
<jointValues>
<joint> 0 </joint>
<joint> M_PI_4</joint>
<joint> M_PI_4 </joint>
<joint> 0 </joint>
<joint>-0.3 </joint>
</jointValues>
<position>
<x> 0</x>
<y> 0 </y>
<z> 0 </z>
</position>
<orientation>
<r>0</r>
<p>0</p>
<y>0</y>
</orientation>
<virtualCamera>
<name>bowtech1</name>
<relativeTo>part0</relativeTo>
<resw> 320 </resw>
<resh> 240 </resh>
<position>
<x>-0.2</x>
<y> -0.1 </y>
<z> 0 </z>
</position>
<orientation>
<r>0</r>
<p>0</p>
<y>1.57 </y>
</orientation>
</virtualCamera>
<virtualCamera>
<name>bowtech2</name>
<relativeTo>part0</relativeTo>
<resw> 320</resw>
<resh> 240 </resh>
<position>
<x>-0.2</x>
<y> 0.1 </y>
<z> 0 </z>
</position>
<orientation>
<r>0</r>
<p>0</p>
<y>1.57 </y>
</orientation>
</virtualCamera>
</vehicle>
<object>
<name>terrain</name>
<file>terrain/CIRS/cirs_trident.osg</file>
<position>
<x> 0</x>
<y> 0 </y>
<z> 0 </z>
</position>
<orientation>
<r>0</r>
<p>0</p>
<y>0</y>
</orientation>
<offsetp>
<x>-1.5</x>
<y>-3.0</y>
<z>0</z>
</offsetp>
<offsetr>
<x> 3.1415</x>
<y> 0</y>
<z> -1.57 </z>
</offsetr>
</object>
<object>
<name> blackbox </name>
<file> objects/blackbox_uib_trimesh.osg </file>
<position>
<x> 0</x>
<y> 0 </y>
<z> 4.8 </z>
</position>
<orientation>
<r>0</r>
<p>3.1415</p>
<y>0</y>
</orientation>
</object>
<rosInterfaces>
<ROSOdomToPAT>
<topic> /dataNavigator </topic>
<vehicleName> girona500 </vehicleName>
</ROSOdomToPAT>
<PATToROSOdom>
<topic> /uwsim/girona500_odom </topic>
<vehicleName> girona500 </vehicleName>
</PATToROSOdom>
<ArmToROSJointState>
<topic>/uwsim/joint_state</topic>
<vehicleName> girona500 </vehicleName>
</ArmToROSJointState>
<ROSJointStateToArm>
<topic>/uwsim/joint_state_command</topic>
<vehicleName> girona500 </vehicleName>
</ROSJointStateToArm>
<VirtualCameraToROSImage>
<cameraName>bowtech1</cameraName>
<imageTopic> /uwsim/camera1 </imageTopic>
<infoTopic> /uwsim/camera1_info </infoTopic>
</VirtualCameraToROSImage>
</rosInterfaces>
</UWSimScene>
The <oceanState> block allows configuring ocean parameters as:
- Wind direction and speed, with <windx>, <windy> and <windSpeed>. Will affect to the amount and height of waves.
- Underwater color and visibility, with <fog></pre> and <pre><color>.
- Underwater color attenuation with <attenuation>
With the <simParams> block, it is possible to:
- Disable the shaders (for video cards not supporting them), via <disableShaders>. Without shaders, visualization will be very simple.
- Set the resolution of the simulation window, with <resw> and <resh> (width and height respectively).
- Set the simulation world frame. By default, the ocean surface is created in a fixed frame where Z axis points upwards (towards the sky). If you want the world frame to be different than this (i.e. need the Z axis pointing towards the ocean floor), you can set a position and orientation offset with <offsetp> and <offsetr>. The former indicates the new frame position with respect to the original one. The latter indicates a roll, pitch, yaw rotation of the new frame with respect to the default.
The block <camera> sets the main camera parameters. The main camera is the one that observes the scene and renders to the main window.
- Set <freeMotion> to 1 if you want to freely move the camera with the mouse buttons. If set to 0, the camera will automatically look towards the object specified in <objectToTrack, and only the rotation around the tracked object and the distance to it will be controllable with the mouse buttons.
- <fov>, <aspectRatio>, <near> and <far> set, respectively, the field of view (in degrees) of the camera, the image aspect ratio and the near and far clipping planes (in meters).
- <position> and <lookAt> set the pose of the camera, in absolute coordinates in case <freeMotion> is 1, or relative to the target object if the camera is tracking an object.
With the <vehicle> tag you can include underwater robots:
- The <name> tags indicates the name of the vehicle and will be used for referencing from other parts, such as setting ROS interfaces.
- <file> indicates an URDF file describing the robot.
- In case the robot includes non-fixed joints, you can set a default value for them with <jointValues>.
- The position of the robot in the scene can be set with <position> and <orientation>. These are given with respect to the world frame that the user sets in <simParams>.
- With the <virtualCamera> tag, virtual cameras can be added relative to any link of the vehicle. Virtual cameras are OSG cameras that are attached to an object, observe the scene, and may have a ROS interface for publishing the captured image. You can set its position and orientation w.r.t the link to which they are attached via <position>, <orientation> and <relativeTo>, and the image resolution with <resw> and <resh>. Multiple virtual cameras can be defined for the same robot. Experimental: a <parameters> block can be included inside a <virtualCamera> for setting the calibration parameters of the camera, e.g:
<parameters>
<fx>257.986</fx>
<fy>257.341</fy>
<x0>120</x0>
<y0>160</y0>
<f>10</f>
<n>0.18</n>
<k>0</k>
</parameters>
The <object> bock allows to include other 3D models to the scene:
- <file> indicates the 3D model file. All formats supported by OSG are possible: .osg, .ive, .stl, .3ds, etc.
- <offsetp> and <offsetr> indicate an offset between the 3D model frame and another arbitrary frame we may want to use. This allows setting a frame different to the one of the 3D model.
- <position> and <orientation> allow to set the pose of the object in the scene. They indicate the pose of the custom frame (after applying the offset previously mentionned), with respect to the world frame.
Finally, <rosInterfaces> allow to attach ROS interfaces to certain objects:
- <ROSOdomToPAT> listens on a ROS nav_msgs/Odometry topic and applies the position/velocity to a vehicle.
- <PATToROSOdom> publishes the position of a vehicle on a ROS nav_msgs/Odometry topic.
- <ROSJointStateToArm> listens on a ROS sensor_msgs/JointState topic and applies the position/velocity to a manipulator joints.
- <ArmToROSJointState> publishes the joint values of a manipulator on a ROS sensor_msgs/JointState topic.
- <VirtualCameraToROSImage> publishes the image of a virtual camera and its calibration parameters into a sensor_msgs/Image and sensor_msgs/CameraInfo topic respectively.
- <ROSImageToHUD> can be used to insert an external ROS image inside the UWSim window. For example:
<ROSImageToHUD>
<width>640</width>
<height>480</height>
<posx>100</posx>
<posy>50</posy>
<scale>0.5</scale>
<imageTopic>/topic/to/image</imageTopic>
</ROSImageToHUD>