What is the best way to simulate a single point spinning range finder sensor?
Hi Experts,
I am currently trying to implement a single point range finder over a spinning base. Here is my current needs: - update rate of 60Hz or less. - single point spinning (sonar or laser, doesn't matter at first)
I can: 1. create a spinning sensor with a single point both with controller manager or custom gazebo plugin. 2. control the angular rotation speed, accurately. 3. generate and read points (even though I am limited to <30Hz no matter what I do)
Still, no matter what I do I keep stuck at 30Hz: a. Tried Gazebo 7 and 9... no success b. Slowing down the simulation seems to have no effect at the 30Hz update rate, and it would suck to make it run at a ratio of full speed. c. gpu_ray is not supported for what I am doing for some reason, even though I am not sure the frame rate would rise for single point. Moreover, it seems to be impossible to make it work anyways (currently using NVidia Geforce GTX1060 -- app hangs).
Is there any way I can increase the number of points per second? Should I use a different setup?
Thanks,
For those that will ask for it, here is my xacro/gazebo stuff...
<!-- Macro description for the 881L sonar -->
<xacro:macro name="spinning_profiling_sonar_881L" params="namespace parent_link update_rate range_max angular_speed *origin">
<xacro:mech_sonar
namespace="${namespace}"
suffix="881L"
parent_link="${parent_link}"
topic="/${namespace}/881L/sonar"
update_rate="${update_rate}"
samples="1"
range_min="0.5"
range_max="${range_max}"
angular_speed="${angular_speed}"
range_stddev="0.01">
<xacro:insert_block name="origin" />
</xacro:mech_sonar>
</xacro:macro>
<xacro:macro name="mech_sonar"
params="namespace suffix parent_link topic update_rate samples range_min range_max angular_speed range_stddev
*origin">
<!-- Sensor link -->
<!-- Give the base link a unique name -->
<link name="${namespace}/${suffix}_root_link">
<xacro:insert_block name="origin" />
<inertial>
<!-- Using Cylinder inertia equation from
https://en.wikipedia.org/wiki/List_of_moments_of_inertia
We are leaving 200g for the motor rotation part-->
<mass value="1.3"/>
<inertia ixx="0.0055276258" iyy="0.0055276258" izz="0.0011820675" ixy="0" ixz="0" iyz="0" />
</inertial>
<xacro:no_collision/>
<visual name="base_visual">
<geometry>
<mesh filename="package://vita_sensors/models/881L/meshes/881L.dae" />
</geometry>
</visual>
</link>
<link name="${namespace}/${suffix}_top_link">
<!-- Give the base link a unique name -->
<origin xyz="0 0 0" rpy="0 ${pi} ${pi}"/>
<inertial>
<mass value="0.2" />
<inertia ixx="0.000090623" iyy="0.000090623" izz="0.000091036" ixy="0" ixz="0" iyz="0" />
</inertial>
<xacro:no_collision/>
<visual>
<geometry>
<cylinder length="${0.000001}" radius="${0.000001}" />
</geometry>
</visual>
</link>
<joint name="${namespace}/${suffix}_fixed_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent_link}" />
<child link="${namespace}/${suffix}_root_link" />
</joint>
<!-- Each joint must have a unique name -->
<joint type="revolute" name="${namespace}/${suffix}_sensor_joint">
<!-- Position the joint at the bottom of the top link -->
<origin xyz="0 0 0.086" rpy="0 0 0" />
<!-- Use the base link as the parent of the joint -->
<parent link="${namespace}/${suffix}_root_link" />
<!-- Use the top link as the child of the joint -->
<child link="${namespace}/${suffix}_top_link"/>
<!-- The axis defines the joint's ...