Skip to content
This repository was archived by the owner on Nov 28, 2025. It is now read-only.

Commit 1ef6c7e

Browse files
committed
DynamicPinocchio has dynamic signals
1 parent 1abef64 commit 1ef6c7e

File tree

3 files changed

+9
-9
lines changed

3 files changed

+9
-9
lines changed

src/dynamic-python-module-py.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ BOOST_PYTHON_MODULE(wrap)
1212
bp::import("dynamic_graph");
1313
bp::import("pinocchio");
1414

15-
dg::python::exposeEntity<dgs::DynamicPinocchio>()
15+
dg::python::exposeEntity<dgs::DynamicPinocchio, bp::bases<dg::Entity>, dg::python::AddCommands>()
1616
.add_property("model",
1717
bp::make_function(&dgs::DynamicPinocchio::getModel, reference_existing_object()),
1818
bp::make_function(&dgs::DynamicPinocchio::setModel))

src/dynamic_graph/sot/dynamic_pinocchio/humanoid_robot.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -286,6 +286,7 @@ def get(s):
286286
def opposite(v):
287287
return [-x for x in v]
288288

289+
self.dynamic.add_signals()
289290
self.device.setPositionBounds( get(self.dynamic.lowerJl), get(self.dynamic.upperJl))
290291
self.device.setVelocityBounds(-get(self.dynamic.upperVl), get(self.dynamic.upperVl))
291292
self.device.setTorqueBounds (-get(self.dynamic.upperTl), get(self.dynamic.upperTl))

tests/python/humanoid_robot.py

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,9 @@
33
# Copyright 2011, Florent Lamiraux, Thomas Moulard, JRL, CNRS/AIST
44

55
import unittest
6-
import pinocchio
76

87
import numpy as np
9-
8+
import pinocchio
109
from dynamic_graph.sot.dynamic_pinocchio import DynamicPinocchio
1110
from dynamic_graph.sot.dynamic_pinocchio.humanoid_robot import AbstractHumanoidRobot
1211

@@ -51,19 +50,19 @@ def test_build_robot_from_string(self):
5150
arobot.dynamic = DynamicPinocchio(self.name + "_dynamic")
5251
arobot.dynamic.setModel(arobot.pinocchioModel)
5352
arobot.dynamic.setData(arobot.pinocchioData)
53+
arobot.dynamic.add_signals()
5454

5555
def get(s):
5656
s.recompute(0)
5757
return s.value
5858

59-
loc_lowerJl=np.array(get(arobot.dynamic.lowerJl))
60-
pin_lowerJl=np.array(arobot.pinocchioModel.lowerPositionLimit[1:len(arobot.pinocchioModel.lowerPositionLimit
61-
)])
59+
loc_lowerJl = np.array(get(arobot.dynamic.lowerJl))
60+
pin_lowerJl = np.array(
61+
arobot.pinocchioModel.lowerPositionLimit[1:len(arobot.pinocchioModel.lowerPositionLimit)])
6262

63-
for i in range(0,len(loc_lowerJl),1):
63+
for i in range(0, len(loc_lowerJl), 1):
6464
if not loc_lowerJl[i] == pin_lowerJl[i]:
65-
self.assertTrue(False,"lowerJl is not working")
66-
65+
self.assertTrue(False, "lowerJl is not working")
6766

6867
def test_build_robot_from_urdf(self):
6968
Robot("test_build_robot_from_string", urdfFile=self.urdf_file_name)

0 commit comments

Comments
 (0)