Ray sensor not showing on urdf robot
Hello,
I don't know if this is the right place to post this question, but this issue is driving me crazy. I couldn't solve it myself and thought I could run it over with everyone here, see if someone had the same issue.
I have created a URDF model of my robot following gazebo tutorial. This robot has a Velodyne sensor at the front, the mesh is showing, and it is somehow rotating when I press play, the ray is not showing. I do not know if I have written something wrong because the sensor tag is showing on gazebo when I select the Velodyne link, but the ray is not showing at all. Is it normal? I have not connected to my ROS project yet, and I do not know how to check if I am getting data otherwise (first time using Gazebo).
This is the part of the URDF where the Velodyne is, it is inside
<link name="velodyne_base"> <origin xyz="0 0 0.029335" rpy="0 0 0" /> <inertial> <mass value="1.2" /> <inertia ixx="0.00108747" iyy="0.00108747" izz="0.00109244" ixy="0" ixz="0" iyz="0"/> </inertial> <collision name="base_collision"> <geometry> <cylinder radius="0.04267" length="0.029335" /> </geometry> </collision> <visual name="base_visual"> <pose frame="">0 0 -0.029335 0 -0 0</pose> <geometry> <mesh filename="model://mower_description/meshes/velodyne_base.dae" /> </geometry> </visual> </link> <link name="velodyne_top"> <origin xyz="0 0 0.095455" rpy="0 0 0" /> <inertial> <mass value="0.1" /> <inertia ixx="0.000090623" iyy="0.000090623" izz="0.000091036" ixy="0" ixz="0" iyz="0" /> </inertial> <collision name="top_collision"> <geometry> <cylinder radius="0.04267" length="0.07357" /> </geometry> </collision> <visual name="top_visual"> <geometry> <mesh filename="model://mower_description/meshes/velodyne_top.dae"/> </geometry> </visual> </link> <gazebo reference="velodyne_base"> <static>true</static> </gazebo> <gazebo reference="velodyne_top"> <sensor name="sensor" type="ray"> <pose frame=''>0 0 -0.004645 0 -0 0</pose> <update_rate>20</update_rate> <ray> <noise> <type>gaussian</type> <mean>0</mean> <stddev>0.1</stddev> </noise> <scan> <horizontal> <samples>96</samples> <resolution>1</resolution> <min_angle>-1.54898</min_angle> <max_angle>1.54898</max_angle> </horizontal> <vertical> <samples>8</samples> <resolution>1</resolution> <min_angle>-0.139626</min_angle> <max_angle>0.139626</max_angle> </vertical> </scan> <range> <min>0.1</min> <max>70</max> <resolution>0.02</resolution> </range> </ray> </sensor> </gazebo>
And this is the joint between the velodyne links
<joint name="velodyne_joint" type="revolute"> <parent link="velodyne_base" /> <child link="velodyne_top" /> <limit lower="-1e+16" upper="1e+16" effort="-1" velocity="-1" /> <origin xyz="0 0 0.05867" rpy="0 -0 0" /> <axis xyz="0 0 1" /> </joint>
The sensor tag on the code, I also tried just adding it by not using
Have anyone tried this before?
Asked by MichelleMouse on 2020-10-19 14:27:00 UTC
Answers
Hi, at the end ended up solving the issue by creating a master model and including my URDF and velodyne SDF files in it, then added a joint to fix them together.
<model name="mower_complete">
<include>
<uri>model://mower_description</uri>
<static>false</static>
<pose>0 0 0 0 0 0</pose>
</include>
<include>
<uri>model://mower_gazebo/models/velodyne</uri>
<pose>1.15 0 0.6 0 0 0</pose>
</include>
<joint type="fixed" name="sensor_to_mower_joint">
<pose>0 0 -0.036785 0 0 0</pose>
<parent>mower::chasis</parent>
<child>velodyne::velodyne_base</child>
</joint>
</model>
The Velodyne sensor ray is working now and the topic is being published. I do not know if this is the best practice or recommended, but it is working!
Please let me know if there is a better way to include this, as the gazebo tag did not work on Gazebo 9 Ros Medolic.
Asked by MichelleMouse on 2020-10-23 17:59:20 UTC
Comments