Cannot spawn my urdf file in gazebo
Hi! I want to spwn my own urdf file in gazebo, but it's been imposible. When I do the roslaunch this is the result:
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://fjnar-MateBook:36831/
SUMMARY
========
PARAMETERS
* /robot_description: <?xml version="1....
* /rosdistro: melodic
* /rosversion: 1.14.12
NODES
/
mybot_spawn (gazebo_ros/spawn_model)
auto-starting new master
process[master]: started with pid [8679]
ROS_MASTER_URI=http://localhost:11311
setting /run_id to 93a8e546-3d9e-11ec-b396-f85971503f0c
process[rosout-1]: started with pid [8715]
started core service [/rosout]
process[mybot_spawn-2]: started with pid [8728]
SpawnModel script started
No handlers could be found for logger "rosout"
[mybot_spawn-2] process has finished cleanly
log file: /home/fjnar/.ros/log/93a8e546-3d9e-11ec-b396-f85971503f0c/mybot_spawn-2*.lo
g
This is my spawn.launch file:
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<param name="robot_description" command="cat '$(find accesrobot_simulation)/urdf/aspayn_room.urdf'" />
<node name="mybot_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
args="-udf -param robot_description -model aspayn_room"/>
</launch>
And this is my urdf file:
<?xml version="1.0" ?>
<robot name="aspayn_closet_room">
<joint name="aspayn_closet_room__link_1_JOINT_2" type="fixed">
<parent link="aspayn_closet_room__link_1"/>
<child link="aspayn_closet_room__link_2"/>
<origin rpy="0 0 0" xyz="0.47903 0.11441 0.01"/>
<axis xyz="0 0 0"/>
<limit effort="0" lower="0" upper="0" velocity="0"/>
</joint>
<joint name="aspayn_closet_room__link_2_JOINT_3" type="prismatic">
<parent link="aspayn_closet_room__link_2"/>
<child link="aspayn_closet_room__link_3"/>
<origin rpy="0 0 0" xyz="0.03 0 0.005"/>
<axis xyz="0 1 0"/>
<limit effort="1.0" lower="0.0" upper="0.86" velocity="1.0"/>
</joint>
<joint name="aspayn_closet_room__link_2_JOINT_4" type="prismatic">
<parent link="aspayn_closet_room__link_2"/>
<child link="aspayn_closet_room__link_4"/>
<origin rpy="0 0 0" xyz="0.065 1.77 0.005"/>
<axis xyz="0 -1 0"/>
<limit effort="-1.0" lower="0.0" upper="0.73" velocity="-1.0"/>
</joint>
<link name="aspayn_closet_room__link_1">
<inertial>
<mass value="5000"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.166667" ixy="0" ixz="0" iyy="0.166667" iyz="0" izz="0.166667"/>
</inertial>
<collision name="aspayn_closet_room__collision">
<origin rpy="0 0 0" xyz="-2.49097 -1.19558 0"/>
<geometry>
<mesh filename="package://PATHTOMESHES/tiago_public_ws/src/accesrobot/accesrobot_simulation/aspayn_room/meshes/ASPAYN_room.dae" scale="1 1 1"/>
</geometry>
</collision>
<visual name="aspayn_closet_room__visual">
<origin rpy="0 0 0" xyz="-2.49097 -1.19558 0"/>
<geometry>
<mesh filename="package://PATHTOMESHES/tiago_public_ws/src/accesrobot/accesrobot_simulation/aspayn_room/meshes/ASPAYN_room.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="aspayn_closet_room__link_2">
<inertial>
<mass value="3"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.166667" ixy="0" ixz="0" iyy="0.166667" iyz="0" izz="0.166667"/>
</inertial>
<collision name="aspayn_closet_room__collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://PATHTOMESHES/tiago_public_ws/src/accesrobot/accesrobot_simulation/aspayn_room/meshes/guides.dae" scale="1 1 1"/>
</geometry>
</collision>
<visual name="aspayn_closet_room__visual">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://PATHTOMESHES/tiago_public_ws/src/accesrobot/accesrobot_simulation/aspayn_room/meshes/guides.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="aspayn_closet_room__link_3">
<inertial>
<mass value="2"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.166667" ixy="0" ixz="0" iyy="0.166667" iyz="0" izz="0.166667"/>
</inertial>
<collision name="aspayn_closet_room__collision">
<origin rpy="0 0 0" xyz="-0.015 0 0"/>
<geometry>
<mesh filename="package://PATHTOMESHES/tiago_public_ws/src/accesrobot/accesrobot_simulation/aspayn_room/meshes/left_door.dae" scale="1 1 1"/>
</geometry>
</collision>
<visual name="aspayn_closet_room__visual">
<origin rpy="0 0 0" xyz="-0.015 0 0"/>
<geometry>
<mesh filename="package://PATHTOMESHES/tiago_public_ws/src/accesrobot/accesrobot_simulation/aspayn_room/meshes/left_door.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<link name="aspayn_closet_room__link_4">
<inertial>
<mass value="2"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.166667" ixy="0" ixz="0" iyy="0.166667" iyz="0" izz="0.166667"/>
</inertial>
<collision name="aspayn_closet_room__collision">
<origin rpy="0 0 0" xyz="-0.015 -0.885 0"/>
<geometry>
<mesh filename="package://PATHTOMESHES/tiago_public_ws/src/accesrobot/accesrobot_simulation/aspayn_room/meshes/right_door.dae" scale="1 1 1"/>
</geometry>
</collision>
<visual name="aspayn_closet_room__visual">
<origin rpy="0 0 0" xyz="-0.015 -0.885 0"/>
<geometry>
<mesh filename="package://PATHTOMESHES/tiago_public_ws/src/accesrobot/accesrobot_simulation/aspayn_room/meshes/right_door.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
</robot>
Asked by FranJRO on 2021-11-04 14:22:51 UTC
Comments
The launch file you posted has
-udf
instead of-urdf
. Could that be the issue?Asked by azeey on 2021-11-10 17:20:23 UTC