Skip to content

Commit

Permalink
Remove rospy usage (#129)
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass authored Oct 2, 2024
1 parent 4710753 commit 733e77d
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 21 deletions.
10 changes: 2 additions & 8 deletions scripts/display_srdf
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#!/usr/bin/env python

#!/usr/bin/env python3
from __future__ import print_function
import sys
import argparse
Expand All @@ -10,19 +9,14 @@ parser = argparse.ArgumentParser(usage="Load an SRDF file")
parser.add_argument(
"file",
type=argparse.FileType("r"),
nargs="?",
default=None,
help="File to load. Use - for stdin",
)
parser.add_argument(
"-o", "--output", type=argparse.FileType("w"), default=None, help="Dump file to XML"
)
args = parser.parse_args()

if args.file is None:
robot = SRDF.from_parameter_server()
else:
robot = SRDF.from_xml_string(args.file.read())
robot = SRDF.from_xml_string(args.file.read())

print(robot)

Expand Down
13 changes: 0 additions & 13 deletions srdfdom/srdf.py
Original file line number Diff line number Diff line change
Expand Up @@ -236,19 +236,6 @@ def add_disable_collisions(self, col):
def add_link_sphere_approximation(self, link):
self.add_aggregate("link_sphere_approximation", link)

@classmethod
def from_parameter_server(cls, key="robot_description_semantic"):
"""
Retrieve the robot semantic model on the parameter server
and parse it to create a SRDF robot structure.
Warning: this requires roscore to be running.
"""
# Could move this into xml_reflection
import rospy

return cls.from_xml_string(rospy.get_param(key))


xmlr.reflect(
Robot,
Expand Down

0 comments on commit 733e77d

Please sign in to comment.