robot.py
Go to the documentation of this file.
1 # BSD 2-Clause License
2 
3 # Copyright (c) 2018-2023, CNRS
4 # All rights reserved.
5 
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions are met:
8 
9 # * Redistributions of source code must retain the above copyright notice, this
10 # list of conditions and the following disclaimer.
11 
12 # * Redistributions in binary form must reproduce the above copyright notice,
13 # this list of conditions and the following disclaimer in the documentation
14 # and/or other materials provided with the distribution.
15 
16 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 # DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
20 # FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
21 # DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
22 # SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
23 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
24 # OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
25 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 import numpy
28 import pinocchio
29 from dynamic_graph.sot.dynamic_pinocchio.dynamic import DynamicPinocchio
30 from dynamic_graph.sot.core.operator import Selec_of_vector
31 from dynamic_graph.sot.core import Integrator
32 from dynamic_graph.tracer_real_time import TracerRealTime
33 from dynamic_graph import plug
34 from abc import ABC
35 
36 
37 class AbstractRobot(ABC):
38  """
39  This class instantiates all the entities required to get a consistent
40  representation of a robot, mainly:
41  - device : to integrate velocities into angular control,
42  - dynamic: to compute forward geometry and kinematics,
43  - integrator: an entity that integrates the velocity of the robot
44  and keeps an internal configuration the robot is controlled to,
45  - selector: an entity that selects the actuated degrees of freedom
46  of the robot to send as a position control to the device.
47  """
48 
49  tracerSize = 2**20
50  tracer = None
51  rosParamName = "/robot_description"
52  defaultFilename = None
53  # Automatically recomputed signals through the use
54  # of integrator.after.
55  # This list is maintained in order to clean the
56  # signal list device.after before exiting.
57  autoRecomputedSignals = []
58 
59  def __init__(self, name, device=None, loadFromFile=False):
60  self.name = name
61  if loadFromFile:
62  if self.defaultFilename is None:
63  raise RuntimeError("Member defaultFilename should be defined.")
64  print("Loading from file " + self.defaultFilename)
65  self.loadModelFromUrdf(self.defaultFilename, rootJointType=None)
66  else:
67  print('Using ROS parameter "/robot_description"')
68  import rospy
69 
70  if self.rosParamName not in rospy.get_param_names():
71  raise RuntimeError(
72  '"' + self.rosParamName + '" is not a ROS parameter.'
73  )
74  s = rospy.get_param(self.rosParamName)
75  self.loadModelFromString(s, rootJointType=None)
76 
77  # Create rigid body dynamics model and data (pinocchio)
78  self.dynamic = DynamicPinocchio(self.name + "_dynamic")
79  self.dynamic.setModel(self.pinocchioModel)
80  self.dynamic.displayModel()
81  self.integrator = Integrator(self.name + "_integrator")
82  self.integrator.setModel(self.pinocchioModel)
83  self.dynamic.add_signals()
84  self.dynamic.signal("velocity").value = numpy.zeros(self.pinocchioModel.nv)
85  self.dynamic.signal("acceleration").value = numpy.zeros(self.pinocchioModel.nv)
86  self.device = device
87  if device is not None:
88  self.selector = Selec_of_vector(self.name + "_selector")
89  plug(self.integrator.signal("configuration"), self.selector.signal("sin"))
90  plug(self.selector.signal("sout"), self.device.signal("control"))
91  self.timeStep = self.device.getTimeStep()
92  plug(self.integrator.signal("configuration"), self.dynamic.signal("position"))
93 
94  def initializeEntities(self):
95  if self.device is not None:
96  # Set the device limits.
97  def get(s):
98  s.recompute(0)
99  return s.value
100 
101  lb = get(self.dynamic.lowerJl)
102  ub = get(self.dynamic.upperJl)
103  actuatedJoints = self.getActuatedJoints()
104  # Joint bounds
105  lb_device = numpy.zeros(len(actuatedJoints))
106  ub_device = numpy.zeros(len(actuatedJoints))
107  for i, j in enumerate(actuatedJoints):
108  lb_device[i] = lb[j]
109  ub_device[i] = ub[j]
110  self.device.setPositionBounds(lb_device, ub_device)
111  # velocity bounds
112  ub = get(self.dynamic.upperVl)
113  ub_device = numpy.zeros(len(actuatedJoints))
114  for i, j in enumerate(actuatedJoints):
115  ub_device[i] = ub[j]
116  self.device.setVelocityBounds(-ub_device, ub_device)
117  # torque bounds
118  ub = get(self.dynamic.upperTl)
119  ub_device = numpy.zeros(len(actuatedJoints))
120  for i, j in enumerate(actuatedJoints):
121  ub_device[i] = ub[j]
122  self.device.setTorqueBounds(-ub_device, ub_device)
123 
124  def _removeMimicJoints(self, urdfFile=None, urdfString=None):
125  """Parse the URDF, extract the mimic joints and call removeJoints."""
126  # get mimic joints
127  import xml.etree.ElementTree as ET
128 
129  if urdfFile is not None:
130  assert (
131  urdfString is None
132  ), "One and only one of input argument should be provided"
133  root = ET.parse(urdfFile)
134  else:
135  assert (
136  urdfString is not None
137  ), "One and only one of input argument should be provided"
138  root = ET.fromstring(urdfString)
139 
140  mimicJoints = list()
141  for e in root.iter("joint"):
142  if "name" in e.attrib:
143  name = e.attrib["name"]
144  for c in e:
145  if hasattr(c, "tag") and c.tag == "mimic":
146  mimicJoints.append(name)
147  self.removeJoints(mimicJoints)
148 
149  def _storeRootJointType(self, rootJointType):
150  if rootJointType == pinocchio.JointModelFreeFlyer:
151  self.rootJointType = "freeflyer"
152  elif rootJointType == pinocchio.JointModelPlanar:
153  self.rootJointType = "planar"
154  elif rootJointType is None:
155  self.rootJointType = "fixed"
156  else:
157  raise TypeError(
158  "rootJointType should be either JointModelFreeflyer, "
159  "JointModelPlanar, or None."
160  )
161 
162  def removeJoints(self, joints):
163  """
164  - param joints: a list of joint names to be removed from the self.pinocchioModel
165  """
166  jointIds = list()
167  for j in joints:
168  if self.pinocchioModel.existJointName(j):
169  jointIds.append(self.pinocchioModel.getJointId(j))
170  if len(jointIds) > 0:
173  self.pinocchioModel, jointIds, q
174  )
176 
178  self,
179  urdfString,
180  rootJointType=pinocchio.JointModelFreeFlyer,
181  removeMimicJoints=True,
182  ):
183  """Load a URDF model contained in a string
184  - param rootJointType: the root joint type. None for no root joint.
185  - param removeMimicJoints: if True, all the mimic joints found in the model
186  are removed.
187  """
188  if rootJointType is None:
189  self.pinocchioModel = pinocchio.buildModelFromXML(urdfString)
190  else:
191  self.pinocchioModel = pinocchio.buildModelFromXML(
192  urdfString, rootJointType()
193  )
195  if removeMimicJoints:
196  self._removeMimicJoints(urdfString=urdfString)
197  self._storeRootJointType(rootJointType)
198 
200  self,
201  urdfPath,
202  urdfDir=None,
203  rootJointType=pinocchio.JointModelFreeFlyer,
204  removeMimicJoints=True,
205  ):
206  """
207  Load a model using the pinocchio urdf parser. This parser looks
208  for urdf files in which kinematics and dynamics information
209  have been added.
210  - param urdfPath: a path to the URDF file.
211  - param urdfDir: A list of directories. If None, will use ROS_PACKAGE_PATH.
212  """
213  if urdfPath.startswith("package://"):
214  from os import path
215 
216  n1 = 10 # len("package://")
217  n2 = urdfPath.index(path.sep, n1)
218  pkg = urdfPath[n1:n2]
219  relpath = urdfPath[n2 + 1 :]
220 
221  import rospkg
222 
223  rospack = rospkg.RosPack()
224  abspkg = rospack.get_path(pkg)
225  urdfFile = path.join(abspkg, relpath)
226  else:
227  urdfFile = urdfPath
228  if urdfDir is None:
229  import os
230 
231  urdfDir = os.environ.get("ROS_PACKAGE_PATH", "").split(":")
232  if rootJointType is None:
233  self.pinocchioModel = pinocchio.buildModelFromUrdf(urdfFile)
234  else:
235  self.pinocchioModel = pinocchio.buildModelFromUrdf(
236  urdfFile, rootJointType()
237  )
239  if removeMimicJoints:
240  self._removeMimicJoints(urdfFile=urdfFile)
241  self._storeRootJointType(rootJointType)
242 
243  def setJointValueInConfig(self, q, jointNames, jointValues):
244  """
245  q: configuration to update
246  jointNames: list of existing joint names in self.pinocchioModel
247  jointValues: corresponding joint values.
248  """
249  model = self.pinocchioModel
250  for jn, jv in zip(jointNames, jointValues):
251  assert model.existJointName(jn)
252  joint = model.joints[model.getJointId(jn)]
253  q[joint.idx_q] = jv
254 
255  def initializeTracer(self):
256  if not self.tracer:
257  self.tracer = TracerRealTime("trace")
258  self.tracer.setBufferSize(self.tracerSize)
259  self.tracer.open("/tmp/", "dg_", ".dat")
260  # Recompute trace.triger at each iteration to enable tracing.
261  self.integrator.after.addSignal("{0}.triger".format(self.tracer.name))
262 
263  def addTrace(self, entityName, signalName):
264  if self.tracer:
265  self.autoRecomputedSignals.append("{0}.{1}".format(entityName, signalName))
266  signal = f"{entityName}.{signalName}"
267  filename = f"{entityName}-{signalName}".replace("/", "_")
268  self.tracer.add(signal, filename)
269  self.integrator.after.addSignal(signal)
270 
271  def startTracer(self):
272  """
273  Start the tracer if it does not already been stopped.
274  """
275  if self.tracer:
276  self.tracer.start()
277 
278  def stopTracer(self):
279  """
280  Stop and destroy tracer.
281  """
282  if self.tracer:
283  self.tracer.dump()
284  self.tracer.stop()
285  self.tracer.close()
286  self.tracer.clear()
287  for s in self.autoRecomputedSignals:
288  self.integrator.after.rmSignal(s)
289  self.tracer = None
dynamic_pinocchio.robot.AbstractRobot.dynamic
dynamic
Definition: robot.py:78
pinocchio::DataTpl
dynamic_pinocchio.robot.AbstractRobot.loadModelFromUrdf
def loadModelFromUrdf(self, urdfPath, urdfDir=None, rootJointType=pinocchio.JointModelFreeFlyer, removeMimicJoints=True)
Definition: robot.py:199
dynamic_graph::sot::core
pinocchio::JointModelPlanarTpl
dynamic_pinocchio.robot.AbstractRobot.removeJoints
def removeJoints(self, joints)
Definition: robot.py:162
dynamic_pinocchio.robot.AbstractRobot.initializeEntities
def initializeEntities(self)
Definition: robot.py:94
dynamic_pinocchio.robot.AbstractRobot._storeRootJointType
def _storeRootJointType(self, rootJointType)
Definition: robot.py:149
dynamic_pinocchio.robot.AbstractRobot.pinocchioData
pinocchioData
Definition: robot.py:175
dynamic_pinocchio.robot.AbstractRobot.setJointValueInConfig
def setJointValueInConfig(self, q, jointNames, jointValues)
Definition: robot.py:243
dynamic_pinocchio.robot.AbstractRobot.device
device
Definition: robot.py:86
pinocchio::buildReducedModel
void buildReducedModel(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, std::vector< JointIndex > list_of_joints_to_lock, const Eigen::MatrixBase< ConfigVectorType > &reference_configuration, ModelTpl< Scalar, Options, JointCollectionTpl > &reduced_model)
dynamic_pinocchio.robot.AbstractRobot.initializeTracer
def initializeTracer(self)
Definition: robot.py:255
pinocchio::JointModelFreeFlyerTpl
dynamic_pinocchio.robot.AbstractRobot.integrator
integrator
Definition: robot.py:81
dynamic_pinocchio.robot.AbstractRobot
Definition: robot.py:37
dynamic_pinocchio.robot.AbstractRobot.pinocchioModel
pinocchioModel
Definition: robot.py:172
dynamic_pinocchio.robot.AbstractRobot.name
name
Definition: robot.py:60
dynamic_pinocchio.robot.AbstractRobot.tracer
tracer
Definition: robot.py:50
dynamic_pinocchio.robot.AbstractRobot.rosParamName
string rosParamName
Definition: robot.py:51
dynamic_pinocchio.robot.AbstractRobot.rootJointType
rootJointType
Definition: robot.py:151
dynamic_pinocchio.robot.AbstractRobot.defaultFilename
defaultFilename
Definition: robot.py:52
dynamic_pinocchio.robot.AbstractRobot.timeStep
timeStep
Definition: robot.py:91
dynamic_pinocchio.robot.AbstractRobot.selector
selector
Definition: robot.py:88
dynamic_pinocchio.robot.AbstractRobot.autoRecomputedSignals
list autoRecomputedSignals
Definition: robot.py:57
dynamic_pinocchio.robot.AbstractRobot.addTrace
def addTrace(self, entityName, signalName)
Definition: robot.py:263
dynamic_pinocchio.robot.AbstractRobot.loadModelFromString
def loadModelFromString(self, urdfString, rootJointType=pinocchio.JointModelFreeFlyer, removeMimicJoints=True)
Definition: robot.py:177
dynamic_pinocchio.robot.AbstractRobot.__init__
def __init__(self, name, device=None, loadFromFile=False)
Definition: robot.py:59
pinocchio::neutral
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model)
dynamic_pinocchio.robot.AbstractRobot._removeMimicJoints
def _removeMimicJoints(self, urdfFile=None, urdfString=None)
Definition: robot.py:124
dynamic_pinocchio.robot.AbstractRobot.stopTracer
def stopTracer(self)
Definition: robot.py:278
dynamic_pinocchio.robot.AbstractRobot.tracerSize
int tracerSize
Definition: robot.py:49
dynamic_pinocchio.robot.AbstractRobot.startTracer
def startTracer(self)
Definition: robot.py:271


sot-dynamic-pinocchio
Author(s): Olivier Stasse
autogenerated on Fri Jul 28 2023 02:10:01