29 from dynamic_graph.sot.dynamic_pinocchio.dynamic
import DynamicPinocchio
30 from dynamic_graph.sot.core.operator
import Selec_of_vector
32 from dynamic_graph.tracer_real_time
import TracerRealTime
33 from dynamic_graph
import plug
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.
51 rosParamName =
"/robot_description"
52 defaultFilename =
None
57 autoRecomputedSignals = []
59 def __init__(self, name, device=None, loadFromFile=False):
63 raise RuntimeError(
"Member defaultFilename should be defined.")
67 print(
'Using ROS parameter "/robot_description"')
87 if device
is not None:
95 if self.
device is not None:
103 actuatedJoints = self.getActuatedJoints()
105 lb_device = numpy.zeros(len(actuatedJoints))
106 ub_device = numpy.zeros(len(actuatedJoints))
107 for i, j
in enumerate(actuatedJoints):
110 self.
device.setPositionBounds(lb_device, ub_device)
113 ub_device = numpy.zeros(len(actuatedJoints))
114 for i, j
in enumerate(actuatedJoints):
116 self.
device.setVelocityBounds(-ub_device, ub_device)
119 ub_device = numpy.zeros(len(actuatedJoints))
120 for i, j
in enumerate(actuatedJoints):
122 self.
device.setTorqueBounds(-ub_device, ub_device)
125 """Parse the URDF, extract the mimic joints and call removeJoints."""
127 import xml.etree.ElementTree
as ET
129 if urdfFile
is not None:
132 ),
"One and only one of input argument should be provided"
133 root = ET.parse(urdfFile)
136 urdfString
is not None
137 ),
"One and only one of input argument should be provided"
138 root = ET.fromstring(urdfString)
141 for e
in root.iter(
"joint"):
142 if "name" in e.attrib:
143 name = e.attrib[
"name"]
145 if hasattr(c,
"tag")
and c.tag ==
"mimic":
146 mimicJoints.append(name)
154 elif rootJointType
is None:
158 "rootJointType should be either JointModelFreeflyer, "
159 "JointModelPlanar, or None."
164 - param joints: a list of joint names to be removed from the self.pinocchioModel
170 if len(jointIds) > 0:
180 rootJointType=pinocchio.JointModelFreeFlyer,
181 removeMimicJoints=True,
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
188 if rootJointType
is None:
195 if removeMimicJoints:
203 rootJointType=pinocchio.JointModelFreeFlyer,
204 removeMimicJoints=True,
207 Load a model using the pinocchio urdf parser. This parser looks
208 for urdf files in which kinematics and dynamics information
210 - param urdfPath: a path to the URDF file.
211 - param urdfDir: A list of directories. If None, will use ROS_PACKAGE_PATH.
213 if urdfPath.startswith(
"package://"):
217 n2 = urdfPath.index(path.sep, n1)
218 pkg = urdfPath[n1:n2]
219 relpath = urdfPath[n2 + 1 :]
223 rospack = rospkg.RosPack()
224 abspkg = rospack.get_path(pkg)
225 urdfFile = path.join(abspkg, relpath)
231 urdfDir = os.environ.get(
"ROS_PACKAGE_PATH",
"").split(
":")
232 if rootJointType
is None:
239 if removeMimicJoints:
245 q: configuration to update
246 jointNames: list of existing joint names in self.pinocchioModel
247 jointValues: corresponding joint values.
250 for jn, jv
in zip(jointNames, jointValues):
251 assert model.existJointName(jn)
252 joint = model.joints[model.getJointId(jn)]
257 self.
tracer = TracerRealTime(
"trace")
259 self.
tracer.open(
"/tmp/",
"dg_",
".dat")
266 signal = f
"{entityName}.{signalName}"
267 filename = f
"{entityName}-{signalName}".replace(
"/",
"_")
268 self.
tracer.add(signal, filename)
273 Start the tracer if it does not already been stopped.
280 Stop and destroy tracer.