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 degree of freedom -->
<limit upper="10000000000000000" lower="-10000000000000000" effort="0.1" velocity="10" />
<axis xyz="0 0 1"/>
</joint>
<gazebo reference="${namespace}/${suffix}_top_link">
<!-- Add a ray sensor, and give it a name -->
<sensor type="ray" name="sonar_${suffix}">
<!-- Position the ray sensor based on the specification. Also rotate
it by 90 degrees around the z-axis so that the <horizontal> rays
become vertical and point to x (which is rotating) -->
<pose>0 0 0 0 0 0</pose>
<!-- Enable visualization to see the rays in the GUI -->
<visualize>true</visualize>
<!-- Set the update period of the sensor
SLOW MEDIUM FAST FASTER FASTEST
(0.3deg) (0.6deg) (0.9deg) (1.2deg) (2.4deg)
20m 38.4 19.2 13.6 10.8 6.9
10m 21.6s 10.8s 8.0s 6.6s 4.8s
5m 14.4s 7.2s - - -
Rays 360/0.3 360/0.6 360/0.9 360/1.2 360/2.4
1200 600 400 300 150 leituras
Update rate for each point reading
SLOW MEDIUM FAST FASTER FASTEST
(0.3deg) (0.6deg) (0.9deg) (1.2deg) (2.4deg)
10m 55.5556Hz 55.56Hz 50.0Hz 45.4545Hz 31.2500Hz
-->
<always_on>true</always_on>
<update_rate>${update_rate}</update_rate>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<noise>
<!-- Use gaussian noise -->
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
<!-- Range defines characteristics of an individual beam -->
<range>
<!-- Minimum distance of the 881L beam -->
<min>${range_min}</min>
<!-- Maximum distance of the 881L beam: it depends on the operating range -->
<max>${range_max}</max>
<!-- Linear resolution of the beam -->
<resolution>0.05</resolution>
</range>
</ray>
<plugin name="${suffix}sonar_controller" filename="libgazebo_ros_laser.so">
<topicName>${topic}</topicName>
<frameName>${suffix}_top_link</frameName>
</plugin>
</sensor>
</gazebo>
<!--
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${namespace}/${suffix}_sensor_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/${namespace}</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>false</legacyModeNS>
</plugin>
</gazebo>
-->
<gazebo>
<plugin name="ps881L_control" filename="libpsonar_881L_plugin.so">
<velocity>${angular_speed}</velocity>
<topicName>${topic}/cmd_vel</topicName>
<joint_name>${namespace}::${namespace}/${suffix}_sensor_joint</joint_name>
</plugin>
</gazebo>
</xacro:macro>
Asked by Vitor AMJ on 2020-07-13 20:22:44 UTC
Comments