Very slooooow simulation
I am trying to simulate a small UAV flying over a terrain, with a lidar (ray) sensor and a camera. I have been successful with a straight flight, but the simulation is very slow. The sensors have a rate of 10 Hz, but the images and lidar data are generated with several seconds 10-20 between frames. This is slow, but tolerable. When I try a banked turn, the simulation slows to a frame every 20-30 minutes. I am using the .sdf file and plugin below. The plugin was generated using a Matlab script to create the banked turn. The heightmap (mtn_height.jpg) is at a resolution of 2049x2049 pixels and the texture (texture_trimmed.png) is of resolution 3993x3992 pixels.
Why is this so slow? I realize this is a lot of computation, but I am amazed that the banked turn takes so much longer than the straight flight over the same terrain. Is there some way to speed this up? Am I using a very inefficient method?
I thought I read that the ray sensor could be sped up using a GPU. Is this available, and if so, how do I get and use it?
Thanks.
<sdf version="1.6"> <world name="animated_box_world"> <scene> <ambient>1.0 1.0 1.0 1</ambient> <background>0.5 0.5 0.5 1</background> <shadows>false</shadows> </scene> <physics name="default_physics" default="0" type="ode"> <real_time_update_rate>1000</real_time_update_rate> <max_step_size>0.0005</max_step_size> <real_time_factor>0.3</real_time_factor> </physics>
<model name="heightmap"> <static>true</static> <link name="height"> <collision name="collision"> <geometry> <heightmap> <uri>file://media/materials/textures/wasatch_calls_fort_canyon/mtn_height.jpg</uri> <size>1000 1000 530</size> <pos>0 0 100</pos> </heightmap> </geometry> </collision> <visual name="visual_abcedf"> <cast_shadows>false</cast_shadows> <geometry> <heightmap> <use_terrain_paging>false</use_terrain_paging> <texture> <diffuse>file://media/materials/textures/wasatch_calls_fort_canyon/texture_trimmed.png</diffuse> <normal>file://media/materials/textures/flat_normal.png</normal> <size>1000</size> </texture> <uri>file://media/materials/textures/wasatch_calls_fort_canyon/mtn_height.jpg</uri> <size>1000 1000 530</size> <pos>0 0 100</pos> </heightmap> </geometry> </visual> </link> </model>
<model name="texelcamera"> <link name="link"> <pose frame="">0 0 0 0 1.57079 0</pose> <inertial> <inertia> <ixx>1</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>1</iyy> <iyz>0</iyz> <izz>1</izz> </inertia> <mass>0.1</mass> <pose frame="">0 0 0 0 -0 0</pose> </inertial> <self_collide>0</self_collide> <kinematic>0</kinematic> <sensor name="camera" type="camera"> <pose frame="texsensor">0 0 0 0 0 0</pose> <camera name="__default__"> <horizontal_fov>0.35</horizontal_fov> <image> <width>1024</width> <height>350</height> <format>BGR_INT8</format> </image> <clip> <near>0.1</near> <far>2000</far> </clip> </camera> <always_on>true</always_on> <update_rate>10</update_rate> <visualize>true</visualize> </sensor> <sensor name="laser" type="ray"> <pose frame="texsensor">0 0 0 0 0 0</pose> <ray> <scan> <horizontal> <samples>210</samples> <resolution>1</resolution> <min_angle>-0.175</min_angle> <max_angle>0.175</max_angle> </horizontal> <vertical> <samples>1</samples> <min_angle>0</min_angle> <max_angle>0</max_angle> </vertical> </scan> <range> <min>0.08</min> <max>2000 ...
is it slow because of a low real time factor or low FPS? Real time factor: 1. increase max_step_size 2. Reduce ode <iters> from default 50 to something lower (sacrifices accuracy) FPS: 1. turn off camera visualization by setting <visualize> to false. 2. reduce heightmap resolution 3. reduce texture resolution
is it slow because of a low real time factor or low FPS? Real time factor: 1. increase max_step_size, 2. Reduce ode <iters> from default 50 to something lower (sacrifices accuracy). FPS: 1. turn off camera visualization by setting <visualize> to false, 2. reduce heightmap resolution, 3. reduce texture resolution.