@@ -923,6 +923,8 @@ def isRootLink(link, childList):
923
923
924
924
def parseGazeboElement (element , parentLink , linkList ):
925
925
"""Parse a Gazebo element."""
926
+ if element .hasAttribute ("reference" ) and any ([link .name == element .getAttribute ('reference' ) for link in linkList ]):
927
+ parentLink = element .getAttribute ("reference" )
926
928
for plugin in element .getElementsByTagName ('plugin' ):
927
929
if plugin .hasAttribute ('filename' ) and plugin .getAttribute ('filename' ).startswith ('libgazebo_ros_imu' ):
928
930
imu = IMU ()
@@ -937,8 +939,6 @@ def parseGazeboElement(element, parentLink, linkList):
937
939
if sensorElement .getAttribute ('type' ) == 'camera' :
938
940
camera = Camera ()
939
941
camera .parentLink = parentLink
940
- if element .hasAttribute ('reference' ) and element .getAttribute ('reference' ) in linkList :
941
- camera .parentLink = element .getAttribute ('reference' )
942
942
camera .name = sensorElement .getAttribute ('name' )
943
943
if hasElement (sensorElement , 'camera' ):
944
944
cameraElement = sensorElement .getElementsByTagName ('camera' )[0 ]
@@ -962,8 +962,6 @@ def parseGazeboElement(element, parentLink, linkList):
962
962
elif sensorElement .getAttribute ('type' ) == 'ray' :
963
963
lidar = Lidar ()
964
964
lidar .parentLink = parentLink
965
- if element .hasAttribute ('reference' ) and element .getAttribute ('reference' ) in linkList :
966
- lidar .parentLink = element .getAttribute ('reference' )
967
965
lidar .name = sensorElement .getAttribute ('name' )
968
966
if hasElement (sensorElement , 'ray' ):
969
967
rayElement = sensorElement .getElementsByTagName ('ray' )[0 ]
0 commit comments