Skip to content
Commits on Source (2)
<launch>
<arg name="paused" default="false"/>
<arg name="gui" default="true"/>
<arg name="use_sim_time" default="true"/>
<node name="plankton_global_sim_time"
pkg="plankton_utils"
exec="plankton_global_sim_time"
output="screen">
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
<include file="$(find-pkg-share gazebo_ros)/launch/gazebo.launch.py">
<arg name="world" value="worlds/pspb_2025_example_lowlight.world"/> <!-- HERE -->
<arg name="pause" value="$(var paused)"/>
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="gui" value="$(var gui)"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
<arg name="verbose" value="true" />
<!-- TODO Remove force_system in foxy, as it will be loaded by default -->
<arg name="extra_gazebo_args" value="-s libgazebo_ros_force_system.so --ros-args -r gazebo:__ns:=/gazebo"/>
</include>
<include file="$(find-pkg-share uuv_assistants)/launch/publish_world_ned_frame.launch">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
</include>
<node name="publish_world_models"
pkg="uuv_assistants"
exec="publish_world_models.py"
output="screen">
<param from="$(find-pkg-share smtupool)/config/empty_pool.yaml"/>
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
</launch>
<launch>
<arg name="paused" default="false"/>
<arg name="gui" default="true"/>
<arg name="use_sim_time" default="true"/>
<node name="plankton_global_sim_time"
pkg="plankton_utils"
exec="plankton_global_sim_time"
output="screen">
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
<include file="$(find-pkg-share gazebo_ros)/launch/gazebo.launch.py">
<arg name="world" value="worlds/pspb_2025_green_lowlight.world"/> <!-- HERE -->
<arg name="pause" value="$(var paused)"/>
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="gui" value="$(var gui)"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
<arg name="verbose" value="true" />
<!-- TODO Remove force_system in foxy, as it will be loaded by default -->
<arg name="extra_gazebo_args" value="-s libgazebo_ros_force_system.so --ros-args -r gazebo:__ns:=/gazebo"/>
</include>
<include file="$(find-pkg-share uuv_assistants)/launch/publish_world_ned_frame.launch">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
</include>
<node name="publish_world_models"
pkg="uuv_assistants"
exec="publish_world_models.py"
output="screen">
<param from="$(find-pkg-share smtupool)/config/empty_pool.yaml"/>
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
</launch>
<launch>
<arg name="paused" default="false"/>
<arg name="gui" default="true"/>
<arg name="use_sim_time" default="true"/>
<node name="plankton_global_sim_time"
pkg="plankton_utils"
exec="plankton_global_sim_time"
output="screen">
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
<include file="$(find-pkg-share gazebo_ros)/launch/gazebo.launch.py">
<arg name="world" value="worlds/pspb_2025_red_lowlight.world"/> <!-- HERE -->
<arg name="pause" value="$(var paused)"/>
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="gui" value="$(var gui)"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
<arg name="verbose" value="true" />
<!-- TODO Remove force_system in foxy, as it will be loaded by default -->
<arg name="extra_gazebo_args" value="-s libgazebo_ros_force_system.so --ros-args -r gazebo:__ns:=/gazebo"/>
</include>
<include file="$(find-pkg-share uuv_assistants)/launch/publish_world_ned_frame.launch">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
</include>
<node name="publish_world_models"
pkg="uuv_assistants"
exec="publish_world_models.py"
output="screen">
<param from="$(find-pkg-share smtupool)/config/empty_pool.yaml"/>
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
</launch>
<launch>
<arg name="paused" default="false"/>
<arg name="gui" default="true"/>
<arg name="use_sim_time" default="true"/>
<node name="plankton_global_sim_time"
pkg="plankton_utils"
exec="plankton_global_sim_time"
output="screen">
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
<include file="$(find-pkg-share gazebo_ros)/launch/gazebo.launch.py">
<arg name="world" value="worlds/pspb_2025_test_lowlight.world"/> <!-- HERE -->
<arg name="pause" value="$(var paused)"/>
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="gui" value="$(var gui)"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
<arg name="verbose" value="true" />
<!-- TODO Remove force_system in foxy, as it will be loaded by default -->
<arg name="extra_gazebo_args" value="-s libgazebo_ros_force_system.so --ros-args -r gazebo:__ns:=/gazebo"/>
</include>
<include file="$(find-pkg-share uuv_assistants)/launch/publish_world_ned_frame.launch">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
</include>
<node name="publish_world_models"
pkg="uuv_assistants"
exec="publish_world_models.py"
output="screen">
<param from="$(find-pkg-share smtupool)/config/empty_pool.yaml"/>
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
</launch>
<launch>
<arg name="paused" default="false"/>
<arg name="gui" default="true"/>
<arg name="use_sim_time" default="true"/>
<node name="plankton_global_sim_time"
pkg="plankton_utils"
exec="plankton_global_sim_time"
output="screen">
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
<include file="$(find-pkg-share gazebo_ros)/launch/gazebo.launch.py">
<arg name="world" value="worlds/pspb_2025_yellow_lowlight.world"/> <!-- HERE -->
<arg name="pause" value="$(var paused)"/>
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="gui" value="$(var gui)"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
<arg name="verbose" value="true" />
<!-- TODO Remove force_system in foxy, as it will be loaded by default -->
<arg name="extra_gazebo_args" value="-s libgazebo_ros_force_system.so --ros-args -r gazebo:__ns:=/gazebo"/>
</include>
<include file="$(find-pkg-share uuv_assistants)/launch/publish_world_ned_frame.launch">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
</include>
<node name="publish_world_models"
pkg="uuv_assistants"
exec="publish_world_models.py"
output="screen">
<param from="$(find-pkg-share smtupool)/config/empty_pool.yaml"/>
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
</launch>
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="pool">
<physics name="default_physics" default="true" type="ode">
<max_step_size>0.01</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>100</real_time_update_rate>
<ode>
<solver>
<type>quick</type>
<iters>50</iters>
<sor>1.2</sor>
</solver>
</ode>
</physics>
<scene>
<ambient>0.1 0.1 0.1 1.0</ambient>
<sky>
<clouds>
<speed>12</speed>
</clouds>
</sky>
<shadows>true</shadows>
<background>0.1 0.1 0.1 1</background>
</scene>
<!-- Origin of SPb -->
<spherical_coordinates>
<latitude_deg>59.9343</latitude_deg>
<longitude_deg>30.3351</longitude_deg>
</spherical_coordinates>
<!-- Global light source -->
<light type="directional" name="sun_diffuse_30">
<pose>-8 -0 10 0 0 0</pose>
<direction>-0.5 0.5 -1</direction>
</light>
<light type="directional" name="sun_diffuse_50">
<pose>-9 5 10 0 1.531698 0</pose>
<direction>-0.5 -0.5 -1</direction>
</light>
<light type="directional" name="sun_diffuse_100">
<pose>22 5 2 0 0 0</pose>
<direction>0 -1 0</direction>
</light>
<light type="directional" name="sun_diffuse_200">
<pose>0.5 9.5 2 0 0 0</pose>
<direction>1 0.3 0</direction>
</light>
<!-- pool model -->
<include>
<uri>model://smtu_pool</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- other model example -->
<include>
<uri>model://pspb_2025/environment/example</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- namespace-->
<plugin name="gazebo_ros" filename="libgazebo_ros_state.so">
<ros>
<namespace>/gazebo</namespace>
</ros>
</plugin>
<plugin name="underwater_current_plugin" filename="libuuv_underwater_current_ros_plugin.so">
<namespace>hydrodynamics</namespace>
<constant_current>
<topic>current_velocity</topic>
<velocity>
<!-- current speed -->
<mean>0</mean>
<min>0</min>
<max>5</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</velocity>
<horizontal_angle>
<!-- current angle -->
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</horizontal_angle>
<vertical_angle>
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</vertical_angle>
</constant_current>
</plugin>
<plugin name="sc_interface" filename="libuuv_sc_ros_interface_plugin.so"/>
<gui fullscreen='0'>
<camera name='user_camera'>
<!-- x y z roll pitch yaw (m/rad) 1.570795 3.14159 -->
<pose frame=''>22 27 14 0 0.57 -1.918</pose>
<!-- orbit/fps -->
<view_controller>fps</view_controller>
<projection_type>perspective</projection_type>
<!-- привязка камеры к визуальному объекту -->
<!--
<track_visual>
<name>ws02::ws02/base_link</name>
<min_dist>1.0</min_dist>
<max_dist>1000.0</max_dist>
</track_visual>
-->
<!-- сохранять ли состояние камеры между запусками -->
</camera>
</gui>
</world>
</sdf>
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="pool">
<physics name="default_physics" default="true" type="ode">
<max_step_size>0.01</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>100</real_time_update_rate>
<ode>
<solver>
<type>quick</type>
<iters>50</iters>
<sor>1.2</sor>
</solver>
</ode>
</physics>
<scene>
<ambient>0.1 0.1 0.1 1.0</ambient>
<sky>
<clouds>
<speed>12</speed>
</clouds>
</sky>
<shadows>true</shadows>
<background>0.1 0.1 0.1 1</background>
</scene>
<!-- Origin of SPb -->
<spherical_coordinates>
<latitude_deg>59.9343</latitude_deg>
<longitude_deg>30.3351</longitude_deg>
</spherical_coordinates>
<!-- Global light source -->
<light type="directional" name="sun_diffuse_30">
<pose>-8 -0 10 0 0 0</pose>
<direction>-0.5 0.5 -1</direction>
</light>
<light type="directional" name="sun_diffuse_50">
<pose>-9 5 10 0 1.531698 0</pose>
<direction>-0.5 -0.5 -1</direction>
</light>
<light type="directional" name="sun_diffuse_100">
<pose>22 5 2 0 0 0</pose>
<direction>0 -1 0</direction>
</light>
<light type="directional" name="sun_diffuse_200">
<pose>0.5 9.5 2 0 0 0</pose>
<direction>1 0.3 0</direction>
</light>
<!-- pool model -->
<include>
<uri>model://smtu_pool</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- other model example -->
<include>
<uri>model://pspb_2025/environment/green_square</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- namespace-->
<plugin name="gazebo_ros" filename="libgazebo_ros_state.so">
<ros>
<namespace>/gazebo</namespace>
</ros>
</plugin>
<plugin name="underwater_current_plugin" filename="libuuv_underwater_current_ros_plugin.so">
<namespace>hydrodynamics</namespace>
<constant_current>
<topic>current_velocity</topic>
<velocity>
<!-- current speed -->
<mean>0</mean>
<min>0</min>
<max>5</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</velocity>
<horizontal_angle>
<!-- current angle -->
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</horizontal_angle>
<vertical_angle>
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</vertical_angle>
</constant_current>
</plugin>
<plugin name="sc_interface" filename="libuuv_sc_ros_interface_plugin.so"/>
<gui fullscreen='0'>
<camera name='user_camera'>
<!-- x y z roll pitch yaw (m/rad) 1.570795 3.14159 -->
<pose frame=''>22 27 14 0 0.57 -1.918</pose>
<!-- orbit/fps -->
<view_controller>fps</view_controller>
<projection_type>perspective</projection_type>
<!-- привязка камеры к визуальному объекту -->
<!--
<track_visual>
<name>ws02::ws02/base_link</name>
<min_dist>1.0</min_dist>
<max_dist>1000.0</max_dist>
</track_visual>
-->
<!-- сохранять ли состояние камеры между запусками -->
</camera>
</gui>
</world>
</sdf>
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="pool">
<physics name="default_physics" default="true" type="ode">
<max_step_size>0.01</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>100</real_time_update_rate>
<ode>
<solver>
<type>quick</type>
<iters>50</iters>
<sor>1.2</sor>
</solver>
</ode>
</physics>
<scene>
<ambient>0.1 0.1 0.1 1.0</ambient>
<sky>
<clouds>
<speed>12</speed>
</clouds>
</sky>
<shadows>true</shadows>
<background>0.1 0.1 0.1 1</background>
</scene>
<!-- Origin of SPb -->
<spherical_coordinates>
<latitude_deg>59.9343</latitude_deg>
<longitude_deg>30.3351</longitude_deg>
</spherical_coordinates>
<!-- Global light source -->
<light type="directional" name="sun_diffuse_30">
<pose>-8 -0 10 0 0 0</pose>
<direction>-0.5 0.5 -1</direction>
</light>
<light type="directional" name="sun_diffuse_50">
<pose>-9 5 10 0 1.531698 0</pose>
<direction>-0.5 -0.5 -1</direction>
</light>
<light type="directional" name="sun_diffuse_100">
<pose>22 5 2 0 0 0</pose>
<direction>0 -1 0</direction>
</light>
<light type="directional" name="sun_diffuse_200">
<pose>0.5 9.5 2 0 0 0</pose>
<direction>1 0.3 0</direction>
</light>
<!-- pool model -->
<include>
<uri>model://smtu_pool</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- other model example -->
<include>
<uri>model://pspb_2025/environment/red_triangle</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- namespace-->
<plugin name="gazebo_ros" filename="libgazebo_ros_state.so">
<ros>
<namespace>/gazebo</namespace>
</ros>
</plugin>
<plugin name="underwater_current_plugin" filename="libuuv_underwater_current_ros_plugin.so">
<namespace>hydrodynamics</namespace>
<constant_current>
<topic>current_velocity</topic>
<velocity>
<!-- current speed -->
<mean>0</mean>
<min>0</min>
<max>5</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</velocity>
<horizontal_angle>
<!-- current angle -->
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</horizontal_angle>
<vertical_angle>
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</vertical_angle>
</constant_current>
</plugin>
<plugin name="sc_interface" filename="libuuv_sc_ros_interface_plugin.so"/>
<gui fullscreen='0'>
<camera name='user_camera'>
<!-- x y z roll pitch yaw (m/rad) 1.570795 3.14159 -->
<pose frame=''>22 27 14 0 0.57 -1.918</pose>
<!-- orbit/fps -->
<view_controller>fps</view_controller>
<projection_type>perspective</projection_type>
<!-- привязка камеры к визуальному объекту -->
<!--
<track_visual>
<name>ws02::ws02/base_link</name>
<min_dist>1.0</min_dist>
<max_dist>1000.0</max_dist>
</track_visual>
-->
<!-- сохранять ли состояние камеры между запусками -->
</camera>
</gui>
</world>
</sdf>
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="pool">
<physics name="default_physics" default="true" type="ode">
<max_step_size>0.01</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>100</real_time_update_rate>
<ode>
<solver>
<type>quick</type>
<iters>50</iters>
<sor>1.2</sor>
</solver>
</ode>
</physics>
<scene>
<ambient>0.1 0.1 0.1 1.0</ambient>
<sky>
<clouds>
<speed>12</speed>
</clouds>
</sky>
<shadows>true</shadows>
<background>0.1 0.1 0.1 1</background>
</scene>
<!-- Origin of SPb -->
<spherical_coordinates>
<latitude_deg>59.9343</latitude_deg>
<longitude_deg>30.3351</longitude_deg>
</spherical_coordinates>
<!-- Global light source -->
<light type="directional" name="sun_diffuse_30">
<pose>-8 -0 10 0 0 0</pose>
<direction>-0.5 0.5 -1</direction>
</light>
<light type="directional" name="sun_diffuse_50">
<pose>-9 5 10 0 1.531698 0</pose>
<direction>-0.5 -0.5 -1</direction>
</light>
<light type="directional" name="sun_diffuse_100">
<pose>22 5 2 0 0 0</pose>
<direction>0 -1 0</direction>
</light>
<light type="directional" name="sun_diffuse_200">
<pose>0.5 9.5 2 0 0 0</pose>
<direction>1 0.3 0</direction>
</light>
<!-- pool model -->
<include>
<uri>model://smtu_pool</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- other model example -->
<include>
<uri>model://pspb_2025/environment/test</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- namespace-->
<plugin name="gazebo_ros" filename="libgazebo_ros_state.so">
<ros>
<namespace>/gazebo</namespace>
</ros>
</plugin>
<plugin name="underwater_current_plugin" filename="libuuv_underwater_current_ros_plugin.so">
<namespace>hydrodynamics</namespace>
<constant_current>
<topic>current_velocity</topic>
<velocity>
<!-- current speed -->
<mean>0</mean>
<min>0</min>
<max>5</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</velocity>
<horizontal_angle>
<!-- current angle -->
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</horizontal_angle>
<vertical_angle>
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</vertical_angle>
</constant_current>
</plugin>
<plugin name="sc_interface" filename="libuuv_sc_ros_interface_plugin.so"/>
<gui fullscreen='0'>
<camera name='user_camera'>
<!-- x y z roll pitch yaw (m/rad) 1.570795 3.14159 -->
<pose frame=''>22 27 14 0 0.57 -1.918</pose>
<!-- orbit/fps -->
<view_controller>fps</view_controller>
<projection_type>perspective</projection_type>
<!-- привязка камеры к визуальному объекту -->
<!--
<track_visual>
<name>ws02::ws02/base_link</name>
<min_dist>1.0</min_dist>
<max_dist>1000.0</max_dist>
</track_visual>
-->
<!-- сохранять ли состояние камеры между запусками -->
</camera>
</gui>
</world>
</sdf>
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="pool">
<physics name="default_physics" default="true" type="ode">
<max_step_size>0.01</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>100</real_time_update_rate>
<ode>
<solver>
<type>quick</type>
<iters>50</iters>
<sor>1.2</sor>
</solver>
</ode>
</physics>
<scene>
<ambient>0.1 0.1 0.1 1.0</ambient>
<sky>
<clouds>
<speed>12</speed>
</clouds>
</sky>
<shadows>true</shadows>
<background>0.1 0.1 0.1 1</background>
</scene>
<!-- Origin of SPb -->
<spherical_coordinates>
<latitude_deg>59.9343</latitude_deg>
<longitude_deg>30.3351</longitude_deg>
</spherical_coordinates>
<!-- Global light source -->
<light type="directional" name="sun_diffuse_30">
<pose>-8 -0 10 0 0 0</pose>
<direction>-0.5 0.5 -1</direction>
</light>
<light type="directional" name="sun_diffuse_50">
<pose>-9 5 10 0 1.531698 0</pose>
<direction>-0.5 -0.5 -1</direction>
</light>
<light type="directional" name="sun_diffuse_100">
<pose>22 5 2 0 0 0</pose>
<direction>0 -1 0</direction>
</light>
<light type="directional" name="sun_diffuse_200">
<pose>0.5 9.5 2 0 0 0</pose>
<direction>1 0.3 0</direction>
</light>
<!-- pool model -->
<include>
<uri>model://smtu_pool</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- other model example -->
<include>
<uri>model://pspb_2025/environment/yellow_circle</uri>
<pose>0 0 0 0 0 0</pose>
</include>
<!-- namespace-->
<plugin name="gazebo_ros" filename="libgazebo_ros_state.so">
<ros>
<namespace>/gazebo</namespace>
</ros>
</plugin>
<plugin name="underwater_current_plugin" filename="libuuv_underwater_current_ros_plugin.so">
<namespace>hydrodynamics</namespace>
<constant_current>
<topic>current_velocity</topic>
<velocity>
<!-- current speed -->
<mean>0</mean>
<min>0</min>
<max>5</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</velocity>
<horizontal_angle>
<!-- current angle -->
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</horizontal_angle>
<vertical_angle>
<mean>0</mean>
<min>-3.141592653589793238</min>
<max>3.141592653589793238</max>
<mu>0.0</mu>
<noiseAmp>0.0</noiseAmp>
</vertical_angle>
</constant_current>
</plugin>
<plugin name="sc_interface" filename="libuuv_sc_ros_interface_plugin.so"/>
<gui fullscreen='0'>
<camera name='user_camera'>
<!-- x y z roll pitch yaw (m/rad) 1.570795 3.14159 -->
<pose frame=''>22 27 14 0 0.57 -1.918</pose>
<!-- orbit/fps -->
<view_controller>fps</view_controller>
<projection_type>perspective</projection_type>
<!-- привязка камеры к визуальному объекту -->
<!--
<track_visual>
<name>ws02::ws02/base_link</name>
<min_dist>1.0</min_dist>
<max_dist>1000.0</max_dist>
</track_visual>
-->
<!-- сохранять ли состояние камеры между запусками -->
</camera>
</gui>
</world>
</sdf>