Skip to content
Snippets Groups Projects
Unverified Commit 8f8b8bec authored by Justin Carpentier's avatar Justin Carpentier Committed by GitHub
Browse files

Merge pull request #73 from cmastalli/topic/q0-fix

Removing duplication of q0 in RobotLoader, instead using the one introduced in RobotWrapper
parents 581f4c1a 5c9f9dba
No related branches found
No related tags found
No related merge requests found
Pipeline #13912 passed with warnings
......@@ -66,11 +66,11 @@ class RobotLoader(object):
if self.srdf_filename:
self.srdf_path = join(self.model_path, self.path, self.srdf_subpath, self.srdf_filename)
self.q0 = readParamsFromSrdf(self.robot.model, self.srdf_path, self.verbose, self.has_rotor_parameters,
self.ref_posture)
self.robot.q0 = readParamsFromSrdf(self.robot.model, self.srdf_path, self.verbose,
self.has_rotor_parameters, self.ref_posture)
else:
self.srdf_path = None
self.q0 = None
self.robot.q0 = None
if self.free_flyer:
self.addFreeFlyerJointLimits()
......@@ -83,6 +83,11 @@ class RobotLoader(object):
lb[:7] = -1
self.robot.model.lowerPositionLimit = lb
@property
def q0(self):
warnings.warn("`q0` is deprecated. Please use `robot.q0`", FutureWarning, 2)
return self.robot.q0
class ANYmalLoader(RobotLoader):
path = 'anymal_b_simple_description'
......@@ -182,8 +187,8 @@ class TalosLegsLoader(TalosLoader):
self.robot.visual_data = pin.GeometryData(g2)
# Load SRDF file
self.q0 = readParamsFromSrdf(self.robot.model, self.srdf_path, self.verbose, self.has_rotor_parameters,
self.ref_posture)
self.robot.q0 = readParamsFromSrdf(self.robot.model, self.srdf_path, self.verbose,
self.has_rotor_parameters, self.ref_posture)
assert (m2.armature[:6] == 0.).all()
# Add the free-flyer joint limits to the new model
......@@ -509,4 +514,4 @@ def load(name, display=False, rootNodeName=''):
def load_full(name, display=False, rootNodeName=''):
"""Load a robot by its name, optionnaly display it in a viewer, and provide its q0 and paths."""
inst = loader(name, display, rootNodeName)
return inst.robot, inst.q0, inst.urdf_path, inst.srdf_path
return inst.robot, inst.robot.q0, inst.urdf_path, inst.srdf_path
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment