#/usr/bin/env python

from hpp.gepetto import Viewer, PathPlayer
from hpp.corbaserver.hrp2 import Robot
from hpp.corbaserver import ProblemSolver
from hpp.corbaserver.wholebody_step.client import Client as WsClient
import time

#Robot.urdfSuffix = '_capsule'
#Robot.srdfSuffix= '_capsule'

robot = Robot('hrp2_14')  #46 DOF
#robot.setJointBounds ('base_joint_xyz', [-2.5, 2.5, -2.5, 2.5, 0.62, 0.68])
robot.setJointBounds('base_joint_xyz', [-3, 3, -3, 3, 0, 1])
ps = ProblemSolver(robot)
cl = robot.client
Viewer.withFloor = True
r = Viewer(ps)
#r.loadObstacleModel ("room_description","room","room")
#r.loadObstacleModel ("room_description","walls","walls")
pp = PathPlayer(cl, r)
q0 = robot.getInitialConfig()
r(q0)

# Add constraints
wcl = WsClient()
wcl.problem.addStaticStabilityConstraints("balance", q0, robot.leftAnkle,
                                          robot.rightAnkle)

ps.setNumericalConstraints("balance", [
    "balance/relative-com", "balance/relative-orientation",
#/usr/bin/env python

from hpp_ros import ScenePublisher, PathPlayer
from hpp.corbaserver.hrp2 import Robot
from hpp.corbaserver import ProblemSolver
from hpp.corbaserver.wholebody_step.client import Client as WsClient

Robot.urdfSuffix = '_capsule'
Robot.srdfSuffix = '_capsule'

robot = Robot('hrp2_14')
robot.setTranslationBounds(-3, 3, -3, 3, 0, 1)
cl = robot.client

r = ScenePublisher(robot)
q0 = robot.getInitialConfig()
r(q0)

# Add constraints
wcl = WsClient()
wcl.problem.addStaticStabilityConstraints("balance", q0, robot.leftAnkle,
                                          robot.rightAnkle)

ps = ProblemSolver(robot)
ps.setNumericalConstraints("balance", [
    "balance/relative-com", "balance/relative-orientation",
    "balance/relative-position", "balance/orientation-left-foot",
    "balance/position-left-foot"
])

# lock hands in closed position
Example #3
0
##
## hpp-wholebody-step-server should be launched
##

from hpp.corbaserver import Client, ProblemSolver
from hpp.corbaserver.wholebody_step import Client as WSClient
from hpp.corbaserver.wholebody_step import Problem
from hpp.corbaserver.hrp2 import Robot
from hpp.gepetto import ViewerFactory


Robot.urdfSuffix = '_capsule'
Robot.srdfSuffix = '_capsule'

robot = Robot ('hrp2')
p = ProblemSolver (robot)
vf = ViewerFactory (p)
wcl = WSClient ()
q0 = robot.getInitialConfig ()

constraintName = "balance"
wcl.problem.addStaticStabilityConstraints (constraintName, q0, robot.leftAnkle,
                                           robot.rightAnkle, "",
                                           Problem.SLIDING)
balanceConstraints = [constraintName + "/relative-com",
                      constraintName + "/relative-orientation",
                      constraintName + "/relative-position",
                      constraintName + "/orientation-left-foot",
                      constraintName + "/position-left-foot"]
c2name = "stability"
wcl.problem.addStabilityConstraints (c2name, q0, robot.leftAnkle,