Skip to content

Commit

Permalink
[binding] Fix issue with Cython >= 3.0.0
Browse files Browse the repository at this point in the history
- Rename __own_impl to own_impl__ to avoid mangling
- Fix MCController.robot overload
  • Loading branch information
gergondet committed Aug 1, 2023
1 parent a863a8e commit 2fdf074
Show file tree
Hide file tree
Showing 11 changed files with 87 additions and 89 deletions.
4 changes: 1 addition & 3 deletions binding/python/mc_control/mc_control.pyx
Original file line number Diff line number Diff line change
Expand Up @@ -128,8 +128,6 @@ cdef class MCController(object):
return self.base.run()
def reset(self, ControllerResetData data):
self.base.reset(deref(data.impl))
def robot(self):
return mc_rbdyn.RobotFromC(self.base.robot())
def env(self):
return mc_rbdyn.RobotFromC(self.base.env())
def robots(self):
Expand Down Expand Up @@ -214,7 +212,7 @@ cdef class MCController(object):
if isinstance(name, unicode):
name = name.encode(u'ascii')
if name is None:
return MCController.robot(self)
return mc_rbdyn.RobotFromC(self.base.robot())
else:
return mc_rbdyn.RobotFromC(self.base.robot(name))
def addContact(self, c, *args):
Expand Down
10 changes: 5 additions & 5 deletions binding/python/mc_rbdyn/mc_rbdyn.pxd
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ cdef class Collision(object):
cdef Collision CollisionFromC(const c_mc_rbdyn.Collision&)

cdef class BodySensor(object):
cdef cppbool __own_impl
cdef cppbool own_impl__
cdef const c_mc_rbdyn.BodySensor * impl

cdef BodySensor BodySensorFromCRef(const c_mc_rbdyn.BodySensor&)
Expand All @@ -30,7 +30,7 @@ cdef class Flexibility(object):
cdef Flexibility FlexibilityFromC(const c_mc_rbdyn.Flexibility&)

cdef class ForceSensor(object):
cdef cppbool __own_impl
cdef cppbool own_impl__
cdef const c_mc_rbdyn.ForceSensor * impl

cdef ForceSensor ForceSensorFromCRef(const c_mc_rbdyn.ForceSensor&)
Expand Down Expand Up @@ -90,13 +90,13 @@ cdef CylindricalSurface CylindricalSurfaceFromPtr(c_mc_rbdyn.CylindricalSurface*

cdef class Contact(object):
cdef c_mc_rbdyn.Contact * impl
cdef cppbool __own_impl
cdef cppbool own_impl__

cdef Contact ContactFromC(const c_mc_rbdyn.Contact &, cppbool copy=?)

cdef class ContactVector(object):
cdef vector[c_mc_rbdyn.Contact] * v
cdef cppbool __own_impl
cdef cppbool own_impl__

cdef ContactVector ContactVectorFromC(const vector[c_mc_rbdyn.Contact] &, cppbool copy=?)

Expand All @@ -107,4 +107,4 @@ cdef GeosGeomGeometry GeosGeomGeometryFromSharedPtr(shared_ptr[c_mc_rbdyn.Geomet

cdef class PolygonInterpolator(object):
cdef c_mc_rbdyn.PolygonInterpolator * impl
cdef cppbool __own_impl
cdef cppbool own_impl__
26 changes: 13 additions & 13 deletions binding/python/mc_rbdyn/mc_rbdyn.pyx
Original file line number Diff line number Diff line change
Expand Up @@ -149,10 +149,10 @@ cdef Flexibility FlexibilityFromC(const c_mc_rbdyn.Flexibility & flex):

cdef class BodySensor(object):
def __dealloc__(self):
if self.__own_impl:
if self.own_impl__:
del self.impl
def __cinit__(self, skip_alloc = False):
self.__own_impl = not skip_alloc
self.own_impl__ = not skip_alloc
if skip_alloc:
self.impl = NULL
return
Expand Down Expand Up @@ -184,7 +184,7 @@ cdef BodySensor BodySensorFromCRef(const c_mc_rbdyn.BodySensor & bs):

cdef class ForceSensor(object):
def __dealloc__(self):
if self.__own_impl:
if self.own_impl__:
del self.impl
def __ctor__(self, sn, bn, sva.PTransformd X_p_f):
if isinstance(sn, unicode):
Expand All @@ -193,7 +193,7 @@ cdef class ForceSensor(object):
bn = bn.encode(u'ascii')
self.impl = new c_mc_rbdyn.ForceSensor(sn, bn, deref(X_p_f.impl))
def __cinit__(self, *args, skip_alloc = False):
self.__own_impl = not skip_alloc
self.own_impl__ = not skip_alloc
if skip_alloc:
assert(len(args) ==0)
self.impl = NULL
Expand Down Expand Up @@ -1045,7 +1045,7 @@ cdef class Contact(object):
defaultFriction = c_mc_rbdyn.ContactdefaultFriction
nrBilatPoints = c_mc_rbdyn.ContactnrBilatPoints
def __dealloc__(self):
if self.__own_impl:
if self.own_impl__:
del self.impl
def __copyctor__(self, Contact other):
self.impl = new c_mc_rbdyn.Contact(deref(other.impl))
Expand Down Expand Up @@ -1077,7 +1077,7 @@ cdef class Contact(object):
skip_alloc = bool(kwds["skip_alloc"])
else:
skip_alloc = False
self.__own_impl = True
self.own_impl__ = True
if len(args) == 0 and skip_alloc:
self.impl = NULL
elif len(args) == 1 and isinstance(args[0], Contact):
Expand Down Expand Up @@ -1189,18 +1189,18 @@ cdef Contact ContactFromC(const c_mc_rbdyn.Contact& c, cppbool copy=True):
if copy:
ret.impl = new c_mc_rbdyn.Contact(c)
else:
ret.__own_impl = False
ret.own_impl__ = False
ret.impl = &(c_mc_rbdyn.const_cast_contact(c))
return ret

cdef class ContactVector(object):
def __dealloc__(self):
if self.__own_impl:
if self.own_impl__:
del self.v
def __push_contact(self, Contact c):
self.v.push_back(deref(c.impl))
def __cinit__(self, *args, skip_alloc = False):
self.__own_impl = True
self.own_impl__ = True
if not skip_alloc:
self.v = new vector[c_mc_rbdyn.Contact]()
if len(args) == 1:
Expand Down Expand Up @@ -1261,7 +1261,7 @@ cdef ContactVector ContactVectorFromC(const vector[c_mc_rbdyn.Contact]& v,
if copy:
ret.v = new vector[c_mc_rbdyn.Contact](v)
else:
ret.__own_impl = False
ret.own_impl__ = False
ret.v = &(c_mc_rbdyn.const_cast_contact_vector(v))
return ret

Expand All @@ -1276,15 +1276,15 @@ cdef GeosGeomGeometry GeosGeomGeometryFromSharedPtr(shared_ptr[c_mc_rbdyn.Geomet

cdef class PolygonInterpolator(object):
def __dealloc__(self):
if self.__own_impl:
if self.own_impl__:
del self.impl
def __cinit__(self, *args, skip_alloc = False):
if skip_alloc:
assert(len(args) == 0)
self.impl = NULL
self.__own_impl = False
self.own_impl__ = False
else:
self.__own_impl = True
self.own_impl__ = True
assert(len(args) == 1)
data_path = args[0]
if isinstance(data_path, unicode):
Expand Down
2 changes: 1 addition & 1 deletion binding/python/mc_rtc/mc_rtc.pxd
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ cdef Logger LoggerFromRef(c_mc_rtc.Logger &)

cdef class Configuration(object):
cdef c_mc_rtc.Configuration * impl
cdef cppbool __own_impl
cdef cppbool own_impl__

cdef Configuration ConfigurationFromValue(c_mc_rtc.Configuration)
cdef Configuration ConfigurationFromRef(c_mc_rtc.Configuration &)
8 changes: 4 additions & 4 deletions binding/python/mc_rtc/mc_rtc.pyx
Original file line number Diff line number Diff line change
Expand Up @@ -101,11 +101,11 @@ cdef Logger LoggerFromRef(c_mc_rtc.Logger & logger):

cdef class Configuration(object):
def __dealloc__(self):
if self.__own_impl:
if self.own_impl__:
del self.impl
def __cinit__(self, *args, skip_alloc = False):
if not skip_alloc:
self.__own_impl = True
self.own_impl__ = True
if(len(args) == 0):
self.impl = new c_mc_rtc.Configuration()
else:
Expand All @@ -115,7 +115,7 @@ cdef class Configuration(object):
path = path.encode(u'ascii')
self.impl = new c_mc_rtc.Configuration(<string>(path))
else:
self.__own_impl = False
self.own_impl__ = False
self.impl = NULL
@staticmethod
def fromData(data):
Expand Down Expand Up @@ -306,7 +306,7 @@ cdef class Configuration(object):

cdef Configuration ConfigurationFromValue(c_mc_rtc.Configuration conf):
cdef Configuration ret = Configuration(skip_alloc = True)
ret.__own_impl = True
ret.own_impl__ = True
ret.impl = new c_mc_rtc.Configuration(conf)
return ret

Expand Down
8 changes: 4 additions & 4 deletions binding/python/mc_solver/mc_solver.pxd
Original file line number Diff line number Diff line change
Expand Up @@ -11,13 +11,13 @@ cdef class ConstraintSet(object):

cdef class ContactConstraint(ConstraintSet):
cdef c_mc_solver.ContactConstraint * impl
cdef cppbool __own_impl
cdef cppbool own_impl__

cdef ContactConstraint ContactConstraintFromPtr(c_mc_solver.ContactConstraint *)

cdef class KinematicsConstraint(ConstraintSet):
cdef c_mc_solver.KinematicsConstraint * impl
cdef cppbool __own_impl
cdef cppbool own_impl__

cdef KinematicsConstraint KinematicsConstraintFromPtr(c_mc_solver.KinematicsConstraint *)

Expand All @@ -28,13 +28,13 @@ cdef DynamicsConstraint DynamicsConstraintFromPtr(c_mc_solver.DynamicsConstraint

cdef class CollisionsConstraint(ConstraintSet):
cdef c_mc_solver.CollisionsConstraint * impl
cdef cppbool __own_impl
cdef cppbool own_impl__

cdef CollisionsConstraint CollisionsConstraintFromPtr(c_mc_solver.CollisionsConstraint*)

cdef class QPSolver(object):
cdef c_mc_solver.QPSolver * impl
cdef cppbool __own_impl
cdef cppbool own_impl__

cdef QPSolver QPSolverFromPtr(c_mc_solver.QPSolver*)

Expand Down
30 changes: 15 additions & 15 deletions binding/python/mc_solver/mc_solver.pyx
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,10 @@ cdef class ContactConstraint(ConstraintSet):
Velocity = c_mc_solver.ContactTypeVelocity
Position = c_mc_solver.ContactTypePosition
def __dealloc__(self):
if self.__own_impl:
if self.own_impl__:
del self.impl
def __cinit__(self, timeStep, int cType = ContactConstraint.Velocity, dynamics = True, skip_alloc = False):
self.__own_impl = True
self.own_impl__ = True
if not skip_alloc:
assert(cType >= ContactConstraint.Acceleration and cType <= ContactConstraint.Position)
self.impl = self.cs_base = new c_mc_solver.ContactConstraint(timeStep, <c_mc_solver.ContactConstraintContactType>cType)
Expand All @@ -54,17 +54,17 @@ cdef class ContactConstraint(ConstraintSet):

cdef ContactConstraint ContactConstraintFromPtr(c_mc_solver.ContactConstraint * p):
cdef ContactConstraint ret = ContactConstraint(0.0, skip_alloc = True)
ret.__own_impl = False
ret.own_impl__ = False
ret.impl = ret.cs_base = p
return ret

cdef class KinematicsConstraint(ConstraintSet):
def __dealloc__(self):
if type(self) is KinematicsConstraint and self.__own_impl:
if type(self) is KinematicsConstraint and self.own_impl__:
del self.impl
def __cinit__(self, mc_rbdyn.Robots robots, robotIndex, timeStep, damper = None, velocityPercent = 1.0, infTorque = False, skip_alloc = False):
cdef c_mc_solver.array3d damp = c_mc_solver.array3d()
self.__own_impl = True
self.own_impl__ = True
if type(self) is KinematicsConstraint and not skip_alloc:
if damper is None:
self.impl = self.cs_base = new c_mc_solver.KinematicsConstraint(deref(robots.impl), robotIndex, timeStep)
Expand All @@ -76,17 +76,17 @@ cdef class KinematicsConstraint(ConstraintSet):

cdef KinematicsConstraint KinematicsConstraintFromPtr(c_mc_solver.KinematicsConstraint*p):
cdef KinematicsConstraint ret = KinematicsConstraint(None, 0, 0.0, skip_alloc = True)
ret.__own_impl = False
ret.own_impl__ = False
ret.impl = ret.cs_base = p
return ret

cdef class DynamicsConstraint(KinematicsConstraint):
def __dealloc__(self):
if self.__own_impl:
if self.own_impl__:
del self.impl
def __cinit__(self, mc_rbdyn.Robots robots, robotIndex, timeStep, isStatic = False, damper = None, velocityPercent = 1.0, infTorque = False, skip_alloc = False):
cdef c_mc_solver.array3d damp = c_mc_solver.array3d()
self.__own_impl = True
self.own_impl__ = True
if not skip_alloc:
if damper is None:
self.d_impl = self.impl = self.cs_base = new c_mc_solver.DynamicsConstraint(deref(robots.impl), robotIndex, timeStep, infTorque)
Expand All @@ -98,17 +98,17 @@ cdef class DynamicsConstraint(KinematicsConstraint):

cdef DynamicsConstraint DynamicsConstraintFromPtr(c_mc_solver.DynamicsConstraint * p):
cdef DynamicsConstraint ret = DynamicsConstraint(None, 0, 0.0, skip_alloc = True)
ret.__own_impl = False
ret.own_impl__ = False
ret.d_impl = ret.impl = ret.cs_base = p
return ret

cdef class CollisionsConstraint(ConstraintSet):
defaultDampingOffset = c_mc_solver.CollisionsConstraintDefaultDampingOffset
def __dealloc__(self):
if self.__own_impl:
if self.own_impl__:
del self.impl
def __cinit__(self, mc_rbdyn.Robots robots, r1Index, r2Index, timeStep, skip_alloc = False):
self.__own_impl = True
self.own_impl__ = True
if not skip_alloc:
self.impl = self.cs_base = new c_mc_solver.CollisionsConstraint(deref(robots.impl), r1Index, r2Index, timeStep)
def removeCollision(self, QPSolver solver, b1Name, b2Name):
Expand Down Expand Up @@ -148,7 +148,7 @@ cdef class CollisionsConstraint(ConstraintSet):

cdef CollisionsConstraint CollisionsConstraintFromPtr(c_mc_solver.CollisionsConstraint * p):
cdef CollisionsConstraint ret = CollisionsConstraint(None, None, None, None, skip_alloc = True)
ret.__own_impl = False
ret.own_impl__ = False
ret.impl = ret.cs_base = p
return ret

Expand All @@ -159,10 +159,10 @@ cdef qp.BilateralContact BilateralContactFromC(const c_qp.BilateralContact & bc)

cdef class QPSolver(object):
def __dealloc__(self):
if self.__own_impl:
if self.own_impl__:
del self.impl
def __cinit__(self, mc_rbdyn.Robots robots, timeStep, skip_alloc = False):
self.__own_impl = True
self.own_impl__ = True
if not skip_alloc:
self.impl = new c_mc_solver.TasksQPSolver(robots.impl, timeStep)
def addConstraintSet(self, ConstraintSet cs):
Expand Down Expand Up @@ -191,7 +191,7 @@ cdef class QPSolver(object):

cdef QPSolver QPSolverFromPtr(c_mc_solver.QPSolver * p):
cdef QPSolver ret = QPSolver(None, 0, skip_alloc = True)
ret.__own_impl = False
ret.own_impl__ = False
ret.impl = p
return ret

Expand Down
2 changes: 1 addition & 1 deletion binding/python/mc_tasks/force/force.pxd
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ cdef class AdmittanceTask(SurfaceTransformTask):

cdef class ComplianceTask(MetaTask):
cdef c_force.ComplianceTask * impl
cdef cppbool __own_impl
cdef cppbool own_impl__

cdef class DampingTask(AdmittanceTask):
cdef c_force.DampingTask * damping_impl
Expand Down
Loading

0 comments on commit 2fdf074

Please sign in to comment.