Gazebo hangs on a blank screen while trying to load a simple model, but other downloaded models work

asked 2019-01-21 11:43:44 -0500

Robot00 gravatar image

I am new to ros and Gazebo, but I have been working on this one problem for a while now. Other team models load launch fine, as well as the tutorial one, but my model just won't load with the gazebo file. The urdf loads fine when <xacro:include filename="$(find bigrdigr_description)/urdf/bigrdigr.gazebo.xacro"/> is commented out. This is my gazebo file

<?xml version="1.0"?>

<robot name="bigrdigr" xmlns:xacro="https://www.ros.org/wiki/xacro"> <xacro:property name="imu_visual" value="false"/> <xacro:property name="pseye_FOV" value="1.309"/>

<gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <robotNamespace>/</robotNamespace>
    </plugin>
</gazebo>

<gazebo reference="world_origin">
    <turnGravityOff>false</turnGravityOff>
</gazebo>

<gazebo reference="base_link">
    <material>Gazebo/DarkGrey</material>
    <turnGravityOff>false</turnGravityOff>
</gazebo>

<gazebo reference="front_left_wheel">
    <mu1>0.3</mu1>
    <mu2>0.3</mu2>
    <kp>1000000.0</kp>
    <kd>1.0</kd>
    <minDepth>0.001</minDepth>
    <maxVel>1</maxVel>
    <fdir1>1 0 0</fdir1>
    <material>Gazebo/FlatBlack</material>
</gazebo>

<gazebo reference="front_right_wheel">
    <mu1>0.3</mu1>
    <mu2>0.3</mu2>
    <kp>1000000.0</kp>
    <kd>1.0</kd>
    <minDepth>0.001</minDepth>
    <maxVel>1</maxVel>
    <fdir1>1 0 0</fdir1>
    <material>Gazebo/FlatBlack</material>
</gazebo>

<gazebo reference="back_left_wheel">
    <mu1>0.3</mu1>
    <mu2>0.3</mu2>
    <kp>1000000.0</kp>
    <kd>1.0</kd>
    <minDepth>0.001</minDepth>
    <maxVel>1</maxVel>
    <fdir1>1 0 0</fdir1>
    <material>Gazebo/FlatBlack</material>
</gazebo>

<gazebo reference="back_right_wheel">
    <mu1>0.3</mu1>
    <mu2>0.3</mu2>
    <kp>1000000.0</kp>
    <kd>1.0</kd>
    <minDepth>0.001</minDepth>
    <maxVel>1</maxVel>
    <fdir1>1 0 0</fdir1>
    <material>Gazebo/FlatBlack</material>
</gazebo>

<gazebo reference="pseye_camera1">
    <material>Gazebo/Red</material>
    <sensor type="camera" name="cam1">
        <update_rate>120</update_rate> <!--fps? -->
        <camera name="front_left">
            <horizontal_fov>${pseye_FOV}</horizontal_fov>
            <image>
                <width>320</width>
                <height>240</height>
                <format>R8G8B8</format>
            </image>
            <clip> <!--distance (m) limits on where a camera can see an object need to find -->
                <near>0.02</near>
                <far>300</far>
            </clip>
            <noise>
                <type>gaussian</type>
                <mean>0.0</mean>
                <stddev>0.007</stddev>
            </noise>
        </camera>
        <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
            <alwaysOn>true</alwaysOn>
            <!--Nodes-->
            <updateRate>0.0</updateRate>
            <cameraName>camera/pseye_camera1</cameraName>
            <imageTopicName>image_raw</imageTopicName>
            <cameraInfoTopicName>camera_info</cameraInfoTopicName>
            <frameName>pseye_camera1</frameName>
            <!--May need to find? -->
            <hackBaseline>0.07</hackBaseline>
            <distortionK1>0.0</distortionK1>
            <distortionK2>0.0</distortionK2>
            <distortionK3>0.0</distortionK3>
            <distortionT1>0.0</distortionT1>
            <distortionT2>0.0</distortionT2>
        </plugin>
    </sensor>
</gazebo>

<gazebo reference="pseye_camera2">
    <material>Gazebo/Red</material>
    <sensor type="camera" name="cam2">
        <update_rate>120</update_rate> <!--fps? -->
        <camera name="front_left">
            <horizontal_fov>${pseye_FOV}</horizontal_fov>
            <image>
                <width>320</width>
                <height>240</height>
                <format>R8G8B8</format>
            </image>
            <clip> <!--distance (m) limits on where a camera can see an object need to find -->
                <near>0.02</near>
                <far>300</far>
            </clip>
            <noise>
                <type>gaussian</type>
                <mean>0.0</mean>
                <stddev>0.007</stddev>
            </noise>
        </camera>
        <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
            <alwaysOn>true</alwaysOn>
            <!--Nodes-->
            <updateRate>0.0</updateRate>
            <cameraName>camera/pseye_camera2</cameraName>
            <imageTopicName>image_raw</imageTopicName>
            <cameraInfoTopicName>camera_info</cameraInfoTopicName>
            <frameName>pseye_camera2</frameName>
            <!--May need to find? -->
            <hackBaseline>0.07</hackBaseline>
            <distortionK1 ...
(more)
edit retag flag offensive close merge delete

Comments

I would think that nothing is "hanging", but your xacro simply doesn't contain anything that Gazebo can use.

<gazebo reference="world_origin">

Those are only references, they don't define any links. So your xacro appears to be essentially empty.

gvdhoorn gravatar image gvdhoorn  ( 2019-01-21 14:20:07 -0500 )edit