How to declare child link for joint when link is in embedded model
I am building a model with a base mesh and three copies of an omniwheel model (Omniwheel model from:GuiRitter OpenBase) that has a 'rim_link' for attaching to a base mesh/link joint. When importing the whole robot model gazebo throws the following four(4) errors per joint/wheel:
[Err] [World.cc:201] Error Code 23 Msg: FrameAttachedToGraph error, Non-LINK vertex with name [leftMotorJoint] is disconnected; it should have 1 outgoing edge in MODEL attached_to graph.
[Err] [World.cc:201] Error Code 23 Msg: Graph has __model__ scope but sink vertex named [leftMotorJoint] does not have FrameType LINK OR MODEL when starting from vertex with name [leftMotorJoint].
[Err] [World.cc:201] Error Code 26 Msg: PoseRelativeToGraph error, Vertex with name [leftMotorJoint] is disconnected; it should have 1 incoming edge in MODEL relative_to graph.
[Err] [World.cc:201] Error Code 26 Msg: PoseRelativeToGraph frame with name [leftMotorJoint] is disconnected; its source vertex has name [leftMotorJoint], but its source name should be __model__.
High level view of model.sdf is:
<sdf version='1.7'>
<model name='myRobot'>
<link name 'myRobotLink'>
<inertial> [entries] </inertial>
<visual> [entries] </visual>
<collision> [entries] </collision>
</link>
<model name='leftOmniWheelModel'>
<link name='omniwheelrimlink'>
[entries for link including initial block]
</link>
[omniWheelModel entries including other links/joints detailing omniwheel]
</model>
<joint name='leftMotorJoint' type='revolute'>
<parent>myRobotLink</parent>
<child>leftOmniWheelModel::omniwheelrimlink</child>
[rest of joint statements]
</joint>
</model>
</sdf>
gz sdf --check model.sdf returns 'check complete'
ign sdf --check model.sdf returns 6 errors
Error: Child link with name[leftOmniWheelModel::omni_wheel_rim_link] specified by joint with name[leftMotorJoint] not found in model with name[myRobot].
Error: FrameAttachedToGraph error, Non-LINK vertex with name [leftMotorJoint] is disconnected; it should have 1 outgoing edge in MODEL attached_to graph.
Error: Graph has __model__ scope but sink vertex named [leftMotorJoint] does not have FrameType LINK OR MODEL when starting from vertex with name [leftMotorJoint].
Error: Child link with name[leftOmniWheelModel::omni_wheel_rim_link] specified by joint with name[leftMotorJoint] not found in model with name[myRobot].
Error: PoseRelativeToGraph error, Vertex with name [leftMotorJoint] is disconnected; it should have 1 incoming edge in MODEL relative_to graph.
Error: PoseRelativeToGraph frame with name [leftMotorJoint] is disconnected; its source vertex has name [leftMotorJoint], but its source name should be __model__.
Searching other questions/errors about the gazebo errors always say to add inertial blocks to the links but all the links have their initial blocks defined. What else do I need to check? Following tutorials I have defined the sub-models, joints, and child-links correctly so unsure what is going on to produce these errors.
Asked by MadRoboticist on 2021-04-30 12:42:57 UTC
Comments
What version of Gazebo are you using? Also, can you attach the model file so it's easy to reproduce?
Asked by azeey on 2021-08-05 12:31:14 UTC