Why isn't my URDF able to show sensor in rviz, but does show in Gazebo11?
Hi everyone,
TL;DR
How to load ultrasonic in rviz/gazebo11 using Foxy? How to place the robot on the floor properly without flip it in Gazebo11 or crash it in rviz? UDRF code is at bottom.
Full post
I fail to see why can't I load sensor in rviz. I'm using Ros2 Foxy, rviz2, and gazebo11.
So, my ultrasonic sensor should be on joint called ultrasonic. It's attached with one link cylinder called head2 and the board link called sensor.
Somehow, the topic isn't appear on rviz.
Here is the screenshot:
So basically, my URDF look like this:
<?xml version="1.0"?>
<robot name="my_robot" xmlns:xacro="http://ros.org/wiki/xacro">
<!--INCLUDE FILES-->
<!-- <xacro:include filename="$(find description)/my_robot.gazebo" />-->
<!-- Define robot constants -->
<xacro:property name="base_width" value="0.2159"/>
<xacro:property name="base_length" value="0.1524"/>
<xacro:property name="base_height" value="0.10795"/>
<xacro:property name="wheel_radius" value="0.0325"/>
<xacro:property name="wheel_width" value="0.02"/>
<xacro:property name="wheel_ygap" value="0.088"/>
<xacro:property name="wheel_zoff" value="0.05"/>
<xacro:property name="wheel_xoff" value="0.1"/>
<xacro:property name="caster_xoff" value="0.14"/>
<!-- Define some commonly used intertial properties -->
<xacro:macro name="box_inertia" params="m w h d">
<inertial>
<origin xyz="0 0 0" rpy="${pi/2} 0 ${pi/2}"/>
<mass value="${m}"/>
<inertia ixx="${(m/12) * (h*h + d*d)}" ixy="0.0" ixz="0.0" iyy="${(m/12) * (w*w + d*d)}" iyz="0.0" izz="${(m/12) * (w*w + h*h)}"/>
</inertial>
</xacro:macro>
<xacro:macro name="cylinder_inertia" params="m r h">
<inertial>
<origin xyz="0 0 0" rpy="${pi/2} 0 0" />
<mass value="${m}"/>
<inertia ixx="${(m/12) * (3*r*r + h*h)}" ixy = "0" ixz = "0" iyy="${(m/12) * (3*r*r + h*h)}" iyz = "0" izz="${(m/2) * (r*r)}"/>
</inertial>
</xacro:macro>
<!-- Robot Base -->
<link name="base_link">
<visual>
<geometry>
<box size="0.2159 0.1524 0.10795"/>
</geometry>
<material name="Cyan">
<color rgba="0 1.0 1.0 1.0"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.2159 0.1524 0.10795"/>
</geometry>
</collision>
<xacro:box_inertia m="15" w="0.2159" d="0.1524" h="0.10795"/>
</link>
<!-- Robot Footprint -->
<link name="base_footprint"/>
<joint name="base_joint" type="fixed">
<parent link="base_link"/>
<child link="base_footprint"/>
<origin xyz="0.0 0.0 ${-(wheel_radius+wheel_zoff)}" rpy="0 0 0"/>
</joint>
<!-- Servos -->
<link name ="head">
<visual>
<geometry>
<cylinder radius="0.01" length="0.02"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.01" length="0.02"/>
</geometry>
</collision>
<xacro:cylinder_inertia m="0.5" r="0.01" h="0.02"/>
< ...
I'm working on something similar and would like to know how you got the gazebo view in your Update #2. I can't find this anywhere.
Hey! Show me your launch file
@Darkproduct
This is under
return launch.LaunchDescription([
This will opens gazebo. To respawn your model in gazebo, use this one under
def generate_launch_description():
then add this under
return launch.LaunchDescription([
They are in my launch file above. Use the ctrl F to find them as well!
Please let me know if you encounter any issue with this
I can open Gazebo and spawn my model just fine. The only thing I can't find is this nice view where you can see and possibly modify the speed and the PID values in Gazebo.
Here, I made the picture for you. You click and hold then pull it to left :)
Thanks. I can't believe I never noticed this.
For you actual question: Launch gazebo in verbose mode with
--verbose
. This will help finding any problems with your configuration. I looked at your gazebo tag for the sensor link and it looks good. Look at the bottem launch file in Update 2 from my answer here to see an example on how to launch gazebo in verbose mode. https://answers.ros.org/question/3841...