Spawning a URDF model in Ignition Fortress fails
Dear community,
i am trying to spawn a URDF model inside Ignition Fortress. My minimal example URDF cyclinder_example.urdf models a cylinder:
<?xml version="1.0"?>
<robot name="my_first_robot">
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.6" radius="0.2"/>
</geometry>
</visual>
</link>
</robot>
and is executed inside a launch file:
[...]
<include file="$(find ros_ign_gazebo)/launch/ign_gazebo.launch">
<arg name="ign_args" value="$(arg ign_args) $(find my_pkg)/worlds/$(arg ign_world).sdf"/>
</include>
<node pkg="ros_ign_gazebo" type="create" name="$(anon ros_ign_create_cylinder)" output="$(arg output)"
args="-world $(arg ign_world) -file $(arg model) -name spawned -x $(arg pos_x) -y $(arg pos_y) -z $(arg pos_z)">
</node>
[...]
Then, i obtain the following error:
[Err] [UserCommands.cc:1184] Error Code 16: Msg: A model must have at least one link.
[Err] [UserCommands.cc:1184] Error Code 16: Msg: A model must have at least one link.
[Err] [UserCommands.cc:1184] Error Code 24: Msg: FrameAttachedToGraph error: scope context name[] does not match __model__ or world.
Most probably, this seems to be caused by a wrong conversion from URDF to SDF error-referenced function, see UserCommands.cc#1184:
bool CreateCommand::Execute()
{
auto createMsg = dynamic_cast<const msgs::EntityFactory *>(this->msg);
if (nullptr == createMsg)
{
ignerr << "Internal error, null create message" << std::endl;
return false;
}
// Load SDF
sdf::Root root;
sdf::Light lightSdf;
sdf::Errors errors;
switch (createMsg->from_case())
{
case msgs::EntityFactory::kSdf:
{
errors = root.LoadSdfString(createMsg->sdf());
break;
}
[...]
Any ideas how this could be solved?
Asked by Illuminatur on 2022-04-30 08:09:27 UTC
Comments
Can you try adding a mass to the link? The URDF->SDFormat conversion removes links without masses.
Asked by azeey on 2022-04-30 12:26:35 UTC