Skip to content
Snippets Groups Projects
Unverified Commit 269bc8db authored by Guilhem Saurel's avatar Guilhem Saurel Committed by GitHub
Browse files

Merge pull request #45 from nim65s/devel

add talos full
parents 1df62135 9829dbb8
No related branches found
No related tags found
No related merge requests found
Pipeline #10917 passed
...@@ -3,6 +3,7 @@ import warnings ...@@ -3,6 +3,7 @@ import warnings
from os.path import dirname, exists, join from os.path import dirname, exists, join
import numpy as np import numpy as np
import pinocchio as pin import pinocchio as pin
from pinocchio.robot_wrapper import RobotWrapper from pinocchio.robot_wrapper import RobotWrapper
...@@ -91,8 +92,13 @@ def loadANYmal(withArm=None): ...@@ -91,8 +92,13 @@ def loadANYmal(withArm=None):
free_flyer=True) free_flyer=True)
def loadTalos(legs=False, arm=False): def loadTalos(legs=False, arm=False, full=False):
URDF_FILENAME = "talos_left_arm.urdf" if arm else "talos_reduced.urdf" if arm:
URDF_FILENAME = "talos_left_arm.urdf"
elif full:
URDF_FILENAME = "talos_full_v2.urdf"
else:
URDF_FILENAME = "talos_reduced.urdf"
SRDF_FILENAME = "talos.srdf" SRDF_FILENAME = "talos.srdf"
robot = robot_loader('talos_data', URDF_FILENAME, SRDF_FILENAME, free_flyer=not arm) robot = robot_loader('talos_data', URDF_FILENAME, SRDF_FILENAME, free_flyer=not arm)
...@@ -260,6 +266,9 @@ ROBOTS = { ...@@ -260,6 +266,9 @@ ROBOTS = {
'talos_legs': (loadTalos, { 'talos_legs': (loadTalos, {
'legs': True 'legs': True
}), }),
'talos_full': (loadTalos, {
'full': True
}),
'tiago': (loadTiago, {}), 'tiago': (loadTiago, {}),
'tiago_no_hand': (loadTiago, { 'tiago_no_hand': (loadTiago, {
'hand': False 'hand': False
......
This diff is collapsed.
...@@ -55,6 +55,9 @@ class RobotTestCase(unittest.TestCase): ...@@ -55,6 +55,9 @@ class RobotTestCase(unittest.TestCase):
def test_talos(self): def test_talos(self):
self.check('talos', 39, 38) self.check('talos', 39, 38)
def test_talos_full(self):
self.check('talos_full', 51, 50)
def test_talos_arm(self): def test_talos_arm(self):
self.check('talos_arm', 7, 7) self.check('talos_arm', 7, 7)
......
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