Robowflex  v0.1
Making MoveIt Easy
robowflex_visualization.robot.Robot Class Reference

Controllable URDF described robot. More...

Public Member Functions

def __init__ (self, name, urdf, make_pretty=True)
 Constructor. More...
 
def load_urdf (self, urdf, load=True)
 Loads the URDF as a COLLADA mesh, as well as loading the XML. More...
 
def get_link (self, link_name)
 Gets a Blender object corresponding to a link on the robot. More...
 
def get_link_xml (self, link_name)
 Get the XML description in the URDF of a link. More...
 
def get_joint_xml (self, joint_name)
 Get the XML description in the URDF of a joint. More...
 
def set_joint (self, joint_name, value, interpolate=True)
 Set the value of a 1-DoF joint in the URDF. More...
 
def set_joint_tf (self, joint_name, tf, interpolate=True)
 Set the value of a 6-DoF joint in the URDF. More...
 
def add_keyframe (self, joint_name, frame)
 Adds a keyframe to a joint in the URDF at a frame in the animation timeline. More...
 
def animate_path (self, path_file, fps=60., start=30, reverse=False, interpolate=False)
 Adds keyframes to animate a moveit_msgs::RobotTrajectoryMsg. More...
 
def set_state (self, state_file)
 Sets the robot's state from a file with a moveit_msgs::RobotState. More...
 
def attach_object (self, link_name, item, frame)
 Attaches an object to a link of the robot. More...
 
def detach_object (self, link_name, item, frame)
 Detaches an object to a link of the robot. More...
 
def prettify (self)
 Cleans up robot mesh geometry and applies modifiers to improve rendering aesthetics. More...
 
def load_link_mesh (self, link_name)
 Loads the mesh data for a specific link on the robot. More...
 
def clear_animation_data (self)
 Clear all animation data for this robot. More...
 
def get_root (self)
 Get the root link of this robot. More...
 

Public Attributes

 name
 Name of Robot and Blender collection. More...
 
 collection
 Blender collection containing loaded robot geometry. More...
 
 urdf_path
 
 urdf_xml
 
 robot
 Parsed URDF file. More...
 

Detailed Description

Controllable URDF described robot.

This class loads a URDF from the package resource URI under a Blender collection.

Definition at line 18 of file robot.py.

Constructor & Destructor Documentation

◆ __init__()

def robowflex_visualization.robot.Robot.__init__ (   self,
  name,
  urdf,
  make_pretty = True 
)

Constructor.

Loads robot and creates a collection.

Parameters
nameName of Blender collection to put Robot geometry in.
urdfURDF package resource URI to load.
make_prettyCalls prettify functions after load.

Definition at line 36 of file robot.py.

36  def __init__(self, name, urdf, make_pretty = True):
37  self.name = name
38 
39  self.collection = rv.utils.get_collection(name)
40  if not self.collection:
41  self.collection = rv.utils.make_collection(name)
42  self.load_urdf(urdf)
43  if make_pretty:
44  self.prettify()
45 
46  else:
47  self.load_urdf(urdf, False)
48 
49  self.clear_animation_data()
50 

Member Function Documentation

◆ add_keyframe()

def robowflex_visualization.robot.Robot.add_keyframe (   self,
  joint_name,
  frame 
)

Adds a keyframe to a joint in the URDF at a frame in the animation timeline.

Adds keyframe actually to child link (same as set_joint()). Uses current transform of the link. Only keyframes important data path for the joint (e.g., rotation for rotation joints).

Parameters
joint_nameJoint to add keyframe to.
frameFrame to add keyframe at.

Definition at line 212 of file robot.py.

212  def add_keyframe(self, joint_name, frame):
213  if joint_name == "virtual_joint":
214  root = self.get_root().name
215  link_xml = self.get_link_xml(root)
216  link = self.get_link(root)
217  else:
218  joint_xml = self.get_joint_xml(joint_name)
219  link_xml = self.get_link_xml(joint_xml.child)
220  link = self.get_link(joint_xml.child)
221 
222  link.keyframe_insert(data_path = "location", frame = frame)
223  link.keyframe_insert(data_path = "rotation_quaternion", frame = frame)
224 

◆ animate_path()

def robowflex_visualization.robot.Robot.animate_path (   self,
  path_file,
  fps = 60.,
  start = 30,
  reverse = False,
  interpolate = False 
)

Adds keyframes to animate a moveit_msgs::RobotTrajectoryMsg.

Parameters
path_fileYAML file for moveit_msgs::RobotTrajectoryMsg.
fpsFrames-per-second to animate the path at.
startFrame to begin the animation at.
reverseIf true, load path from end-to-start rather than start-to-end.
interpolateIf true, interpolates quaternion from previous state.

Definition at line 233 of file robot.py.

238  interpolate = False):
239  path = rv.utils.read_YAML_data(path_file)
240 
241  trajectory = path["joint_trajectory"]
242  names = trajectory["joint_names"]
243 
244  if "multi_dof_joint_trajectory" in path:
245  mdof_trajectory = path["multi_dof_joint_trajectory"]
246  mdof_names = mdof_trajectory["joint_names"]
247 
248  last_time = float(trajectory["points"][-1]["time_from_start"])
249  last_frame = start
250 
251  # Add keyframe at start
252  for name in names:
253  self.add_keyframe(name, start)
254 
255  for i in range(len(trajectory["points"])):
256  point = trajectory["points"][i]
257 
258  time = float(point["time_from_start"])
259  if reverse:
260  time = last_time - time
261 
262  frame = start + time * fps
263  if frame > last_frame:
264  last_frame = frame
265 
266  for value, name in zip(point["positions"], names):
267  self.set_joint(name, value, interpolate or i > 0)
268  self.add_keyframe(name, frame)
269 
270  if "multi_dof_joint_trajectory" in path:
271  mdof_point = mdof_trajectory["points"][i]
272  for tf, name in zip(mdof_point["transforms"], mdof_names):
273  self.set_joint_tf(name, tf, interpolate or i > 0)
274  self.add_keyframe(name, frame)
275 
276  return math.ceil(last_frame)
277 

◆ attach_object()

def robowflex_visualization.robot.Robot.attach_object (   self,
  link_name,
  item,
  frame 
)

Attaches an object to a link of the robot.

Parameters
link_nameName of link to attach item to.
itemBlender object to attach to link.
frameAnimation frame to parent in.

Definition at line 297 of file robot.py.

297  def attach_object(self, link_name, item, frame):
298  rv.utils.parent_object(self.get_link(link_name), item, frame)
299 

◆ clear_animation_data()

def robowflex_visualization.robot.Robot.clear_animation_data (   self)

Clear all animation data for this robot.

Definition at line 361 of file robot.py.

361  def clear_animation_data(self):
362  for link_xml in self.robot.links:
363  link = self.get_link(link_xml.name)
364  if link:
365  link.animation_data_clear()
366 

◆ detach_object()

def robowflex_visualization.robot.Robot.detach_object (   self,
  link_name,
  item,
  frame 
)

Detaches an object to a link of the robot.

Object must have been previously parented.

Parameters
link_nameName of link to attach item to.
itemBlender object to attach to link.
frameAnimation frame to parent in.

Definition at line 307 of file robot.py.

307  def detach_object(self, link_name, item, frame):
308  rv.utils.unparent_object(self.get_link(link_name), item, frame)
309 

◆ get_joint_xml()

def robowflex_visualization.robot.Robot.get_joint_xml (   self,
  joint_name 
)

Get the XML description in the URDF of a joint.

Parameters
joint_nameName of the joint to find in the robot.

Definition at line 113 of file robot.py.

113  def get_joint_xml(self, joint_name):
114  for joint in self.robot.joints:
115  if joint.name == joint_name:
116  return joint
117 
118  return None
119 

◆ get_link()

def robowflex_visualization.robot.Robot.get_link (   self,
  link_name 
)

Gets a Blender object corresponding to a link on the robot.

Parameters
link_nameName of the link to find in the robot.

Definition at line 95 of file robot.py.

95  def get_link(self, link_name):
96  return rv.utils.find_object_in_collection(self.name, link_name)
97 

◆ get_link_xml()

def robowflex_visualization.robot.Robot.get_link_xml (   self,
  link_name 
)

Get the XML description in the URDF of a link.

Parameters
link_nameName of the link to find in the robot.

Definition at line 102 of file robot.py.

102  def get_link_xml(self, link_name):
103  for link in self.robot.links:
104  if link.name == link_name:
105  return link
106 
107  return None
108 

◆ get_root()

def robowflex_visualization.robot.Robot.get_root (   self)

Get the root link of this robot.

Definition at line 368 of file robot.py.

368  def get_root(self):
369  children = []
370  for joint in self.robot.joints:
371  xml = self.get_joint_xml(joint.name)
372  children.append(xml.child)
373 
374  for link in self.robot.links:
375  if link.name not in children:
376  return link

◆ load_link_mesh()

def robowflex_visualization.robot.Robot.load_link_mesh (   self,
  link_name 
)

Loads the mesh data for a specific link on the robot.

If the mesh is originally a COLLADA mesh, loads and replaces current mesh data. This provides better textures if they exist, as collada_urdf does not preserve them when converting the robot.

Parameters
link_nameName of the link to the load the mesh for.

Definition at line 332 of file robot.py.

332  def load_link_mesh(self, link_name):
333  link_xml = self.get_link_xml(link_name)
334 
335  name = self.name + "_temp"
336  collection = rv.utils.make_collection(name)
337 
338  if link_xml.visuals:
339  visual = link_xml.visuals[0]
340  geometry = visual.geometry
341 
342  # Only replace geometry if COLLADA
343  if hasattr(geometry, 'filename') and ".dae" in geometry.filename:
344  meshes, top = rv.primitives.add_mesh(
345  {"resource": geometry.filename})
346 
347  rv.utils.deselect_all()
348  bpy.context.view_layer.objects.active = meshes[0]
349  for mesh in meshes:
350  mesh.select_set(True)
351  bpy.ops.object.join()
352  rv.utils.move_selected_to_collection(name)
353  rv.utils.deselect_all()
354 
355  old = self.get_link(link_name)
356  old.data = meshes[0].data
357 
358  rv.utils.remove_collection(name)
359 

◆ load_urdf()

def robowflex_visualization.robot.Robot.load_urdf (   self,
  urdf,
  load = True 
)

Loads the URDF as a COLLADA mesh, as well as loading the XML.

Parameters
urdfURDF package resource URI to load.
loadLoad the actual COLLADA mesh, not just URDF info.

Definition at line 56 of file robot.py.

56  def load_urdf(self, urdf, load = True):
57  self.urdf_path = rv.utils.resolve_path(urdf)
58  xml_output = os.path.join("/tmp",
59  os.path.basename(self.urdf_path) + ".xml")
60  dae_output = os.path.join("/tmp",
61  os.path.basename(self.urdf_path) + ".dae")
62 
63  subprocess.check_output([
64  "rosrun",
65  "xacro",
66  "xacro",
67  self.urdf_path,
68  "-o",
69  xml_output,
70  ])
71 
72  self.urdf_xml = open(xml_output, 'r').read()
73  self.robot = URDF.Robot.from_xml_string(self.urdf_xml)
74 
75  if load:
76  # Don't regenerate URDF COLLADA if it already exists.
77  if not os.path.exists(dae_output):
78  subprocess.check_output([
79  "rosrun",
80  "collada_urdf",
81  "urdf_to_collada",
82  xml_output,
83  dae_output,
84  ])
85 
86  # Import and move into new collection.
87  bpy.ops.wm.collada_import(filepath = dae_output)
88  rv.utils.move_selected_to_collection(self.name)
89  rv.utils.deselect_all()
90 

◆ prettify()

def robowflex_visualization.robot.Robot.prettify (   self)

Cleans up robot mesh geometry and applies modifiers to improve rendering aesthetics.

Definition at line 313 of file robot.py.

313  def prettify(self):
314  for link_xml in self.robot.links:
315  # Loads original mesh.
316  self.load_link_mesh(link_xml.name)
317 
318  link = self.get_link(link_xml.name)
319  rv.utils.remove_doubles(link)
320  # rv.utils.remove_inner_faces(link)
321  rv.utils.apply_edge_split(link)
322  rv.utils.apply_smooth_shade(link)
323 

◆ set_joint()

def robowflex_visualization.robot.Robot.set_joint (   self,
  joint_name,
  value,
  interpolate = True 
)

Set the value of a 1-DoF joint in the URDF.

Works by finding the child link of the joint and setting its relative transformation in Blender according to the axis of movement. Basically reimplementing forward kinematics.

Parameters
joint_nameName of the joint to set in the robot.
valueValue of joint to set.
interpolateIf true, will attempt to make quaternions compatible with current pose.

Definition at line 131 of file robot.py.

131  def set_joint(self, joint_name, value, interpolate = True):
132  joint_xml = self.get_joint_xml(joint_name)
133  parent_xml = self.get_link_xml(joint_xml.parent)
134  link_xml = self.get_link_xml(joint_xml.child)
135  link = self.get_link(joint_xml.child)
136 
137  link.rotation_mode = "QUATERNION"
138 
139  parent_l = mathutils.Matrix.Identity(4)
140  if parent_xml.visual:
141  parent_l = rv.utils.get_tf_origin_xml(parent_xml.visual)
142  parent_l = parent_l.inverted()
143 
144  origin_l = mathutils.Matrix.Identity(4)
145  if link_xml.visual:
146  origin_l = rv.utils.get_tf_origin_xml(link_xml.visual)
147 
148  origin_j = rv.utils.get_tf_origin_xml(joint_xml)
149 
150  if joint_xml.type == "prismatic":
151  rm = mathutils.Matrix.Translation(
152  mathutils.Vector(joint_xml.axis) * value)
153 
154  else:
155  rotation = mathutils.Quaternion(joint_xml.axis, value)
156  rm = rotation.to_matrix()
157  rm.resize_4x4()
158 
159  output = parent_l @ origin_j @ rm @ origin_l
160 
161  prior = link.rotation_quaternion.copy()
162 
163  link.location = output.to_translation()
164  link.rotation_quaternion = output.to_quaternion()
165 
166  if interpolate:
167  link.rotation_quaternion.make_compatible(prior)
168 

◆ set_joint_tf()

def robowflex_visualization.robot.Robot.set_joint_tf (   self,
  joint_name,
  tf,
  interpolate = True 
)

Set the value of a 6-DoF joint in the URDF.

Assumes input transform is of the form: { 'translation' : [x, y, z], 'rotation' : [x, y, z, w] }

Parameters
joint_nameName of the joint to set in the robot.
tfYAML of the transform.
interpolateIf true, will attempt to make quaternions compatible with current pose.

Definition at line 182 of file robot.py.

182  def set_joint_tf(self, joint_name, tf, interpolate = True):
183  # Check for "virtual_joint", which isn't in the URDF
184  if joint_name == "virtual_joint":
185  root = self.get_root().name
186  link_xml = self.get_link_xml(root)
187  link = self.get_link(root)
188  else:
189  joint_xml = self.get_joint_xml(joint_name)
190  link_xml = self.get_link_xml(joint_xml.child)
191  link = self.get_link(joint_xml.child)
192 
193  link.rotation_mode = "QUATERNION"
194  link.location = tf['translation']
195 
196  q = mathutils.Quaternion([tf['rotation'][3]] + tf['rotation'][:3])
197  if interpolate:
198  q.make_compatible(link.rotation_quaternion)
199 
200  link.rotation_quaternion = q
201 

◆ set_state()

def robowflex_visualization.robot.Robot.set_state (   self,
  state_file 
)

Sets the robot's state from a file with a moveit_msgs::RobotState.

Parameters
state_fileFile containing the state.

Definition at line 281 of file robot.py.

281  def set_state(self, state_file):
282  state = rv.utils.read_YAML_data(state_file)
283  joint_state = state["joint_state"]
284 
285  names = joint_state["name"]
286  position = joint_state["position"]
287 
288  for name, value in zip(names, position):
289  self.set_joint(name, value)
290 

Member Data Documentation

◆ collection

robowflex_visualization.robot.Robot.collection

Blender collection containing loaded robot geometry.

Definition at line 39 of file robot.py.

◆ name

robowflex_visualization.robot.Robot.name

Name of Robot and Blender collection.

Definition at line 37 of file robot.py.

◆ robot

robowflex_visualization.robot.Robot.robot

Parsed URDF file.

Definition at line 73 of file robot.py.

◆ urdf_path

robowflex_visualization.robot.Robot.urdf_path

Definition at line 57 of file robot.py.

◆ urdf_xml

robowflex_visualization.robot.Robot.urdf_xml

Definition at line 72 of file robot.py.


The documentation for this class was generated from the following file: