Beispiel #1
0
    def test_self_load(self):
        hint_list = [self.model_dir]

        model = pin.buildModelFromUrdf(self.model_path,
                                       pin.JointModelFreeFlyer())
        collision_model_ref = pin.buildGeomFromUrdf(model, self.model_path,
                                                    pin.GeometryType.COLLISION,
                                                    hint_list)

        collision_model_self = pin.GeometryModel()
        pin.buildGeomFromUrdf(model, self.model_path,
                              pin.GeometryType.COLLISION, collision_model_self,
                              hint_list)
        self.assertTrue(checkGeom(collision_model_ref, collision_model_self))

        collision_model_self = pin.GeometryModel()
        pin.buildGeomFromUrdf(model, self.model_path,
                              pin.GeometryType.COLLISION, collision_model_self,
                              self.model_dir)
        self.assertTrue(checkGeom(collision_model_ref, collision_model_self))

        hint_vec = pin.StdVec_StdString()
        hint_vec.append(self.model_dir)

        collision_model_self = pin.GeometryModel()
        pin.buildGeomFromUrdf(model, self.model_path,
                              pin.GeometryType.COLLISION, collision_model_self,
                              hint_vec)
        self.assertTrue(checkGeom(collision_model_ref, collision_model_self))
Beispiel #2
0
    def __init__(self, q0, omega, t):
        self.omega = omega
        self.q0 = q0
        self.qdes = q0.copy()
        self.vdes = np.zeros((8, 1))
        self.ades = np.zeros((8, 1))
        self.error = False

        ########################################################################
        #             Definition of the Model and TSID problem                 #
        ########################################################################

        ## Set the paths where the urdf and srdf file of the robot are registered

        modelPath = "/opt/openrobots/lib/python3.5/site-packages/../../../share/example-robot-data/robots"
        urdf = modelPath + "/solo_description/robots/solo.urdf"
        srdf = modelPath + "/solo_description/srdf/solo.srdf"
        vector = pin.StdVec_StdString()
        vector.extend(item for item in modelPath)

        ## Create the robot wrapper from the urdf model (without the free flyer)

        robot = tsid.RobotWrapper(urdf, vector, False)

        self.model = robot.model()
        self.data = robot.data()
Beispiel #3
0
def computeWrench(cs, Robot, dt):
    rp = RosPack()
    urdf = rp.get_path(
        Robot.packageName
    ) + '/urdf/' + Robot.urdfName + Robot.urdfSuffix + '.urdf'
    #srdf = "package://" + package + '/srdf/' +  cfg.Robot.urdfName+cfg.Robot.srdfSuffix + '.srdf'
    robot = RobotWrapper.BuildFromURDF(urdf, pin.StdVec_StdString(),
                                       pin.JointModelFreeFlyer(), False)
    model = robot.model
    data = robot.data
    q_t = cs.concatenateQtrajectories()
    dq_t = cs.concatenateQtrajectories()
    ddq_t = cs.concatenateQtrajectories()
    t = q_t.min()
    for phase in cs.contactPhases:
        phase.wrench_t = None
        t = phase.timeInitial
        while t <= phase.timeFinal:
            pin.rnea(model, data, phase.q_t(t), phase.dq_t(t), phase.ddq_t(t))
            pcom, vcom, acom = robot.com(phase.q_t(t), phase.dq_t(t),
                                         phase.ddq_t(t))
            # FIXME : why do I need to call com to have the correct values in data ??
            phi0 = data.oMi[1].act(pin.Force(data.tau[:6]))
            if phase.wrench_t is None:
                phase.wrench_t = piecewise(
                    polynomial(phi0.vector.reshape(-1, 1), t, t))
            else:
                phase.wrench_t.append(phi0.vector, t)
            t += dt
            if phase.timeFinal - dt / 2. <= t <= phase.timeFinal + dt / 2.:
                t = phase.timeFinal
Beispiel #4
0
    def test_deprecated_signatures(self):
        model = pin.buildModelFromUrdf(self.model_path,
                                       pin.JointModelFreeFlyer())

        hint_list = [self.model_dir, "wrong/hint"]
        collision_model = pin.buildGeomFromUrdf(model, self.model_path,
                                                hint_list,
                                                pin.GeometryType.COLLISION)

        hint_vec = pin.StdVec_StdString()
        hint_vec.append(self.model_dir)
        collision_model = pin.buildGeomFromUrdf(model, self.model_path,
                                                hint_vec,
                                                pin.GeometryType.COLLISION)

        collision_model = pin.buildGeomFromUrdf(model, self.model_path,
                                                self.model_dir,
                                                pin.GeometryType.COLLISION)

        if pin.WITH_HPP_FCL_BINDINGS:
            collision_model = pin.buildGeomFromUrdf(model, self.model_path,
                                                    hint_list,
                                                    pin.GeometryType.COLLISION,
                                                    pin.hppfcl.MeshLoader())
            collision_model = pin.buildGeomFromUrdf(model, self.model_path,
                                                    hint_vec,
                                                    pin.GeometryType.COLLISION,
                                                    pin.hppfcl.MeshLoader())
            collision_model = pin.buildGeomFromUrdf(model, self.model_path,
                                                    self.model_dir,
                                                    pin.GeometryType.COLLISION,
                                                    pin.hppfcl.MeshLoader())
def generate_wholebody_load(cfg, cs, fullBody=None, viewer=None):
    rp = RosPack()
    urdf = rp.get_path(cfg.Robot.packageName) + '/urdf/' + cfg.Robot.urdfName + cfg.Robot.urdfSuffix + '.urdf'
    logger.info("load robot : %s", urdf)
    robot = pin.RobotWrapper.BuildFromURDF(urdf, pin.StdVec_StdString(), pin.JointModelFreeFlyer(), False)
    logger.info("robot loaded.")
    cs_wb = ContactSequence()
    logger.warning("Load wholebody contact sequence from  file : %s", cfg.WB_FILENAME)
    cs_wb.loadFromBinary(cfg.WB_FILENAME)
    return cs_wb, robot
def generateWholeBodyMotion(cs, fullBody=None, viewer=None):
    rp = RosPack()
    urdf = rp.get_path(
        cfg.Robot.packageName
    ) + '/urdf/' + cfg.Robot.urdfName + cfg.Robot.urdfSuffix + '.urdf'
    if cfg.WB_VERBOSE:
        print "load robot : ", urdf
    robot = pin.RobotWrapper.BuildFromURDF(urdf, pin.StdVec_StdString(),
                                           pin.JointModelFreeFlyer(), False)
    if cfg.WB_VERBOSE:
        print "robot loaded."
    filename = cfg.EXPORT_PATH + "/npz/" + cfg.DEMO_NAME + ".npz"
    print "Load npz file : ", filename
    res = wholebody_result.loadFromNPZ(filename)
    return res, robot
Beispiel #7
0
def export(cs_com, cs_wb):
    rp = RosPack()
    urdf = rp.get_path(cfg.Robot.packageName) + '/urdf/' + cfg.Robot.urdfName + cfg.Robot.urdfSuffix + '.urdf'
    if cfg.WB_VERBOSE:
        print("load robot : ", urdf)
    #srdf = "package://" + package + '/srdf/' +  cfg.Robot.urdfName+cfg.Robot.srdfSuffix + '.srdf'
    robot = RobotWrapper.BuildFromURDF(urdf, pin.StdVec_StdString(), pin.JointModelFreeFlyer(), False)
    if cfg.WB_VERBOSE:
        print("robot loaded in export OpenHRP")

    results = computeWaistData(robot, res)
    path = cfg.EXPORT_PATH + "/openHRP/" + cfg.DEMO_NAME
    if not os.path.exists(path):
        os.makedirs(path)
    q_openhrp_l = generateOpenHRPMotion(results, path, cfg.DEMO_NAME, useRefZMP=cfg.openHRP_useZMPref)
    writeKinematicsData(results, path, cfg.DEMO_NAME)
def computeWrench(res):
    rp = RosPack()
    urdf = rp.get_path(
        cfg.Robot.packageName
    ) + '/urdf/' + cfg.Robot.urdfName + cfg.Robot.urdfSuffix + '.urdf'
    #srdf = "package://" + package + '/srdf/' +  cfg.Robot.urdfName+cfg.Robot.srdfSuffix + '.srdf'
    robot = RobotWrapper.BuildFromURDF(urdf, pin.StdVec_StdString(),
                                       pin.JointModelFreeFlyer(), False)
    model = robot.model
    data = robot.data
    for k in range(res.N):
        pin.rnea(model, data, res.q_t[:, k], res.dq_t[:, k], res.ddq_t[:, k])
        pcom, vcom, acom = robot.com(
            res.q_t[:, k], res.dq_t[:, k], res.ddq_t[:, k]
        )  # FIXME : why do I need to call com to have the correct values in data ??
        phi0 = data.oMi[1].act(pin.Force(data.tau[:6]))
        res.wrench_t[:, k] = phi0.vector
    return res
def initScenePinocchio(urdfName,
                       packageName,
                       envName=None,
                       envPackageName="hpp_environments"):
    rp = RosPack()
    urdf = rp.get_path(packageName) + '/urdf/' + urdfName + '.urdf'
    robot = pin.RobotWrapper.BuildFromURDF(urdf, pin.StdVec_StdString(),
                                           pin.JointModelFreeFlyer())
    robot.initDisplay(loadModel=True)
    robot.displayCollisions(False)
    robot.displayVisuals(True)
    robot.display(robot.model.neutralConfiguration)

    cl = gepetto.corbaserver.Client()
    gui = cl.gui
    if envName:
        urdfEnvPath = rp.get_path(envPackageName)
        urdfEnv = urdfEnvPath + '/urdf/' + envName + '.urdf'
        gui.addUrdfObjects(sceneName + "/environments", urdfEnv, urdfEnvPath,
                           True)
    return robot, gui
Beispiel #10
0
def generate_wholebody_tsid(cfg, cs_ref, fullBody=None, viewer=None, robot=None, queue_qt = None):
    """
    Generate the whole body motion corresponding to the given contactSequence
    :param cs: Contact sequence containing the references,
     it will only be modified if the end effector trajectories are not valid.
     New references will be generated and added to the cs
    :param fullBody: Required to compute collision free end effector trajectories
    :param viewer: If provided, and the settings are enabled, display the end effector trajectories and the last step computed
    :param robot: a tsid.RobotWrapper instance. If None, a new one is created from the urdf files defined in cfg
    :param queue_qt: If not None, the joint trajectories are send to this multiprocessing.Queue during computation
        The queue take a tuple: [q_t (a Curve object), ContactPhase (may be None), Bool (True mean that this is the
         last trajectory of the motion)]
    :return: a new ContactSequence object, containing the wholebody trajectories,
    and the other trajectories computed from the wholebody motion request with cfg.IK_STORE_* and a robotWrapper instance
    """

    # define nested functions used in control loop #

    def appendJointsValues(first_iter_for_phase = False):
        """
        Append the current q value to the current phase.q_t trajectory
        :param first_iter_for_phase: if True, set the current phase.q_init value
        and initialize a new Curve for phase.q_t
        """
        if first_iter_for_phase:
            phase.q_init = q
            phase.q_t = piecewise(polynomial(q.reshape(-1,1), t, t))
            #phase.root_t = piecewise_SE3(constantSE3curve(SE3FromConfig(q) ,t))
        else:
            phase.q_t.append(q, t)
            #phase.root_t.append(SE3FromConfig(q), t)
        if queue_qt:
            queue_qt.put([phase.q_t.curve_at_index(phase.q_t.num_curves()-1),
                          phase.dq_t.curve_at_index(phase.dq_t.num_curves()-1),
                          None,
                          False])

    def appendJointsDerivatives(first_iter_for_phase=False):
        """
        Append the current v and dv value to the current phase.dq_t and phase.ddq_t trajectory
        :param first_iter_for_phase: if True, initialize a new Curve for phase.dq_t and phase.ddq_t
        """
        if first_iter_for_phase:
            phase.dq_t = piecewise(polynomial(v.reshape(-1, 1), t, t))
            phase.ddq_t = piecewise(polynomial(dv.reshape(-1, 1), t, t))
        else:
            phase.dq_t.append(v, t)
            phase.ddq_t.append(dv, t)

    def appendTorques(first_iter_for_phase = False):
        """
        Append the current tau value to the current phase.tau_t trajectory
        :param first_iter_for_phase: if True, initialize a new Curve for phase.tau_t
        """
        tau = invdyn.getActuatorForces(sol)
        if first_iter_for_phase:
            phase.tau_t = piecewise(polynomial(tau.reshape(-1,1), t, t))
        else:
            phase.tau_t.append(tau, t)

    def appendCentroidal(first_iter_for_phase = False):
        """
        Compute the values of the CoM position, velocity, acceleration, the anuglar momentum and it's derivative
        from the wholebody data and append them to the current phase trajectories
        :param first_iter_for_phase: if True, set the initial values for the current phase
        and initialize the centroidal trajectories
        """
        pcom, vcom, acom = pinRobot.com(q, v, dv)
        L = pinRobot.centroidalMomentum(q, v).angular
        dL = pin.computeCentroidalMomentumTimeVariation(pinRobot.model, pinRobot.data, q, v, dv).angular
        if first_iter_for_phase:
            phase.c_init = pcom
            phase.dc_init = vcom
            phase.ddc_init = acom
            phase.L_init = L
            phase.dL_init = dL
            phase.c_t = piecewise(polynomial(pcom.reshape(-1,1), t , t))
            phase.dc_t = piecewise(polynomial(vcom.reshape(-1,1), t, t))
            phase.ddc_t = piecewise(polynomial(acom.reshape(-1,1), t, t))
            phase.L_t = piecewise(polynomial(L.reshape(-1,1), t, t))
            phase.dL_t = piecewise(polynomial(dL.reshape(-1,1), t, t))
        else:
            phase.c_t.append(pcom, t)
            phase.dc_t.append(vcom, t)
            phase.ddc_t.append(acom, t)
            phase.L_t.append(L, t)
            phase.dL_t.append(dL, t)

    def appendZMP(first_iter_for_phase = False):
        """
        Compute the zmp from the current wholebody data and append it to the current phase
        :param first_iter_for_phase: if True, initialize a new Curve for phase.zmp_t
        """
        tau = pin.rnea(pinRobot.model, pinRobot.data, q, v, dv)
        # tau without external forces, only used for the 6 first
        # res.tau_t[:6,k_t] = tau[:6]
        phi0 = pinRobot.data.oMi[1].act(Force(tau[:6]))
        wrench = phi0.vector
        zmp = shiftZMPtoFloorAltitude(cs, t, phi0, cfg.Robot)
        if first_iter_for_phase:
            phase.zmp_t = piecewise(polynomial(zmp.reshape(-1,1), t, t))
            phase.wrench_t = piecewise(polynomial(wrench.reshape(-1,1), t, t))
        else:
            phase.zmp_t.append(zmp, t)
            phase.wrench_t.append(wrench, t)

    def appendEffectorsTraj(first_iter_for_phase = False):
        """
        Append the current position of the effectors not in contact to the current phase trajectories
        :param first_iter_for_phase: if True, initialize a new Curve for the phase effector trajectories
        """
        if first_iter_for_phase and phase_prev:
            for eeName in phase_prev.effectorsWithTrajectory():
                if t > phase_prev.effectorTrajectory(eeName).max():
                    placement = getCurrentEffectorPosition(robot, invdyn.data(), eeName)
                    phase_prev.effectorTrajectory(eeName).append(placement, t)

        for eeName in phase.effectorsWithTrajectory():
            placement = getCurrentEffectorPosition(robot, invdyn.data(), eeName)
            if first_iter_for_phase:
                phase.addEffectorTrajectory(eeName, piecewise_SE3(constantSE3curve(placement, t)))
            else:
                phase.effectorTrajectory(eeName).append(placement, t)


    def appendContactForcesTrajs(first_iter_for_phase = False):
        """
        Append the current contact force value to the current phase, for all the effectors in contact
        :param first_iter_for_phase: if True, initialize a new Curve for the phase contact trajectories
        """
        for eeName in phase.effectorsInContact():
            contact = dic_contacts[eeName]
            if invdyn.checkContact(contact.name, sol):
                contact_forces = invdyn.getContactForce(contact.name, sol)
                contact_normal_force = np.array(contact.getNormalForce(contact_forces))
            else:
                logger.warning("invdyn check contact returned false while the reference contact is active !")
                contact_normal_force = np.zeros(1)
                if cfg.Robot.cType == "_3_DOF":
                    contact_forces = np.zeros(3)
                else:
                    contact_forces = np.zeros(12)
            if first_iter_for_phase:
                phase.addContactForceTrajectory(eeName, piecewise(polynomial(contact_forces.reshape(-1,1), t, t)))
                phase.addContactNormalForceTrajectory(eeName, piecewise(polynomial(contact_normal_force.reshape(1,1), t, t)))
            else:
                phase.contactForce(eeName).append(contact_forces, t)
                phase.contactNormalForce(eeName).append(contact_normal_force.reshape(1), t)


    def storeData(first_iter_for_phase = False):
        """
        Append all the required data (selected in the configuration file) to the current ContactPhase
        :param first_iter_for_phase: if True, set the initial values for the current phase
        and correctly initiliaze empty trajectories for this phase
        """
        if cfg.IK_store_joints_derivatives:
            appendJointsDerivatives(first_iter_for_phase)
        appendJointsValues(first_iter_for_phase)
        if cfg.IK_store_joints_torque:
            appendTorques(first_iter_for_phase)
        if cfg.IK_store_centroidal:
            appendCentroidal(first_iter_for_phase)
        if cfg.IK_store_zmp:
            appendZMP(first_iter_for_phase)
        if cfg.IK_store_effector:
            appendEffectorsTraj(first_iter_for_phase)
        if cfg.IK_store_contact_forces:
            appendContactForcesTrajs(first_iter_for_phase)


    def printIntermediate():
        """
        Print the current state: active contacts, tracking errors, computed joint acceleration and velocity
        :return:
        """
        if logger.isEnabledFor(logging.INFO):
            print("Time %.3f" % (t))
            for eeName, contact in dic_contacts.items():
                if invdyn.checkContact(contact.name, sol):
                    f = invdyn.getContactForce(contact.name, sol)
                    print("\tnormal force %s: %.1f" % (contact.name.ljust(20, '.'), contact.getNormalForce(f)))

            print("\ttracking err %s: %.3f" % (comTask.name.ljust(20, '.'), norm(comTask.position_error, 2)))
            for eeName in phase.effectorsWithTrajectory():
                task = dic_effectors_tasks[eeName]
                error = task.position_error
                if cfg.Robot.cType == "_3_DOF":
                    error = error[0:3]
                print("\ttracking err %s: %.3f" % (task.name.ljust(20, '.'), norm(error, 2)))
            print("\t||v||: %.3f\t ||dv||: %.3f" % (norm(v, 2), norm(dv)))

    def checkDiverge():
        """
        Check if either the joint velocity or acceleration is over a treshold or is NaN, and raise an error
        """
        if norm(dv) > 1e6 or norm(v) > 1e6:
            logger.error("!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!")
            logger.error("/!\ ABORT : controler unstable at t = %f  /!\ ", t)
            logger.error("!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!")
            raise ValueError("ABORT : controler unstable at t = " + str(t))
        if math.isnan(norm(dv)) or math.isnan(norm(v)):
            logger.error("!!!!!!    !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!")
            logger.error("/!\ ABORT : nan   at t = %f   /!\ ", t)
            logger.error("!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!")
            raise ValueError("ABORT : controler unstable at t = " + str(t))

    def stopHere():
        """
        Set the current data as final values for the current phase, resize the contact sequence if needed and return
        :return: [The current ContactSequence, the RobotWrapper]
        """
        setPreviousFinalValues(phase_prev, phase, cfg)
        if cfg.WB_ABORT_WHEN_INVALID:
            # cut the sequence up to the last phase
            cs.resize(pid)
            return cs, robot
        elif cfg.WB_RETURN_INVALID:
            # cut the sequence up to the current phase
            cs.resize(pid+1)
            return cs, robot

    ### End of nested functions definitions ###
    if not viewer:
        logger.warning("No viewer linked, cannot display end_effector trajectories.")
    logger.warning("Start TSID ... ")


    # copy the given contact sequence to keep it as reference :
    cs = ContactSequence(cs_ref)
    # delete all the 'reference' trajectories from result (to leave room for the real trajectories stored)
    deleteAllTrajectories(cs)

    # Create a robot wrapper
    if robot is None or cfg.IK_store_centroidal or cfg.IK_store_zmp:
        rp = RosPack()
        package_name = cfg.Robot.packageName.split("/")[0]
        package_path = rp.get_path(package_name)
        urdf = package_path + cfg.Robot.packageName.lstrip(
            package_name) + '/urdf/' + cfg.Robot.urdfName + cfg.Robot.urdfSuffix + '.urdf'
        logger.info("load robot : %s", urdf)
    if robot is None:
        logger.info("load robot : %s", urdf)
        robot = tsid.RobotWrapper(urdf, pin.StdVec_StdString(), pin.JointModelFreeFlyer(), False)
    else:
        logger.info("Use given robot in tsid.")
    logger.info("robot loaded in tsid.")
    if cfg.IK_store_centroidal or cfg.IK_store_zmp:
        logger.info("load pinocchio robot ...")
        # FIXME : tsid robotWrapper don't have all the required methods, only pinocchio have them
        pinRobot = pin.RobotWrapper.BuildFromURDF(urdf, package_path, pin.JointModelFreeFlyer())
        logger.info("pinocchio robot loaded.")

    # get the selected end effector trajectory generation method
    effectorMethod, effectorCanRetry = cfg.get_effector_method()

    # get the selected simulator method
    Simulator = cfg.get_simulator_class()
    simulator = Simulator(cfg.IK_dt, robot.model())

    ### Define initial state of the robot ###
    phase0 = cs.contactPhases[0]
    q = phase0.q_init[:robot.nq].copy()
    if not q.any():
        raise RuntimeError("The contact sequence doesn't contain an initial whole body configuration")
    t = phase0.timeInitial
    if cs_ref.contactPhases[0].dq_t and cs_ref.contactPhases[0].dq_t.min() <= t <= cs_ref.contactPhases[0].dq_t.max():
        v = cs_ref.contactPhases[0].dq_t(t)
    else:
        v = np.zeros(robot.nv)
    logger.debug("V_init used in tsid : %s", v)

    invdyn = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False)
    invdyn.computeProblemData(t, q, v)
    simulator.init(q, v)

    # add initial contacts :
    dic_contacts = {}
    for eeName in cs.contactPhases[0].effectorsInContact():
        # replace the initial contact patch placements if needed to match exactly the current position in the problem:
        updateContactPlacement(cs, 0, eeName,
                               getCurrentEffectorPosition(robot, invdyn.data(), eeName),
                               cfg.Robot.cType == "_6_DOF")
        # create the contacts :
        contact = createContactForEffector(cfg, invdyn, robot, eeName, phase0.contactPatch(eeName), False)
        dic_contacts.update({eeName: contact})

    if cfg.EFF_CHECK_COLLISION:  # initialise object needed to check the motion
        from mlp.utils import check_path
        validator = check_path.PathChecker(fullBody, cfg.CHECK_DT, logger.isEnabledFor(logging.INFO))

    ### Initialize all task used  ###
    logger.info("initialize tasks : ")
    if cfg.w_com > 0. :
        comTask = tsid.TaskComEquality("task-com", robot)
        comTask.setKp(cfg.kp_com * np.ones(3))
        comTask.setKd(2.0 * np.sqrt(cfg.kp_com) * np.ones(3))
        invdyn.addMotionTask(comTask, cfg.w_com, cfg.level_com, 0.0)
    else:
        comTask = None

    if cfg.w_am > 0.:
        amTask = tsid.TaskAMEquality("task-am", robot)
        amTask.setKp(cfg.kp_am * np.array([1., 1., 0.]))
        amTask.setKd(2.0 * np.sqrt(cfg.kp_am * np.array([1., 1., 0.])))
        invdyn.addMotionTask(amTask, cfg.w_am, cfg.level_am, 0.)
    else:
        amTask = None

    if cfg.w_posture > 0.:
        postureTask = tsid.TaskJointPosture("task-joint-posture", robot)
        postureTask.setKp(cfg.kp_posture * cfg.gain_vector)
        postureTask.setKd(2.0 * np.sqrt(cfg.kp_posture * cfg.gain_vector))
        postureTask.setMask(cfg.masks_posture)
        invdyn.addMotionTask(postureTask, cfg.w_posture, cfg.level_posture, 0.0)
        q_ref = cfg.IK_REFERENCE_CONFIG
        samplePosture = tsid.TrajectorySample(q_ref.shape[0] - 7)
        samplePosture.pos(q_ref[7:]) # -7 because we remove the freeflyer part
    else :
        postureTask = None

    if cfg.w_rootOrientation > 0. :
        orientationRootTask = tsid.TaskSE3Equality("task-orientation-root", robot, 'root_joint')
        mask = np.ones(6)
        mask[0:3] = 0
        mask[5] = cfg.YAW_ROT_GAIN
        orientationRootTask.setMask(mask)
        orientationRootTask.setKp(cfg.kp_rootOrientation * mask)
        orientationRootTask.setKd(2.0 * np.sqrt(cfg.kp_rootOrientation * mask))
        invdyn.addMotionTask(orientationRootTask, cfg.w_rootOrientation, cfg.level_rootOrientation, 0.0)
    else:
        orientationRootTask = None

    # init effector task objects :
    usedEffectors = cs.getAllEffectorsInContact()
    dic_effectors_tasks = createEffectorTasksDic(cfg, usedEffectors, robot)

    # Add bounds tasks if required:
    if cfg.w_torque_bounds > 0.:
        tau_max = cfg.scaling_torque_bounds*robot.model().effortLimit[-robot.na:]
        tau_min = -tau_max
        actuationBoundsTask = tsid.TaskActuationBounds("task-actuation-bounds", robot)
        actuationBoundsTask.setBounds(tau_min, tau_max)
        invdyn.addActuationTask(actuationBoundsTask, cfg.w_torque_bounds, 0, 0.0)
    if cfg.w_joint_bounds > 0.:
        jointBoundsTask = tsid.TaskJointBounds("task-joint-bounds", robot, cfg.IK_dt)
        v_max = cfg.scaling_vel_bounds * robot.model().velocityLimit[-robot.na:]
        v_min = -v_max
        print("v_max : ", v_max)
        jointBoundsTask.setVelocityBounds(v_min, v_max)
        invdyn.addMotionTask(jointBoundsTask, cfg.w_joint_bounds, 0, 0.0)

    solver = tsid.SolverHQuadProg("qp solver")
    solver.resize(invdyn.nVar, invdyn.nEq, invdyn.nIn)

    # time check
    dt = cfg.IK_dt
    logger.info("dt : %f", dt)
    logger.info("tsid initialized, start control loop")
    #raw_input("Enter to start the motion (motion displayed as it's computed, may be slower than real-time)")
    time_start = time.time()

    # For each phases, create the necessary task and references trajectories :
    for pid in range(cs.size()):
        logger.info("## for phase : %d", pid)
        logger.info("t = %f", t)
        # phase_ref contains the reference trajectories and should not be modified exept for new effector trajectories
        # when the first ones was not collision free
        phase_ref = cs_ref.contactPhases[pid]
        # phase de not contains trajectories (exept for the end effectors) and should be modified with the new values computed
        phase = cs.contactPhases[pid]
        if pid > 0:
            phase_prev = cs.contactPhases[pid - 1]
        else:
            phase_prev = None
        if pid < cs.size() - 1:
            phase_next = cs.contactPhases[pid + 1]
        else:
            phase_next = None

        time_interval = [phase_ref.timeInitial, phase_ref.timeFinal]

        logger.info("time_interval %s", time_interval)

        # take CoM and AM trajectory from the phase, with their derivatives
        com_traj = [phase_ref.c_t, phase_ref.dc_t, phase_ref.ddc_t]
        am_traj = [phase_ref.L_t, phase_ref.L_t, phase_ref.dL_t]

        # add root's orientation ref from reference config :
        root_traj = phase_ref.root_t


        # add se3 tasks for end effector when required
        for eeName in phase.effectorsWithTrajectory():
                logger.info("add se3 task for %s", eeName)
                task = dic_effectors_tasks[eeName]
                invdyn.addMotionTask(task, cfg.w_eff, cfg.level_eff, 0.)
                adjustEndEffectorTrajectoryIfNeeded(cfg, phase_ref, robot, invdyn.data(), eeName, effectorMethod)
                logger.info("t interval : %s", time_interval)

        # add newly created contacts :
        new_contacts_names = [] # will store the names of the contact tasks created at this phase
        for eeName in usedEffectors:
            if phase_prev and phase_ref.isEffectorInContact(eeName) and not phase_prev.isEffectorInContact(eeName):
                invdyn.removeTask(dic_effectors_tasks[eeName].name, 0.0)  # remove pin task for this contact
                logger.info("remove se3 effector task : %s", dic_effectors_tasks[eeName].name)
                if logger.isEnabledFor(logging.DEBUG):
                    current_placement = getCurrentEffectorPosition(robot, invdyn.data(), eeName)
                    logger.debug("Current   effector placement : %s", current_placement)
                    logger.debug("Reference effector placement : %s", cs.contactPhases[pid].contactPatch(eeName).placement)
                updateContactPlacement(cs, pid, eeName,
                                       getCurrentEffectorPosition(robot, invdyn.data(), eeName),
                                       cfg.Robot.cType == "_6_DOF")
                contact = createContactForEffector(cfg, invdyn, robot, eeName, phase.contactPatch(eeName))
                new_contacts_names += [contact.name]
                dic_contacts.update({eeName: contact})
                logger.info("Create contact for : %s", eeName)

        # start removing the contact that will be broken in the next phase :
        # (This tell the solver that it should start minimizing the contact force on this contact, and ideally get to 0 at the given time)
        for eeName, contact in dic_contacts.items():
            if phase_next and phase.isEffectorInContact(eeName) and not phase_next.isEffectorInContact(eeName):
                transition_time = phase.duration + dt/2.
                logger.info("\nTime %.3f Start breaking contact %s. transition time : %.3f\n",
                            t, contact.name, transition_time)
                exist = invdyn.removeRigidContact(contact.name, transition_time)
                assert exist, "Try to remove a non existing contact !"

        # Remove all effectors not in contact at this phase,
        # This is required as the block above may not remove the contact exactly at the desired time
        # FIXME: why is it required ? Numerical approximation in the transition_time ?
        for eeName, contact in dic_contacts.items():
            if not phase.isEffectorInContact(eeName):
                exist = invdyn.removeRigidContact(contact.name, 0.)
                if exist:
                    logger.warning("Contact "+eeName+" was not remove after the given transition time.")

        if cfg.WB_STOP_AT_EACH_PHASE:
            input('start simulation')

        # save values at the beginning of the current phase
        q_begin = q.copy()
        v_begin = v.copy()
        phase.q_init = q_begin
        if phase_prev:
            phase_prev.q_final = q_begin
        phaseValid = False
        iter_for_phase = -1
        # iterate until a valid motion for this phase is found (ie. collision free and which respect joint-limits)
        while not phaseValid:
            deletePhaseWBtrajectories(phase) # clean previous invalid trajectories
            t = phase.timeInitial
            k_t = 0
            if iter_for_phase >= 0:
                # reset values to their value at the beginning of the current phase
                q = q_begin.copy()
                v = v_begin.copy()
                simulator.q = q
                simulator.v = v
            iter_for_phase += 1
            logger.info("Start computation for phase %d , t = %f, try number :  %d", pid, t, iter_for_phase)
            # loop to generate states (q,v,a) for the current contact phase :
            while t < phase.timeFinal - (dt / 2.):

                # set traj reference for current time :
                # com
                if comTask:
                    sampleCom = curvesToTSID(com_traj,t)
                    comTask.setReference(sampleCom)

                # am
                if amTask:
                    if cfg.IK_trackAM:
                        sampleAM =  curvesToTSID(am_traj,t)
                    else:
                        sampleAM = tsid.TrajectorySample(3)
                    amTask.setReference(sampleAM)


                # posture
                #print "postural task ref : ",samplePosture.pos()
                if postureTask:
                    postureTask.setReference(samplePosture)

                # root orientation :
                if orientationRootTask:
                    sampleRoot = curveSE3toTSID(root_traj,t)
                    orientationRootTask.setReference(sampleRoot)

                # update weight of regularization tasks for the new contacts:
                if len(new_contacts_names) > 0 :
                    # linearly decrease the weight of the tasks for the newly created contacts
                    u_w_force = (t - phase.timeInitial) / (phase.duration * cfg.w_forceRef_time_ratio)
                    if u_w_force <= 1.:
                        current_w_force = cfg.w_forceRef_init * (1. - u_w_force) + cfg.w_forceRef_end * u_w_force
                        for contact_name in new_contacts_names:
                            success = invdyn.updateRigidContactWeights(contact_name, current_w_force)
                            assert success, "Unable to change the weight of the force regularization task for contact "+contact_name

                logger.debug("### references given : ###")
                logger.debug("com  pos : %s", sampleCom.pos())
                logger.debug("com  vel : %s", sampleCom.vel())
                logger.debug("com  acc : %s", sampleCom.acc())
                if amTask:
                    logger.debug("AM   pos : %s", sampleAM.pos())
                    logger.debug("AM   vel : %s", sampleAM.vel())
                logger.debug("root pos : %s", sampleRoot.pos())
                logger.debug("root vel : %s", sampleRoot.vel())

                # end effector (if they exists)
                for eeName, traj in phase_ref.effectorTrajectories().items():
                    sampleEff = curveSE3toTSID(traj,t,True)
                    dic_effectors_tasks[eeName].setReference(sampleEff)
                    logger.debug("effector %s, pos = %s", eeName, sampleEff.pos())
                    logger.debug("effector %s, vel = %s", eeName, sampleEff.vel())

                logger.debug("previous q = %s", q)
                logger.debug("previous v = %s", v)
                # solve HQP for the current time
                HQPData = invdyn.computeProblemData(t, q, v)
                if t < phase.timeInitial + dt:
                    logger.info("final data for phase %d", pid)
                    if logger.isEnabledFor(logging.INFO):
                        HQPData.print_all()
                sol = solver.solve(HQPData)
                dv = invdyn.getAccelerations(sol)

                storeData(k_t == 0)
                q, v = simulator.simulate(dv)
                t += dt
                k_t += 1
                if t >= phase.timeFinal - (dt / 2.):
                    t = phase.timeFinal # avoid numerical imprecisions

                logger.debug("v = %s", v)
                logger.debug("dv = %s", dv)

                if int(t / dt) % cfg.IK_PRINT_N == 0:
                    printIntermediate()
                try:
                    checkDiverge()
                except ValueError:
                    return stopHere()


            # end while t \in phase_t (loop for the current contact phase)
            if len(phase.effectorsWithTrajectory()) > 0 and cfg.EFF_CHECK_COLLISION:
                phaseValid, t_invalid = validator.check_motion(phase.q_t)
                #if iter_for_phase < 3 :# debug only, force limb-rrt
                #    phaseValid = False
                #    t_invalid = (phase.timeInitial + phase.timeFinal) / 2.
                if not phaseValid:
                    if iter_for_phase == 0:
                        # save the first q_t trajectory computed, for limb-rrt
                        first_q_t = phase.q_t
                    logger.warning("Phase %d not valid at t = %f", pid, t_invalid)
                    logger.info("First invalid q : %s", phase.q_t(t_invalid))
                    if t_invalid <= (phase.timeInitial + cfg.EFF_T_PREDEF) \
                            or t_invalid >= (phase.timeFinal - cfg.EFF_T_PREDEF):
                        logger.error("Motion is invalid during predefined phases, cannot change this.")
                        return stopHere()
                    if effectorCanRetry():
                        logger.warning("Try new end effector trajectory.")
                        try:
                            for eeName, ref_traj in phase_ref.effectorTrajectories().items():
                                placement_init = ref_traj.evaluateAsSE3(phase.timeInitial)
                                placement_end = ref_traj.evaluateAsSE3(phase.timeFinal)
                                traj = effectorMethod(cfg, time_interval, placement_init, placement_end,
                                                                   iter_for_phase + 1, first_q_t, phase_prev,
                                                                   phase_ref, phase_next, fullBody, eeName, viewer)
                                # save the new trajectory in the phase with the references
                                phase_ref.addEffectorTrajectory(eeName,traj)
                                if cfg.DISPLAY_ALL_FEET_TRAJ and logger.isEnabledFor(logging.INFO):
                                    color = fullBody.dict_limb_color_traj[eeName]
                                    color[-1] = 0.6 # set small transparency
                                    display_tools.displaySE3Traj(phase_ref.effectorTrajectory(eeName),
                                                       viewer.client.gui,
                                                       viewer.sceneName,
                                                       eeName + "_traj_" + str(pid) + "_" + str(iter_for_phase),
                                                       color,
                                                       [phase.timeInitial, phase.timeFinal],
                                                       fullBody.dict_offset[eeName])
                        except ValueError as e:
                            logging.error("ERROR in generateEndEffectorTraj :", exc_info=e)
                            return stopHere()
                    else:
                        logging.error("End effector method choosen do not allow retries, abort here.")
                        return stopHere()
            else:  # no effector motions, phase always valid (or bypass the check)
                phaseValid = True
                logging.info("Phase %d valid.", pid)
            if phaseValid:
                setPreviousFinalValues(phase_prev, phase, cfg)
                # display the progress by moving the robot at the last configuration computed
                if viewer and cfg.IK_SHOW_PROGRESS:
                    display_tools.displayWBconfig(viewer,q)
        #end while not phaseValid
    # end for all phases
    # store the data of the last point
    phase_prev = phase
    phase = ContactPhase(phase_prev)
    storeData(True)
    setPreviousFinalValues(phase_prev, phase, cfg)
    time_end = time.time() - time_start
    logger.warning("Whole body motion generated in : %f s.", time_end)
    logger.info("\nFinal COM Position  %s", robot.com(invdyn.data()))
    logger.info("Desired COM Position %s", cs.contactPhases[-1].c_final)
    if queue_qt:
        queue_qt.put([phase.q_t.curve_at_index(phase.q_t.num_curves() - 1), None, True])
    return cs, robot
Beispiel #11
0
    def __init__(self, conf, viewer=True):
        self.conf = conf
        vector = se3.StdVec_StdString()
        vector.extend(item for item in conf.path)
        self.robot = tsid.RobotWrapper(conf.urdf, vector, False)
        robot = self.robot
        self.model = model = robot.model()
        try:
            #            q = se3.getNeutralConfiguration(model, conf.srdf, False)
            se3.loadReferenceConfigurations(model, conf.srdf, False)
            q = model.referenceConfigurations['default']
#        q = model.referenceConfigurations["half_sitting"]
        except:
            q = conf.q0
#            q = np.matrix(np.zeros(robot.nv)).T
        v = np.matrix(np.zeros(robot.nv)).T

        assert model.existFrame(conf.ee_frame_name)

        formulation = tsid.InverseDynamicsFormulationAccForce(
            "tsid", robot, False)
        formulation.computeProblemData(0.0, q, v)

        postureTask = tsid.TaskJointPosture("task-posture", robot)
        postureTask.setKp(conf.kp_posture * matlib.ones(robot.nv).T)
        postureTask.setKd(2.0 * np.sqrt(conf.kp_posture) *
                          matlib.ones(robot.nv).T)
        formulation.addMotionTask(postureTask, conf.w_posture, 1, 0.0)

        self.eeTask = tsid.TaskSE3Equality("task-ee", self.robot,
                                           self.conf.ee_frame_name)
        self.eeTask.setKp(self.conf.kp_ee * np.matrix(np.ones(6)).T)
        self.eeTask.setKd(2.0 * np.sqrt(self.conf.kp_ee) *
                          np.matrix(np.ones(6)).T)
        self.eeTask.setMask(conf.ee_task_mask)
        self.eeTask.useLocalFrame(False)
        self.EE = model.getFrameId(conf.ee_frame_name)
        H_ee_ref = self.robot.framePosition(formulation.data(), self.EE)
        self.trajEE = tsid.TrajectorySE3Constant("traj-ee", H_ee_ref)
        formulation.addMotionTask(self.eeTask, conf.w_ee, 1, 0.0)

        self.tau_max = conf.tau_max_scaling * model.effortLimit
        self.tau_min = -self.tau_max
        actuationBoundsTask = tsid.TaskActuationBounds("task-actuation-bounds",
                                                       robot)
        actuationBoundsTask.setBounds(self.tau_min, self.tau_max)
        if (conf.w_torque_bounds > 0.0):
            formulation.addActuationTask(actuationBoundsTask,
                                         conf.w_torque_bounds, 0, 0.0)

        jointBoundsTask = tsid.TaskJointBounds("task-joint-bounds", robot,
                                               conf.dt)
        self.v_max = conf.v_max_scaling * model.velocityLimit
        self.v_min = -self.v_max
        jointBoundsTask.setVelocityBounds(self.v_min, self.v_max)
        if (conf.w_joint_bounds > 0.0):
            formulation.addMotionTask(jointBoundsTask, conf.w_joint_bounds, 0,
                                      0.0)

        trajPosture = tsid.TrajectoryEuclidianConstant("traj_joint", q)
        postureTask.setReference(trajPosture.computeNext())

        solver = tsid.SolverHQuadProgFast("qp solver")
        solver.resize(formulation.nVar, formulation.nEq, formulation.nIn)

        self.trajPosture = trajPosture
        self.postureTask = postureTask
        self.actuationBoundsTask = actuationBoundsTask
        self.jointBoundsTask = jointBoundsTask
        self.formulation = formulation
        self.solver = solver
        self.q = q
        self.v = v

        # for gepetto viewer
        if (viewer):
            self.robot_display = se3.RobotWrapper.BuildFromURDF(
                conf.urdf, [
                    conf.path,
                ])
            l = subprocess.getstatusoutput(
                "ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l")
            if int(l[1]) == 0:
                os.system('gepetto-gui &')
            time.sleep(1)
            gepetto.corbaserver.Client()
            self.robot_display.initViewer(loadModel=True)
            self.robot_display.displayCollisions(False)
            self.robot_display.displayVisuals(True)
            self.robot_display.display(q)
            self.gui = self.robot_display.viewer.gui
            self.gui.setCameraTransform(0, conf.CAMERA_TRANSFORM)
    cs_name = args.cs_name
    if args.env_name:
        env_name = args.env_name

    # Start the gepetto-gui background process
    subprocess.run(["killall", "gepetto-gui"])
    process_viewer = subprocess.Popen("gepetto-gui",
                                      stdout=subprocess.PIPE,
                                      stderr=subprocess.DEVNULL,
                                      preexec_fn=os.setpgrp)
    atexit.register(process_viewer.kill)

    # Load robot model in pinocchio
    rp = RosPack()
    urdf = rp.get_path(robot_package_name) + '/urdf/' + urdf_name + '.urdf'
    robot = pin.RobotWrapper.BuildFromURDF(urdf, pin.StdVec_StdString(),
                                           pin.JointModelFreeFlyer())
    robot.initDisplay(loadModel=True)
    robot.displayCollisions(False)
    robot.displayVisuals(True)

    # Load environment model
    cl = gepetto.corbaserver.Client()
    gui = cl.gui
    env_package_path = rp.get_path(env_package_name)
    env_urdf_path = env_package_path + '/urdf/' + env_name + '.urdf'
    gui.addUrdfObjects(scene_name + "/environments", env_urdf_path, True)

    # Load the motion from the multicontact-api file
    cs = ContactSequence()
    cs.loadFromBinary(cs_name)
	def __init__(self, q0, omega, t):
		
		self.qdes = q0.copy()
		self.vdes = np.zeros((8,1))
		self.ades = np.zeros((8,1))
		self.error = False
		
		kp_posture = 1.0
		w_posture = 10.0
		
		########################################################################
		#             Definition of the Model and TSID problem                 #
		########################################################################
		
		## Set the paths where the urdf and srdf file of the robot are registered

		modelPath = "/opt/openrobots/lib/python3.5/site-packages/../../../share/example-robot-data/robots"
		urdf = modelPath + "/solo_description/robots/solo.urdf"
		srdf = modelPath + "/solo_description/srdf/solo.srdf"
		vector = pin.StdVec_StdString()
		vector.extend(item for item in modelPath)

		## Create the robot wrapper from the urdf model (without the free flyer)

		self.robot = tsid.RobotWrapper(urdf, vector, False)
		
		self.model = self.robot.model()
		
		## Creation of the Invverse Dynamics HQP problem using the robot
		## accelerations (base + joints) and the contact forces

		self.invdyn = tsid.InverseDynamicsFormulationAccForce("tsid", self.robot, False)
		# Compute the problem data with a solver based on EiQuadProg
		self.invdyn.computeProblemData(t, self.qdes, self.vdes)
		# Get the initial data
		self.data = self.invdyn.data()
		
		## Task definition
		
		# POSTURE Task
		self.postureTask = tsid.TaskJointPosture("task-posture", self.robot)
		self.postureTask.setKp(kp_posture * matlib.ones(8).T) # Proportional gain 
		self.postureTask.setKd(2.0 * np.sqrt(kp_posture) * matlib.ones(8).T) # Derivative gain 
		# Add the task to the HQP with weight = w_posture, priority level = 0 (as real constraint) and a transition duration = 0.0
		self.invdyn.addMotionTask(self.postureTask, w_posture, 0, 0.0)

		
		## TSID Trajectory 
		
		pin.loadReferenceConfigurations(self.model, srdf, False)
		
		q_ref = self.model.referenceConfigurations['straight_standing'] 
		trajPosture = tsid.TrajectoryEuclidianConstant("traj_joint", q_ref)
		
		# Set the trajectory as reference for the posture task
		samplePosture = trajPosture.computeNext()
		self.postureTask.setReference(samplePosture)
		
		## Initialization of the solver

		# Use EiquadprogFast solver
		self.solver = tsid.SolverHQuadProgFast("qp solver")
		# Resize the solver to fit the number of variables, equality and inequality constraints
		self.solver.resize(self.invdyn.nVar, self.invdyn.nEq, self.invdyn.nIn)
Beispiel #14
0
    def __init__(self, N_simulation, k_mpc, n_periods):

        self.q_ref = np.array([[0.0, 0.0, 0.2027682, 0.0, 0.0, 0.0, 1.0,
                                0.0, 0.8, -1.6, 0, 0.8, -1.6,
                                0, -0.8, 1.6, 0, -0.8, 1.6]]).transpose()

        self.qtsid = self.q_ref.copy()
        self.vtsid = np.zeros((18, 1))
        self.ades = np.zeros((18, 1))

        self.error = False
        self.verbose = True

        # List with the names of all feet frames
        self.foot_frames = ['FL_FOOT', 'FR_FOOT', 'HL_FOOT', 'HR_FOOT']

        # Constraining the contacts
        mu = 0.9 				# friction coefficient
        fMin = 1.0				# minimum normal force
        fMax = 25.0  			# maximum normal force
        contactNormal = np.matrix([0., 0., 1.]).T  # direction of the normal to the contact surface

        # Coefficients of the posture task
        kp_posture = 10.0		# proportionnal gain of the posture task
        w_posture = 1.0         # weight of the posture task

        # Coefficients of the contact tasks
        kp_contact = 100.0         # proportionnal gain for the contacts
        self.w_forceRef = 50.0  # weight of the forces regularization
        self.w_reg_f = 50.0

        # Coefficients of the foot tracking task
        kp_foot = 100.0               # proportionnal gain for the tracking task
        self.w_foot = 500.0       # weight of the tracking task

        # Arrays to store logs
        k_max_loop = N_simulation
        self.f_pos = np.zeros((4, k_max_loop, 3))
        self.f_vel = np.zeros((4, k_max_loop, 3))
        self.f_acc = np.zeros((4, k_max_loop, 3))
        self.f_pos_ref = np.zeros((4, k_max_loop, 3))
        self.f_vel_ref = np.zeros((4, k_max_loop, 3))
        self.f_acc_ref = np.zeros((4, k_max_loop, 3))
        self.b_pos = np.zeros((k_max_loop, 6))
        self.b_vel = np.zeros((k_max_loop, 6))
        self.com_pos = np.zeros((k_max_loop, 3))
        self.com_pos_ref = np.zeros((k_max_loop, 3))
        self.c_forces = np.zeros((4, k_max_loop, 3))
        self.h_ref_feet = np.zeros((k_max_loop, ))
        self.goals = np.zeros((3, 4))
        self.vgoals = np.zeros((3, 4))
        self.agoals = np.zeros((3, 4))
        self.mgoals = np.zeros((6, 4))

        # Position of the shoulders in local frame
        self.shoulders = np.array([[0.19, 0.19, -0.19, -0.19], [0.15005, -0.15005, 0.15005, -0.15005]])
        self.footsteps = self.shoulders.copy()
        self.memory_contacts = self.shoulders.copy()

        # Foot trajectory generator
        max_height_feet = 0.05
        t_lock_before_touchdown = 0.05
        self.ftgs = [ftg.Foot_trajectory_generator(max_height_feet, t_lock_before_touchdown) for i in range(4)]

        # Which pair of feet is active (0 for [1, 2] and 1 for [0, 3])
        self.pair = -1

        # Number of TSID steps for 1 step of the MPC
        self.k_mpc = k_mpc

        # For update_feet_tasks function
        self.dt = 0.001  #  [s], time step
        self.t1 = 0.14  # [s], duration of swing phase

        # Rotation matrix
        self.R = np.eye(3)

        # Feedforward torques
        self.tau_ff = np.zeros((12, 1))

        # Torques sent to the robot
        self.torques12 = np.zeros((12, 1))
        self.tau = np.zeros((12, ))

        self.ID_base = None  # ID of base link
        self.ID_feet = [None] * 4  # ID of feet links

        # Footstep planner object
        # self.fstep_planner = FootstepPlanner.FootstepPlanner(0.001, 32)
        self.vu_m = np.zeros((6, 1))
        self.t_stance = 0.16
        self.T_gait = 0.32
        self.n_periods = n_periods
        self.h_ref = 0.235 - 0.01205385
        self.t_swing = np.zeros((4, ))  # Total duration of current swing phase for each foot

        self.contacts_order = [0, 1, 2, 3]

        # Parameter to enable/disable hybrid control
        self.enable_hybrid_control = False

        # Time since the start of the simulation
        self.t = 0.0

        ########################################################################
        #             Definition of the Model and TSID problem                 #
        ########################################################################

        # Set the paths where the urdf and srdf file of the robot are registered
        modelPath = "/opt/openrobots/share/example-robot-data/robots"
        urdf = modelPath + "/solo_description/robots/solo12.urdf"
        srdf = modelPath + "/solo_description/srdf/solo.srdf"
        vector = pin.StdVec_StdString()
        vector.extend(item for item in modelPath)

        # Create the robot wrapper from the urdf model (which has no free flyer) and add a free flyer
        self.robot = tsid.RobotWrapper(urdf, vector, pin.JointModelFreeFlyer(), False)
        self.model = self.robot.model()

        # Creation of the Invverse Dynamics HQP problem using the robot
        # accelerations (base + joints) and the contact forces
        self.invdyn = tsid.InverseDynamicsFormulationAccForce("tsid", self.robot, False)

        # Compute the problem data with a solver based on EiQuadProg
        t = 0.0
        self.invdyn.computeProblemData(t, self.qtsid, self.vtsid)

        # Saving IDs for later
        self.ID_base = self.model.getFrameId("base_link")
        for i, name in enumerate(self.foot_frames):
            self.ID_feet[i] = self.model.getFrameId(name)

        # Store a frame object to avoid creating one each time
        self.pos_foot = self.robot.framePosition(self.invdyn.data(), self.ID_feet[0])

        #####################
        # LEGS POSTURE TASK #
        #####################

        # Task definition (creating the task object)
        self.postureTask = tsid.TaskJointPosture("task-posture", self.robot)
        self.postureTask.setKp(kp_posture * matlib.ones(self.robot.nv-6).T)  # Proportional gain
        self.postureTask.setKd(2.0 * np.sqrt(kp_posture) * matlib.ones(self.robot.nv-6).T)  # Derivative gain

        # Add the task to the HQP with weight = w_posture, priority level = 1 (not real constraint)
        # and a transition duration = 0.0
        self.invdyn.addMotionTask(self.postureTask, w_posture, 1, 0.0)

        # TSID Trajectory (creating the trajectory object and linking it to the task)
        pin.loadReferenceConfigurations(self.model, srdf, False)
        self.trajPosture = tsid.TrajectoryEuclidianConstant("traj_joint", self.q_ref[7:])
        self.samplePosture = self.trajPosture.computeNext()
        self.postureTask.setReference(self.samplePosture)

        ############
        # CONTACTS #
        ############

        self.contacts = 4*[None]  # List to store the rigid contact tasks

        for i, name in enumerate(self.foot_frames):

            # Contact definition (creating the contact object)
            self.contacts[i] = tsid.ContactPoint(name, self.robot, name, contactNormal, mu, fMin, fMax)
            self.contacts[i].setKp((kp_contact * matlib.ones(3).T))
            self.contacts[i].setKd((2.0 * np.sqrt(kp_contact) * matlib.ones(3).T))
            self.contacts[i].useLocalFrame(False)

            # Set the contact reference position
            H_ref = self.robot.framePosition(self.invdyn.data(), self.ID_feet[i])
            H_ref.translation = np.matrix(
                [H_ref.translation[0, 0],
                 H_ref.translation[1, 0],
                 0.0]).T
            self.contacts[i].setReference(H_ref)

            # Regularization weight for the force tracking subtask
            self.contacts[i].setRegularizationTaskWeightVector(
                np.matrix([self.w_reg_f, self.w_reg_f, self.w_reg_f]).T)

            # Adding the rigid contact after the reference contact force has been set
            self.invdyn.addRigidContact(self.contacts[i], self.w_forceRef)

        #######################
        # FOOT TRACKING TASKS #
        #######################

        self.feetTask = 4*[None]  # List to store the foot tracking tasks
        mask = np.matrix([1.0, 1.0, 1.0, 0.0, 0.0, 0.0]).T

        # Task definition (creating the task object)
        for i_foot in range(4):
            self.feetTask[i_foot] = tsid.TaskSE3Equality(
                "foot_track_" + str(i_foot), self.robot, self.foot_frames[i_foot])
            self.feetTask[i_foot].setKp(kp_foot * mask)
            self.feetTask[i_foot].setKd(2.0 * np.sqrt(kp_foot) * mask)
            self.feetTask[i_foot].setMask(mask)
            self.feetTask[i_foot].useLocalFrame(False)

        # The reference will be set later when the task is enabled

        ##########
        # SOLVER #
        ##########

        # Use EiquadprogFast solver
        self.solver = tsid.SolverHQuadProgFast("qp solver")

        # Resize the solver to fit the number of variables, equality and inequality constraints
        self.solver.resize(self.invdyn.nVar, self.invdyn.nEq, self.invdyn.nIn)
Beispiel #15
0
    def __init__(self, conf, viewer=True):
        self.conf = conf
        vector = se3.StdVec_StdString()
        vector.extend(item for item in conf.path)
        self.robot = tsid.RobotWrapper(conf.urdf, vector,
                                       se3.JointModelFreeFlyer(), False)
        robot = self.robot
        self.model = robot.model()
        pin.loadReferenceConfigurations(self.model, conf.srdf, False)
        self.q0 = q = self.model.referenceConfigurations["half_sitting"]
        v = np.zeros(robot.nv)

        assert self.model.existFrame(conf.rf_frame_name)
        assert self.model.existFrame(conf.lf_frame_name)

        formulation = tsid.InverseDynamicsFormulationAccForce(
            "tsid", robot, False)
        formulation.computeProblemData(0.0, q, v)
        data = formulation.data()
        contact_Point = np.ones((3, 4)) * conf.lz
        contact_Point[0, :] = [-conf.lxn, -conf.lxn, conf.lxp, conf.lxp]
        contact_Point[1, :] = [-conf.lyn, conf.lyp, -conf.lyn, conf.lyp]

        contactRF = tsid.Contact6d("contact_rfoot", robot, conf.rf_frame_name,
                                   contact_Point, conf.contactNormal, conf.mu,
                                   conf.fMin, conf.fMax)
        contactRF.setKp(conf.kp_contact * np.ones(6))
        contactRF.setKd(2.0 * np.sqrt(conf.kp_contact) * np.ones(6))
        self.RF = robot.model().getJointId(conf.rf_frame_name)
        H_rf_ref = robot.position(data, self.RF)

        # modify initial robot configuration so that foot is on the ground (z=0)
        q[2] -= H_rf_ref.translation[2] - conf.lz
        formulation.computeProblemData(0.0, q, v)
        data = formulation.data()
        H_rf_ref = robot.position(data, self.RF)
        contactRF.setReference(H_rf_ref)
        formulation.addRigidContact(contactRF, conf.w_forceRef)

        contactLF = tsid.Contact6d("contact_lfoot", robot, conf.lf_frame_name,
                                   contact_Point, conf.contactNormal, conf.mu,
                                   conf.fMin, conf.fMax)
        contactLF.setKp(conf.kp_contact * np.ones(6))
        contactLF.setKd(2.0 * np.sqrt(conf.kp_contact) * np.ones(6))
        self.LF = robot.model().getJointId(conf.lf_frame_name)
        H_lf_ref = robot.position(data, self.LF)
        contactLF.setReference(H_lf_ref)
        formulation.addRigidContact(contactLF, conf.w_forceRef)

        comTask = tsid.TaskComEquality("task-com", robot)
        comTask.setKp(conf.kp_com * np.ones(3))
        comTask.setKd(2.0 * np.sqrt(conf.kp_com) * np.ones(3))
        formulation.addMotionTask(comTask, conf.w_com, 1, 0.0)

        postureTask = tsid.TaskJointPosture("task-posture", robot)
        postureTask.setKp(conf.kp_posture * np.ones(robot.nv - 6))
        postureTask.setKd(2.0 * np.sqrt(conf.kp_posture) *
                          np.ones(robot.nv - 6))
        formulation.addMotionTask(postureTask, conf.w_posture, 1, 0.0)

        self.leftFootTask = tsid.TaskSE3Equality("task-left-foot", self.robot,
                                                 self.conf.lf_frame_name)
        self.leftFootTask.setKp(self.conf.kp_foot * np.ones(6))
        self.leftFootTask.setKd(2.0 * np.sqrt(self.conf.kp_foot) * np.ones(6))
        self.trajLF = tsid.TrajectorySE3Constant("traj-left-foot", H_lf_ref)
        formulation.addMotionTask(self.leftFootTask, self.conf.w_foot, 1, 0.0)

        self.rightFootTask = tsid.TaskSE3Equality("task-right-foot",
                                                  self.robot,
                                                  self.conf.rf_frame_name)
        self.rightFootTask.setKp(self.conf.kp_foot * np.ones(6))
        self.rightFootTask.setKd(2.0 * np.sqrt(self.conf.kp_foot) * np.ones(6))
        self.trajRF = tsid.TrajectorySE3Constant("traj-right-foot", H_rf_ref)
        formulation.addMotionTask(self.rightFootTask, self.conf.w_foot, 1, 0.0)

        self.tau_max = conf.tau_max_scaling * robot.model(
        ).effortLimit[-robot.na:]
        self.tau_min = -self.tau_max
        actuationBoundsTask = tsid.TaskActuationBounds("task-actuation-bounds",
                                                       robot)
        actuationBoundsTask.setBounds(self.tau_min, self.tau_max)
        if (conf.w_torque_bounds > 0.0):
            formulation.addActuationTask(actuationBoundsTask,
                                         conf.w_torque_bounds, 0, 0.0)

        jointBoundsTask = tsid.TaskJointBounds("task-joint-bounds", robot,
                                               conf.dt)
        self.v_max = conf.v_max_scaling * robot.model(
        ).velocityLimit[-robot.na:]
        self.v_min = -self.v_max
        jointBoundsTask.setVelocityBounds(self.v_min, self.v_max)
        if (conf.w_joint_bounds > 0.0):
            formulation.addMotionTask(jointBoundsTask, conf.w_joint_bounds, 0,
                                      0.0)

        com_ref = robot.com(data)
        self.trajCom = tsid.TrajectoryEuclidianConstant("traj_com", com_ref)
        self.sample_com = self.trajCom.computeNext()

        q_ref = q[7:]
        self.trajPosture = tsid.TrajectoryEuclidianConstant(
            "traj_joint", q_ref)
        postureTask.setReference(self.trajPosture.computeNext())

        self.sampleLF = self.trajLF.computeNext()
        self.sample_LF_pos = self.sampleLF.pos()
        self.sample_LF_vel = self.sampleLF.vel()
        self.sample_LF_acc = self.sampleLF.acc()

        self.sampleRF = self.trajRF.computeNext()
        self.sample_RF_pos = self.sampleRF.pos()
        self.sample_RF_vel = self.sampleRF.vel()
        self.sample_RF_acc = self.sampleRF.acc()

        self.solver = tsid.SolverHQuadProgFast("qp solver")
        self.solver.resize(formulation.nVar, formulation.nEq, formulation.nIn)

        self.comTask = comTask
        self.postureTask = postureTask
        self.contactRF = contactRF
        self.contactLF = contactLF
        self.actuationBoundsTask = actuationBoundsTask
        self.jointBoundsTask = jointBoundsTask
        self.formulation = formulation
        self.q = q
        self.v = v

        self.contact_LF_active = True
        self.contact_RF_active = True

        # for gepetto viewer
        if (viewer):
            self.robot_display = se3.RobotWrapper.BuildFromURDF(
                conf.urdf, [
                    conf.path,
                ], se3.JointModelFreeFlyer())
            l = subprocess.getstatusoutput(
                "ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l")
            if int(l[1]) == 0:
                os.system('gepetto-gui &')
            time.sleep(1)
            gepetto.corbaserver.Client()
            self.robot_display.initViewer(loadModel=True)
            self.robot_display.displayCollisions(False)
            self.robot_display.displayVisuals(True)
            self.robot_display.display(q)

            self.gui = self.robot_display.viewer.gui
            #            self.gui.setCameraTransform(0, conf.CAMERA_TRANSFORM)
            self.gui.addFloor('world/floor')
            self.gui.setLightingMode('world/floor', 'OFF')
Beispiel #16
0
    def __init__(self):

        ########################################################################
        #             Definition of the Model and TSID problem                 #
        ########################################################################

        # set the path
        path = "/opt/openrobots/share/example-robot-data/robots/solo_description/robots"
        urdf = path + "/solo12.urdf"
        srdf = "/opt/openrobots/share/example-robot-data/robots/solo_description/srdf/solo.srdf"
        vec = pin.StdVec_StdString()
        vec.extend(item for item in path)

        # get the solo12 wrapper
        self.solo12_wrapper = tsid.RobotWrapper(urdf, vec,
                                                pin.JointModelFreeFlyer(),
                                                False)
        self.solo12_model = self.solo12_wrapper.model()
        pin.loadReferenceConfigurations(self.solo12_model, srdf, False)

        # problem formulation
        self.formulation = tsid.InverseDynamicsFormulationAccForce(
            "tsid", self.solo12_wrapper, False)
        self.q0 = self.solo12_model.referenceConfigurations[
            "straight_standing"]
        self.v0 = np.zeros(self.solo12_model.nv)
        self.formulation.computeProblemData(0.0, self.q0, self.v0)
        self.data = self.formulation.data()

        # get frame ID
        self.ID_FL = self.solo12_model.getFrameId("FL_FOOT")
        self.ID_FR = self.solo12_model.getFrameId("FR_FOOT")
        self.ID_HL = self.solo12_model.getFrameId("HL_FOOT")
        self.ID_HR = self.solo12_model.getFrameId("HR_FOOT")
        self.ID_BASE = self.solo12_model.getFrameId("base_link")

        ############
        # COM TASK #
        ############
        self.kp_com = 50
        self.w_com = 3
        self.comTask = tsid.TaskComEquality("task-com", self.solo12_wrapper)
        self.comTask.setKp(self.kp_com * np.ones(3).T)
        self.comTask.setKd(2 * np.sqrt(self.kp_com) * np.ones(3).T)
        self.formulation.addMotionTask(self.comTask, self.w_com, 1, 0.0)
        self.com_ref = self.solo12_wrapper.com(self.data)
        self.trajCom = tsid.TrajectoryEuclidianConstant(
            "traj-com", self.com_ref)

        #################
        # SE3 BASE TASK #
        #################
        self.kp_trunk = 50
        self.w_trunk = 1
        self.trunkTask = tsid.TaskSE3Equality("task-trunk",
                                              self.solo12_wrapper, 'base_link')
        mask = np.matrix([1.0, 1.0, 0.0, 1.0, 1.0, 1.0]).T
        self.trunkTask.setKp(
            np.matrix([
                self.kp_trunk, self.kp_trunk, 0.0, self.kp_trunk,
                self.kp_trunk, self.kp_trunk
            ]).T)
        self.trunkTask.setKd(
            np.matrix([
                2.0 * np.sqrt(self.kp_trunk), 2.0 * np.sqrt(self.kp_trunk),
                0.0, 2.0 * np.sqrt(self.kp_trunk),
                2.0 * np.sqrt(self.kp_trunk), 2.0 * np.sqrt(self.kp_trunk)
            ]).T)
        self.trunkTask.useLocalFrame(False)
        self.trunkTask.setMask(mask)
        self.formulation.addMotionTask(self.trunkTask, self.w_trunk, 1, 0.0)
        self.trunk_ref = self.solo12_wrapper.framePosition(
            self.data, self.ID_BASE)
        self.trajTrunk = tsid.TrajectorySE3Constant("traj_base_link",
                                                    self.trunk_ref)

        ##################
        # CONTACT FORCES #
        ##################

        self.contactNormal = np.array([0, 0, 1])
        self.kp_contact = 30
        self.mu = 0.5

        self.contactFL = tsid.ContactPoint("contactFL", self.solo12_wrapper,
                                           "FL_FOOT", self.contactNormal,
                                           self.mu, 1, 1000)
        self.contactFL.setKp(self.kp_contact * np.ones(6).T)
        self.contactFL.setKd(2 * np.sqrt(self.kp_contact) * np.ones(6).T)
        self.fl_ref = self.solo12_wrapper.framePosition(self.data, self.ID_FL)
        self.contactFL.setReference(self.fl_ref)
        self.formulation.addRigidContact(self.contactFL, 10)

        self.contactFR = tsid.ContactPoint("contactFR", self.solo12_wrapper,
                                           "FR_FOOT", self.contactNormal,
                                           self.mu, 1, 1000)
        self.contactFR.setKp(self.kp_contact * np.ones(6).T)
        self.contactFR.setKd(2 * np.sqrt(self.kp_contact) * np.ones(6).T)
        self.fr_ref = self.solo12_wrapper.framePosition(self.data, self.ID_FR)
        self.contactFR.setReference(self.fr_ref)
        self.formulation.addRigidContact(self.contactFR, 10)

        self.contactHR = tsid.ContactPoint("contactHR", self.solo12_wrapper,
                                           "HR_FOOT", self.contactNormal,
                                           self.mu, 1, 1000)
        self.contactHR.setKp(self.kp_contact * np.ones(6).T)
        self.contactHR.setKd(2 * np.sqrt(self.kp_contact) * np.ones(6).T)
        self.hr_ref = self.solo12_wrapper.framePosition(self.data, self.ID_HR)
        self.contactHR.setReference(self.hr_ref)
        self.formulation.addRigidContact(self.contactHR, 10)

        self.contactHL = tsid.ContactPoint("contactHL", self.solo12_wrapper,
                                           "HL_FOOT", self.contactNormal,
                                           self.mu, 1, 1000)
        self.contactHL.setKp(self.kp_contact * np.ones(6).T)
        self.contactHL.setKd(2 * np.sqrt(self.kp_contact) * np.ones(6).T)
        self.hl_ref = self.solo12_wrapper.framePosition(self.data, self.ID_HL)
        self.contactHL.setReference(self.hl_ref)
        self.formulation.addRigidContact(self.contactHL, 10)

        ##########
        # SOLVER #
        ##########

        self.solver = tsid.SolverHQuadProgFast("qp solver")
        self.solver.resize(self.formulation.nVar, self.formulation.nEq,
                           self.formulation.nIn)
Beispiel #17
0
    def __init__(self, conf, dt, urdf, modelPath, srdf):
        self.conf = conf
        self.dt = dt
        vector = pin.StdVec_StdString()
        vector.extend(item for item in modelPath)
        self.robot = tsid.RobotWrapper(urdf, vector, pin.JointModelFreeFlyer(),
                                       False)
        robot = self.robot
        self.model = robot.model()
        pin.loadReferenceConfigurations(self.model, srdf, False)
        try:
            self.q0 = conf.q0
            q = np.copy(conf.q0)
        except:
            self.q0 = self.model.referenceConfigurations["half_sitting"]
            q = np.copy(self.q0)
        self.v0 = v = np.zeros(robot.nv)

        assert self.model.existFrame(conf.rf_frame_name)
        assert self.model.existFrame(conf.lf_frame_name)

        formulation = tsid.InverseDynamicsFormulationAccForce(
            "tsid", robot, False)
        formulation.computeProblemData(0.0, q, v)
        data = formulation.data()
        contact_Point = np.ones((3, 4)) * conf.lz
        contact_Point[0, :] = [-conf.lxn, -conf.lxn, conf.lxp, conf.lxp]
        contact_Point[1, :] = [-conf.lyn, conf.lyp, -conf.lyn, conf.lyp]

        contactRF = tsid.Contact6d("contact_rfoot", robot, conf.rf_frame_name,
                                   contact_Point, conf.contact_normal, conf.mu,
                                   conf.fMin, conf.fMax)
        contactRF.setKp(conf.kp_contact * np.ones(6))
        contactRF.setKd(2.0 * np.sqrt(conf.kp_contact) * np.ones(6))
        self.RF = robot.model().getFrameId(conf.rf_frame_name)
        H_rf_ref = robot.framePosition(formulation.data(), self.RF)
        #        print('H RF\n', H_rf_ref.translation)

        # modify initial robot configuration so that foot is on the ground (z=0)
        q[2] -= H_rf_ref.translation[2] + conf.lz
        formulation.computeProblemData(0.0, q, v)
        data = formulation.data()
        H_rf_ref = robot.framePosition(data, self.RF)
        #        print('H RF\n', H_rf_ref)
        contactRF.setReference(H_rf_ref)
        if (conf.w_contact >= 0.0):
            formulation.addRigidContact(contactRF, conf.w_forceRef,
                                        conf.w_contact, 1)
        else:
            formulation.addRigidContact(contactRF, conf.w_forceRef)

        contactLF = tsid.Contact6d("contact_lfoot", robot, conf.lf_frame_name,
                                   contact_Point, conf.contact_normal, conf.mu,
                                   conf.fMin, conf.fMax)
        contactLF.setKp(conf.kp_contact * np.ones(6))
        contactLF.setKd(2.0 * np.sqrt(conf.kp_contact) * np.ones(6))
        self.LF = robot.model().getFrameId(conf.lf_frame_name)
        H_lf_ref = robot.framePosition(formulation.data(), self.LF)
        #        print('H LF\n', H_lf_ref)
        contactLF.setReference(H_lf_ref)
        if (conf.w_contact >= 0.0):
            formulation.addRigidContact(contactLF, conf.w_forceRef,
                                        conf.w_contact, 1)
        else:
            formulation.addRigidContact(contactLF, conf.w_forceRef)

        comTask = tsid.TaskComEquality("task-com", robot)
        comTask.setKp(conf.kp_com * np.ones(3))
        comTask.setKd(2.0 * np.sqrt(conf.kp_com) * np.ones(3))
        if (conf.w_com > 0):
            formulation.addMotionTask(comTask, conf.w_com, 1, 0.0)

        postureTask = tsid.TaskJointPosture("task-posture", robot)
        try:
            postureTask.setKp(conf.kp_posture)
            postureTask.setKd(2.0 * np.sqrt(conf.kp_posture))
        except:
            postureTask.setKp(conf.kp_posture * np.ones(robot.nv - 6))
            postureTask.setKd(2.0 * np.sqrt(conf.kp_posture) *
                              np.ones(robot.nv - 6))
        if (conf.w_posture > 0):
            formulation.addMotionTask(postureTask, conf.w_posture, 1, 0.0)

        self.leftFootTask = tsid.TaskSE3Equality("task-left-foot", self.robot,
                                                 self.conf.lf_frame_name)
        self.leftFootTask.setKp(self.conf.kp_foot * np.ones(6))
        self.leftFootTask.setKd(2.0 * np.sqrt(self.conf.kp_foot) * np.ones(6))
        self.trajLF = tsid.TrajectorySE3Constant("traj-left-foot", H_lf_ref)
        if (conf.w_foot > 0):
            formulation.addMotionTask(self.leftFootTask, self.conf.w_foot, 1,
                                      0.0)
#
        self.rightFootTask = tsid.TaskSE3Equality("task-right-foot",
                                                  self.robot,
                                                  self.conf.rf_frame_name)
        self.rightFootTask.setKp(self.conf.kp_foot * np.ones(6))
        self.rightFootTask.setKd(2.0 * np.sqrt(self.conf.kp_foot) * np.ones(6))
        self.trajRF = tsid.TrajectorySE3Constant("traj-right-foot", H_rf_ref)
        if (conf.w_foot > 0):
            formulation.addMotionTask(self.rightFootTask, self.conf.w_foot, 1,
                                      0.0)

        self.waistTask = tsid.TaskSE3Equality("task-waist", self.robot,
                                              self.conf.waist_frame_name)
        self.waistTask.setKp(self.conf.kp_waist * np.ones(6))
        self.waistTask.setKd(2.0 * np.sqrt(self.conf.kp_waist) * np.ones(6))
        self.waistTask.setMask(np.array([0, 0, 0, 1, 1, 1.]))
        waistID = robot.model().getFrameId(conf.waist_frame_name)
        H_waist_ref = robot.framePosition(formulation.data(), waistID)
        self.trajWaist = tsid.TrajectorySE3Constant("traj-waist", H_waist_ref)
        if (conf.w_waist > 0):
            formulation.addMotionTask(self.waistTask, self.conf.w_waist, 1,
                                      0.0)

        self.tau_max = conf.tau_max_scaling * robot.model(
        ).effortLimit[-robot.na:]
        self.tau_min = -self.tau_max
        actuationBoundsTask = tsid.TaskActuationBounds("task-actuation-bounds",
                                                       robot)
        actuationBoundsTask.setBounds(self.tau_min, self.tau_max)
        if (conf.w_torque_bounds > 0.0):
            formulation.addActuationTask(actuationBoundsTask,
                                         conf.w_torque_bounds, 0, 0.0)

        jointBoundsTask = tsid.TaskJointBounds("task-joint-bounds", robot, dt)
        self.v_max = conf.v_max_scaling * robot.model(
        ).velocityLimit[-robot.na:]
        self.v_min = -self.v_max
        jointBoundsTask.setVelocityBounds(self.v_min, self.v_max)
        if (conf.w_joint_bounds > 0.0):
            formulation.addMotionTask(jointBoundsTask, conf.w_joint_bounds, 0,
                                      0.0)

        com_ref = robot.com(formulation.data())
        self.trajCom = tsid.TrajectoryEuclidianConstant("traj_com", com_ref)
        self.sample_com = self.trajCom.computeNext()

        q_ref = q[7:]
        self.trajPosture = tsid.TrajectoryEuclidianConstant(
            "traj_joint", q_ref)
        postureTask.setReference(self.trajPosture.computeNext())

        self.sampleLF = self.trajLF.computeNext()
        self.sample_LF_pos = self.sampleLF.pos()
        self.sample_LF_vel = self.sampleLF.vel()
        self.sample_LF_acc = self.sampleLF.acc()

        self.sampleRF = self.trajRF.computeNext()
        self.sample_RF_pos = self.sampleRF.pos()
        self.sample_RF_vel = self.sampleRF.vel()
        self.sample_RF_acc = self.sampleRF.acc()

        self.solver = tsid.SolverHQuadProgFast("qp solver")
        self.solver.resize(formulation.nVar, formulation.nEq, formulation.nIn)

        self.comTask = comTask
        self.postureTask = postureTask
        self.contactRF = contactRF
        self.contactLF = contactLF
        self.actuationBoundsTask = actuationBoundsTask
        self.jointBoundsTask = jointBoundsTask
        self.formulation = formulation
        self.q = q
        self.v = v
        self.q0 = np.copy(self.q)

        self.contact_LF_active = True
        self.contact_RF_active = True

        #        self.reset()

        data = np.load(conf.DATA_FILE_TSID)
        # assume dt>dt_ref
        r = int(dt / conf.dt_ref)

        self.N = int(data['com'].shape[1] / r)

        self.contact_phase = data['contact_phase'][::r]
        self.com_pos_ref = np.asarray(data['com'])[:, ::r]
        self.com_vel_ref = np.asarray(data['dcom'])[:, ::r]
        self.com_acc_ref = np.asarray(data['ddcom'])[:, ::r]
        self.x_RF_ref = np.asarray(data['x_RF'])[:, ::r]
        self.dx_RF_ref = np.asarray(data['dx_RF'])[:, ::r]
        self.ddx_RF_ref = np.asarray(data['ddx_RF'])[:, ::r]
        self.x_LF_ref = np.asarray(data['x_LF'])[:, ::r]
        self.dx_LF_ref = np.asarray(data['dx_LF'])[:, ::r]
        self.ddx_LF_ref = np.asarray(data['ddx_LF'])[:, ::r]
        self.cop_ref = np.asarray(data['cop'])[:, ::r]

        x_rf = self.get_placement_RF().translation
        offset = x_rf - self.x_RF_ref[:, 0]
        #        print("offset", offset)
        for i in range(self.N):
            self.com_pos_ref[:, i] += offset
            self.x_RF_ref[:, i] += offset
            self.x_LF_ref[:, i] += offset
Beispiel #18
0
w_forceRef = 1e-3	# weight of force regularization task

kp_posture = 10.0  	# proportionnal gain of the posture task
kp_foot = 1000.0		# proportionnal gain of the feet tasks

N_SIMULATION = 10000	# number of time steps simulated
dt = 0.001			# controller time step



## Set the path where the urdf and srdf file of the robot is registered

modelPath = "/opt/openrobots/lib/python2.7/site-packages/../../../share/example-robot-data"
urdf = modelPath + "/solo_description/robots/solo12.urdf"
srdf = modelPath + "/solo_description/srdf/solo.srdf"
vector = pin.StdVec_StdString()
vector.extend(item for item in modelPath)
# Create the robot wrapper from the urdf model
robot = tsid.RobotWrapper(urdf, vector, pin.JointModelFreeFlyer(), False)


## Creation of the robot wrapper for the Gepetto Viewer

robot_display = pin.RobotWrapper.BuildFromURDF(urdf, [modelPath, ], pin.JointModelFreeFlyer())
robot_display.initViewer(loadModel=True)


## Take the model of the robot and load its reference configuration

model = robot.model()
pin.loadReferenceConfigurations(model, srdf, False)
def mcapi_playback(name_interface):
    """Main function that calibrates the robot, get it into a default waiting position then launch
    the main control loop once the user has pressed the Enter key

    Args:
        name_interface (string): name of the interface that is used to communicate with the robot
    """

    if SIMULATION:
        device = PyBulletSimulator()
        qc = None
    else:
        device = Solo12(name_interface, dt=DT)
        qc = QualisysClient(ip="140.93.16.160", body_id=0)

    if LOGGING:
        logger = Logger(device, qualisys=qc)

    # Number of motors
    nb_motors = device.nb_motors
    q_viewer = np.array((7 + nb_motors) * [
        0.,
    ])

    # Gepetto-gui
    v = viewerClient()
    v.display(q_viewer)

    # PyBullet GUI
    enable_pyb_GUI = True

    # Maximum duration of the demonstration
    t_max = 300.0

    # Default position after calibration
    q_init = np.array([0, 0.8, -1.6, 0, 0.8, -1.6, 0, -0.8, 1.6, 0, -0.8, 1.6])

    # Create Estimator object
    estimator = Estimator(DT, np.int(t_max / DT))

    # Set the paths where the urdf and srdf file of the robot are registered
    modelPath = "/opt/openrobots/share/example-robot-data/robots"
    urdf = modelPath + "/solo_description/robots/solo12.urdf"
    vector = pin.StdVec_StdString()
    vector.extend(item for item in modelPath)

    # Create the robot wrapper from the urdf model (which has no free flyer) and add a free flyer
    robot = tsid.RobotWrapper(urdf, vector, pin.JointModelFreeFlyer(), False)
    model = robot.model()

    # Creation of the Invverse Dynamics HQP problem using the robot
    # accelerations (base + joints) and the contact forces
    invdyn = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False)

    # Compute the problem data with a solver based on EiQuadProg
    invdyn.computeProblemData(0.0, np.hstack((np.zeros(7), q_init)),
                              np.zeros(18))

    # Initiate communication with the device and calibrate encoders
    if SIMULATION:
        device.Init(calibrateEncoders=True,
                    q_init=q_init,
                    envID=0,
                    use_flat_plane=True,
                    enable_pyb_GUI=enable_pyb_GUI,
                    dt=DT)
    else:
        device.Init(calibrateEncoders=True, q_init=q_init)

        # Wait for Enter input before starting the control loop
        put_on_the_floor(device, q_init)

    # CONTROL LOOP ***************************************************
    t = 0.0
    k = 0

    while ((not device.hardware.IsTimeout()) and (t < t_max)):

        device.UpdateMeasurment()  # Retrieve data from IMU and Motion capture

        # Run estimator with hind left leg touching the ground
        estimator.run_filter(k, np.array([0, 0, 1, 0]), device, invdyn.data(),
                             model)

        # Zero desired torques
        tau = np.zeros(12)

        # Set desired torques for the actuators
        device.SetDesiredJointTorque(tau)

        # Call logger
        if LOGGING:
            logger.sample(device, qualisys=qc, estimator=estimator)

        # Send command to the robot
        device.SendCommand(WaitEndOfCycle=True)
        if ((device.cpt % 100) == 0):
            device.Print()

        # Gepetto GUI
        if k > 0:
            pos = np.array(estimator.data.oMf[26].translation).ravel()
            q_viewer[0:3] = np.array([-pos[0], -pos[1],
                                      estimator.FK_h])  # Position
            q_viewer[3:7] = estimator.q_FK[3:7, 0]  # Orientation
            q_viewer[7:] = estimator.q_FK[7:, 0]  # Encoders
            v.display(q_viewer)

        t += DT
        k += 1

    # ****************************************************************

    # Whatever happened we send 0 torques to the motors.
    device.SetDesiredJointTorque([0] * nb_motors)
    device.SendCommand(WaitEndOfCycle=True)

    if device.hardware.IsTimeout():
        print("Masterboard timeout detected.")
        print(
            "Either the masterboard has been shut down or there has been a connection issue with the cable/wifi."
        )
    # Shut down the interface between the computer and the master board
    device.hardware.Stop()

    # Save the logs of the Logger object
    if LOGGING:
        logger.saveAll()

    if SIMULATION and enable_pyb_GUI:
        # Disconnect the PyBullet server (also close the GUI)
        device.Stop()

    print("End of script")
    quit()
    def __init__(self, q0, omega, t):

        self.omega = omega
        self.qdes = q0.copy()
        self.vdes = np.zeros((18, 1))
        self.ades = np.zeros((18, 1))
        self.error = False

        kp_posture = 10.0  # proportionnal gain of the posture task
        w_posture = 1.0  # weight of the posture task

        kp_com = 100.0  # proportionnal gain of the CoM task
        w_com = 100.0  # weight of the CoM task

        kp_lock = 1.0  # proportionnal gain of the lock task
        w_lock = 100.0  # weight of the lock task

        # For the contacts
        mu = 0.3  # friction coefficient
        fMin = 1.0  # minimum normal force
        fMax = 100.0  # maximum normal force

        w_forceRef = 1e-3  # weight of the forces regularization
        kp_contact = 1.0  # proportionnal gain for the contacts

        foot_frames = ['HL_FOOT', 'HR_FOOT', 'FL_FOOT',
                       'FR_FOOT']  # tab with all the foot frames names
        contactNormal = np.matrix(
            [0., 0., 1.]).T  # direction of the normal to the contact surface

        ########################################################################
        #             Definition of the Model and TSID problem                 #
        ########################################################################

        ## Set the paths where the urdf and srdf file of the robot are registered

        modelPath = "/opt/openrobots/lib/python3.5/site-packages/../../../share/example-robot-data/robots"
        urdf = modelPath + "/solo_description/robots/solo12.urdf"
        srdf = modelPath + "/solo_description/srdf/solo.srdf"
        vector = pin.StdVec_StdString()
        vector.extend(item for item in modelPath)

        ## Create the robot wrapper from the urdf model (without the free flyer)

        self.robot = tsid.RobotWrapper(urdf, vector, pin.JointModelFreeFlyer(),
                                       False)

        self.model = self.robot.model()

        ## Creation of the Invverse Dynamics HQP problem using the robot
        ## accelerations (base + joints) and the contact forces

        self.invdyn = tsid.InverseDynamicsFormulationAccForce(
            "tsid", self.robot, False)
        # Compute the problem data with a solver based on EiQuadProg
        self.invdyn.computeProblemData(t, self.qdes, self.vdes)
        # Get the initial data
        self.data = self.invdyn.data()

        ## Task definition

        # POSTURE Task
        self.postureTask = tsid.TaskJointPosture("task-posture", self.robot)
        self.postureTask.setKp(
            kp_posture * matlib.ones(self.robot.nv - 6).T)  # Proportional gain
        self.postureTask.setKd(
            2.0 * np.sqrt(kp_posture) *
            matlib.ones(self.robot.nv - 6).T)  # Derivative gain
        # Add the task to the HQP with weight = w_posture, priority level = 0 (as real constraint) and a transition duration = 0.0
        self.invdyn.addMotionTask(self.postureTask, w_posture, 1, 0.0)

        # COM Task
        self.comTask = tsid.TaskComEquality("task-com", self.robot)
        self.comTask.setKp(
            kp_com * matlib.ones(3).T)  # Proportional gain of the CoM task
        self.comTask.setKd(2.0 * np.sqrt(kp_com) *
                           matlib.ones(3).T)  # Derivative gain
        self.invdyn.addMotionTask(
            self.comTask, w_com, 1, 0.0
        )  # Add the task to the HQP with weight = w_com, priority level = 1 (in the cost function) and a transition duration = 0.0

        # LOCK Task
        self.lockTask = tsid.TaskJointPosture("task-lock-shoulder", self.robot)
        self.lockTask.setKp(kp_lock * matlib.ones(self.robot.nv - 6).T)
        self.lockTask.setKd(2.0 * np.sqrt(kp_lock) *
                            matlib.ones(self.robot.nv - 6).T)
        mask = np.matrix(np.zeros(
            self.robot.nv -
            6))  # Add a mask to take into account only the shoulders joints
        for i in [0, 3, 6, 9]:
            mask[0, i] = 1
        self.lockTask.mask(mask.T)
        self.invdyn.addMotionTask(
            self.lockTask, w_lock, 0,
            0.0)  # Add the task as real constraint (priority level = 0)

        ## CONTACTS

        self.contacts = 4 * [None]

        for i, name in enumerate(foot_frames):
            self.contacts[i] = tsid.ContactPoint(name, self.robot, name,
                                                 contactNormal, mu, fMin, fMax)
            self.contacts[i].setKp(kp_contact * matlib.ones(3).T)
            self.contacts[i].setKd(2.0 * np.sqrt(kp_contact) *
                                   matlib.ones(3).T)
            H_ref = self.robot.framePosition(self.data,
                                             self.model.getFrameId(name))
            self.contacts[i].setReference(H_ref)
            self.contacts[i].useLocalFrame(False)
            self.invdyn.addRigidContact(self.contacts[i], w_forceRef, 1.0, 1)

        ## TSID Trajectory

        # POSTURE Task
        pin.loadReferenceConfigurations(self.model, srdf, False)

        self.q_ref = self.model.referenceConfigurations['straight_standing']
        self.trajPosture = tsid.TrajectoryEuclidianConstant(
            "traj_joint", self.q_ref[7:])
        # Set the trajectory as reference for the posture task
        self.samplePosture = self.trajPosture.computeNext()
        self.postureTask.setReference(self.samplePosture)

        # COM Task
        self.com_ref = self.data.com[0].copy()  # Initial value of the CoM
        self.trajCom = tsid.TrajectoryEuclidianConstant(
            "traj_com", self.com_ref)

        self.sampleCom = self.trajCom.computeNext()
        self.comTask.setReference(self.sampleCom)

        # LOCK Task
        # The mask is enough to set the shoulder acceleration to 0 because 0 is the initial configuration for the shoulders
        trajLock = tsid.TrajectoryEuclidianConstant("traj_lock_shoulder",
                                                    self.q_ref[7:])

        sampleLock = trajLock.computeNext()
        self.lockTask.setReference(sampleLock)

        ## Initialization of the solver

        # Use EiquadprogFast solver
        self.solver = tsid.SolverHQuadProgFast("qp solver")
        # Resize the solver to fit the number of variables, equality and inequality constraints
        self.solver.resize(self.invdyn.nVar, self.invdyn.nEq, self.invdyn.nIn)
Beispiel #21
0
    def __init__(self, conf, viewer=True):
        self.conf = conf
        self.contact_frame_names = conf.contact_frame_names
        print('Robot files:')
        print(conf.urdf)
        print(conf.srdf)
        vector = pin.StdVec_StdString()
        vector.extend(item for item in conf.path)
        self.robot = tsid.RobotWrapper(conf.urdf, vector,
                                       pin.JointModelFreeFlyer(), False)
        robot = self.robot
        self.model = robot.model()

        pin.loadReferenceConfigurations(self.model, conf.srdf, False)
        self.q0 = q = self.model.referenceConfigurations[
            conf.reference_config_q_name]
        v = np.zeros(robot.nv)

        assert (all([
            self.model.existFrame(frame_name)
            for frame_name in self.contact_frame_names
        ]))

        invdyn = tsid.InverseDynamicsFormulationAccForce('tsid', robot, False)
        invdyn.computeProblemData(0.0, q, v)
        data = invdyn.data()

        robot.computeAllTerms(data, q, v)

        #####################################
        # define contact and associated tasks
        #####################################

        self.contact_frame_ids = [
            self.model.getFrameId(frame_name)
            for frame_name in self.contact_frame_names
        ]
        self.nc = len(self.contact_frame_ids)  # contact number

        self.contacts = self.nc * [None]
        self.tasks_tracking_foot = self.nc * [None]
        self.traj_feet = self.nc * [None]
        self.sample_feet = self.nc * [None]
        mask = np.ones(6)
        if not conf.contact6d:
            mask[3:] = 0
        for i_foot, (frame_name, fid) in enumerate(
                zip(self.contact_frame_names, self.contact_frame_ids)):
            Hf_ref = robot.framePosition(data, fid)

            if conf.contact6d:
                # DEFINE FOOT CONTACT POINTS LOCATION WRT LOCAL FOOT FRAMES
                # contact_points = np.ones((3,4)) * conf.lz
                contact_points = -np.ones((3, 4)) * conf.lz
                contact_points[0, :] = [
                    -conf.lxn, -conf.lxn, conf.lxp, conf.lxp
                ]
                contact_points[1, :] = [
                    -conf.lyn, conf.lyp, -conf.lyn, conf.lyp
                ]

                # RIGID CONTACT RIGHT FOOT
                self.contacts[i_foot] = tsid.Contact6d(
                    'contact_{}'.format(frame_name), robot, frame_name,
                    contact_points, conf.contactNormal, conf.mu, conf.fMin,
                    conf.fMax)
                self.contacts[i_foot].setKp(conf.kp_contact * np.ones(6).T)
                self.contacts[i_foot].setKd(2.0 * np.sqrt(conf.kp_contact) *
                                            np.ones(6).T)
                self.contacts[i_foot].setReference(Hf_ref)
                invdyn.addRigidContact(self.contacts[i_foot], conf.w_forceRef)

            else:
                # RIGID POINT CONTACTS
                self.contacts[i_foot] = tsid.ContactPoint(
                    'contact_{}'.format(frame_name), robot, frame_name,
                    conf.contactNormal, conf.mu, conf.fMin, conf.fMax)
                self.contacts[i_foot].setKp(conf.kp_contact * np.ones(3))
                self.contacts[i_foot].setKd(2.0 * np.sqrt(conf.kp_contact) *
                                            np.ones(3))
                self.contacts[i_foot].setReference(Hf_ref)
                self.contacts[i_foot].useLocalFrame(conf.useLocalFrame)
                invdyn.addRigidContact(self.contacts[i_foot], conf.w_forceRef)

            # FEET TRACKING TASKS
            self.tasks_tracking_foot[i_foot] = tsid.TaskSE3Equality(
                'task-foot{}'.format(i_foot), self.robot,
                self.contact_frame_names[i_foot])
            self.tasks_tracking_foot[i_foot].setKp(conf.kp_foot * mask)
            self.tasks_tracking_foot[i_foot].setKd(
                2.0 * np.sqrt(conf.kp_foot) * mask)
            self.tasks_tracking_foot[i_foot].setMask(mask)
            self.tasks_tracking_foot[i_foot].useLocalFrame(False)
            invdyn.addMotionTask(self.tasks_tracking_foot[i_foot], conf.w_foot,
                                 conf.priority_foot, 0.0)

            self.traj_feet[i_foot] = tsid.TrajectorySE3Constant(
                'traj-foot{}'.format(i_foot), Hf_ref)
            self.sample_feet[i_foot] = self.traj_feet[i_foot].computeNext()

        #############
        # Other tasks
        #############

        # COM TASK
        self.comTask = tsid.TaskComEquality('task-com', robot)
        self.comTask.setKp(conf.kp_com * np.ones(3))
        self.comTask.setKd(2.0 * np.sqrt(conf.kp_com) * np.ones(3))
        invdyn.addMotionTask(self.comTask, conf.w_com, conf.priority_com, 1.0)

        # POSTURE TASK
        self.postureTask = tsid.TaskJointPosture('task-posture', robot)
        self.postureTask.setKp(conf.kp_posture * np.ones(robot.nv - 6))
        self.postureTask.setKd(2.0 * np.sqrt(conf.kp_posture) *
                               np.ones(robot.nv - 6))
        invdyn.addMotionTask(self.postureTask, conf.w_posture,
                             conf.priority_posture, 0.0)

        # TRUNK Task
        self.trunkTask = tsid.TaskSE3Equality("keepTrunk", robot, 'root_joint')
        self.trunkTask.setKp(conf.kp_trunk * np.ones(6))
        self.trunkTask.setKd(2.0 * np.sqrt(conf.kp_trunk) * np.ones(6))
        # Add a Mask to the task which will select the vector dimensions on which the task will act.
        # In this case the trunk configuration is a vector 6d (position and orientation -> SE3)
        # Here we set a mask = [0 0 0 1 1 1] so the task on the trunk will act on the orientation of the robot
        mask = np.ones(6)
        mask[:3] = 0.
        self.trunkTask.useLocalFrame(False)
        self.trunkTask.setMask(mask)
        invdyn.addMotionTask(self.trunkTask, conf.w_trunk, conf.priority_trunk,
                             0.0)

        # TORQUE BOUND TASK
        # self.tau_max = conf.tau_max_scaling*robot.model().effortLimit[-robot.na:]
        # self.tau_min = -self.tau_max
        # actuationBoundsTask = tsid.TaskActuationBounds('task-actuation-bounds', robot)
        # actuationBoundsTask.setBounds(self.tau_min, self.tau_max)
        # if(conf.w_torque_bounds>0.0):
        #     invdyn.addActuationTask(actuationBoundsTask, conf.w_torque_bounds, conf.priority_torque_bounds, 0.0)

        # JOINT BOUND TASK
        # jointBoundsTask = tsid.TaskJointBounds('task-joint-bounds', robot, conf.dt)
        # self.v_max = conf.v_max_scaling * robot.model().velocityLimit[-robot.na:]
        # self.v_min = -self.v_max
        # jointBoundsTask.setVelocityBounds(self.v_min, self.v_max)
        # if(conf.w_joint_bounds>0.0):
        #     invdyn.addMotionTask(jointBoundsTask, conf.w_joint_bounds, conf.priority_joint_bounds, 0.0)

        ##################################
        # Init task reference trajectories
        ##################################

        self.sample_feet = self.nc * [None]
        self.sample_feet_pos = self.nc * [None]
        self.sample_feet_vel = self.nc * [None]
        self.sample_feet_acc = self.nc * [None]
        for i_foot, traj in enumerate(self.traj_feet):
            self.sample_feet[i_foot] = traj.computeNext()
            self.sample_feet_pos[i_foot] = self.sample_feet[i_foot].pos()
            self.sample_feet_vel[i_foot] = self.sample_feet[i_foot].vel()
            self.sample_feet_acc[i_foot] = self.sample_feet[i_foot].acc()

        com_ref = robot.com(data)
        self.trajCom = tsid.TrajectoryEuclidianConstant('traj_com', com_ref)
        self.sample_com = self.trajCom.computeNext()

        q_ref = q[7:]
        self.trajPosture = tsid.TrajectoryEuclidianConstant(
            'traj_joint', q_ref)
        self.postureTask.setReference(self.trajPosture.computeNext())

        self.trunk_link_id = self.model.getFrameId('base_link')
        R_trunk_init = robot.framePosition(data, self.trunk_link_id).rotation
        self.trunk_ref = self.robot.framePosition(data, self.trunk_link_id)
        self.trajTrunk = tsid.TrajectorySE3Constant("traj_base_link",
                                                    self.trunk_ref)
        self.sample_trunk = self.trajTrunk.computeNext()
        pos_trunk = np.hstack([np.zeros(3), R_trunk_init.flatten()])
        self.sample_trunk.pos()
        self.sample_trunk.vel(np.zeros(6))
        self.sample_trunk.acc(np.zeros(6))
        self.trunkTask.setReference(self.sample_trunk)

        self.solver = tsid.SolverHQuadProgFast('qp solver')
        self.solver.resize(invdyn.nVar, invdyn.nEq, invdyn.nIn)

        self.invdyn = invdyn
        self.q = q
        self.v = v

        self.active_contacts = self.nc * [True]

        # for gepetto viewer
        if (viewer):
            self.robot_display = pin.RobotWrapper.BuildFromURDF(
                conf.urdf, [
                    conf.path,
                ], pin.JointModelFreeFlyer())
            l = subprocess.getstatusoutput(
                "ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l")
            if int(l[1]) == 0:
                os.system('gepetto-gui &')
            time.sleep(1)
            gepetto.corbaserver.Client()
            self.robot_display.initViewer(loadModel=True)
            self.robot_display.displayCollisions(False)
            self.robot_display.displayVisuals(True)
            self.robot_display.display(q)

            self.gui = self.robot_display.viewer.gui
            self.gui.setCameraTransform('python-pinocchio',
                                        conf.CAMERA_TRANSFORM)
            self.gui.addFloor('world/floor')
            self.gui.setLightingMode('world/floor', 'OFF')

            self.gui.addSphere('world/com', conf.SPHERE_RADIUS,
                               conf.COM_SPHERE_COLOR)
            self.gui.addSphere('world/com_ref', conf.REF_SPHERE_RADIUS,
                               conf.COM_REF_SPHERE_COLOR)
            for frame_name in self.contact_frame_names:
                self.gui.addSphere('world/{}'.format(frame_name),
                                   conf.SPHERE_RADIUS, conf.F_SPHERE_COLOR)
                self.gui.addSphere('world/{}_ref'.format(frame_name),
                                   conf.REF_SPHERE_RADIUS,
                                   conf.F_REF_SPHERE_COLOR)
Beispiel #22
0
	def __init__(self, q0, omega, t):
		
		self.omega = omega
		self.qdes = q0.copy()
		self.vdes = np.zeros((8,1))
		self.ades = np.zeros((8,1))
		self.error = False
		
		kp_foot = 10.0
		w_foot = 10.0
		
		
		########################################################################
		#             Definition of the Model and TSID problem                 #
		########################################################################
		
		## Set the paths where the urdf and srdf file of the robot are registered

		modelPath = "/opt/openrobots/lib/python3.5/site-packages/../../../share/example-robot-data/robots"
		urdf = modelPath + "/solo_description/robots/solo.urdf"
		srdf = modelPath + "/solo_description/srdf/solo.srdf"
		vector = pin.StdVec_StdString()
		vector.extend(item for item in modelPath)

		## Create the robot wrapper from the urdf model (without the free flyer)

		self.robot = tsid.RobotWrapper(urdf, vector, False)
		
		self.model = self.robot.model()
		
		## Creation of the Invverse Dynamics HQP problem using the robot
		## accelerations (base + joints) and the contact forces

		self.invdyn = tsid.InverseDynamicsFormulationAccForce("tsid", self.robot, False)
		# Compute the problem data with a solver based on EiQuadProg
		self.invdyn.computeProblemData(t, self.qdes, self.vdes)
		# Get the initial data
		self.data = self.invdyn.data()
		
		# Task definition
		self.FRfootTask = tsid.TaskSE3Equality("FR-foot-placement", self.robot, 'FR_FOOT')
		self.FRfootTask.setKp(kp_foot * matlib.ones(6).T)
		self.FRfootTask.setKd(2.0 * np.sqrt(kp_foot) * matlib.ones(6).T)
		self.FRfootTask.setMask(np.matrix([[1,0,1, 0,0,0]]).T) #set a mask allowing only the transation upon x and z-axis
		self.FRfootTask.useLocalFrame(False)
		# Add the task to the HQP with weight = w_foot, priority level = 0 (as real constraint) and a transition duration = 0.0
		self.invdyn.addMotionTask(self.FRfootTask, w_foot, 1, 0.0)
		
		
		## TSID Trajectory 
		
		pin.forwardKinematics(self.model, self.data, self.qdes)
		pin.updateFramePlacements(self.model, self.data)
	
		self.FR_foot_ref = self.robot.framePosition(self.data, self.model.getFrameId('FR_FOOT'))
		
		FRgoalx = self.FR_foot_ref.translation[0,0] + 0.1 
		FRgoalz = self.FR_foot_ref.translation[2,0] + 0.1
		
		self.FR_foot_goal = self.FR_foot_ref.copy()
		self.FR_foot_goal.translation = np.matrix([FRgoalx, self.FR_foot_ref.translation[1,0], FRgoalz]).T
		
		self.trajFRfoot = tsid.TrajectorySE3Constant("traj_FR_foot", self.FR_foot_goal)
		
		# Set the trajectory as reference for the foot positionning task
		self.sampleFoot = self.trajFRfoot.computeNext()
		self.FRfootTask.setReference(self.sampleFoot)
		
		## Initialization of the solver

		# Use EiquadprogFast solver
		self.solver = tsid.SolverHQuadProgFast("qp solver")
		# Resize the solver to fit the number of variables, equality and inequality constraints
		self.solver.resize(self.invdyn.nVar, self.invdyn.nEq, self.invdyn.nIn)
Beispiel #23
0
kp_com = 30.0                   # proportional gain of center of mass task
kp_posture = 30.0               # proportional gain of joint posture task
kp_RF = 30.0                    # proportional gain of right foot motion task
REMOVE_CONTACT_N = 100          # remove right foot contact constraint after REMOVE_CONTACT_N time steps
CONTACT_TRANSITION_TIME = 1.0   # duration of the contact transition (to smoothly get a zero contact force before removing a contact constraint)
DELTA_COM_Y = 0.1               # distance between initial and desired center of mass position in y direction
DELTA_FOOT_Z = 0.1              # desired elevation of right foot in z direction
dt = 0.001                      # controller time step
PRINT_N = 500                   # print every PRINT_N time steps
DISPLAY_N = 25                  # update robot configuration in viwewer every DISPLAY_N time steps
N_SIMULATION = 4000             # number of time steps simulated

filename = str(os.path.dirname(os.path.abspath(__file__)))
path = filename + '/../models/romeo'
urdf = path + '/urdf/romeo.urdf'
vector = se3.StdVec_StdString()
vector.extend(item for item in path)
robot = tsid.RobotWrapper(urdf, vector, se3.JointModelFreeFlyer(), False)
srdf = path + '/srdf/romeo_collision.srdf'

# for gepetto viewer .. but Fix me!!
robot_display = se3.RobotWrapper(urdf, [path, ], se3.JointModelFreeFlyer())

l = commands.getstatusoutput("ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l")
if int(l[1]) == 0:
    os.system('gepetto-gui &')
time.sleep(1)
cl = gepetto.corbaserver.Client()
gui = cl.gui
robot_display.initDisplay(loadModel=True)
def generateWholeBodyMotion(cs, fullBody=None, viewer=None):
    if not viewer:
        print "No viewer linked, cannot display end_effector trajectories."
    print "Start TSID ... "

    rp = RosPack()
    urdf = rp.get_path(
        cfg.Robot.packageName
    ) + '/urdf/' + cfg.Robot.urdfName + cfg.Robot.urdfSuffix + '.urdf'
    if cfg.WB_VERBOSE:
        print "load robot : ", urdf
    #srdf = "package://" + package + '/srdf/' +  cfg.Robot.urdfName+cfg.Robot.srdfSuffix + '.srdf'
    robot = tsid.RobotWrapper(urdf, pin.StdVec_StdString(),
                              pin.JointModelFreeFlyer(), False)
    if cfg.WB_VERBOSE:
        print "robot loaded in tsid."
    # FIXME : tsid robotWrapper don't have all the required methods, only pinocchio have them
    pinRobot = pin.RobotWrapper.BuildFromURDF(urdf, pin.StdVec_StdString(),
                                              pin.JointModelFreeFlyer(), False)

    q = cs.contact_phases[0].reference_configurations[0][:robot.nq].copy()
    v = np.matrix(np.zeros(robot.nv)).transpose()
    t = 0.0  # time
    # init states list with initial state (assume joint velocity is null for t=0)
    invdyn = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False)
    invdyn.computeProblemData(t, q, v)
    data = invdyn.data()

    if cfg.EFF_CHECK_COLLISION:  # initialise object needed to check the motion
        from mlp.utils import check_path
        validator = check_path.PathChecker(fullBody, cs, len(q),
                                           cfg.WB_VERBOSE)

    if cfg.WB_VERBOSE:
        print "initialize tasks : "
    comTask = tsid.TaskComEquality("task-com", robot)
    comTask.setKp(cfg.kp_com * np.matrix(np.ones(3)).transpose())
    comTask.setKd(2.0 * np.sqrt(cfg.kp_com) *
                  np.matrix(np.ones(3)).transpose())
    invdyn.addMotionTask(comTask, cfg.w_com, cfg.level_com, 0.0)

    com_ref = robot.com(invdyn.data())
    trajCom = tsid.TrajectoryEuclidianConstant("traj_com", com_ref)

    amTask = tsid.TaskAMEquality("task-am", robot)
    amTask.setKp(cfg.kp_am * np.matrix([1., 1., 0.]).T)
    amTask.setKd(2.0 * np.sqrt(cfg.kp_am * np.matrix([1., 1., 0.]).T))
    invdyn.addTask(amTask, cfg.w_am, cfg.level_am)
    trajAM = tsid.TrajectoryEuclidianConstant("traj_am",
                                              np.matrix(np.zeros(3)).T)

    postureTask = tsid.TaskJointPosture("task-joint-posture", robot)
    postureTask.setKp(cfg.kp_posture * cfg.gain_vector)
    postureTask.setKd(2.0 * np.sqrt(cfg.kp_posture * cfg.gain_vector))
    postureTask.mask(cfg.masks_posture)
    invdyn.addMotionTask(postureTask, cfg.w_posture, cfg.level_posture, 0.0)
    q_ref = cfg.IK_REFERENCE_CONFIG
    trajPosture = tsid.TrajectoryEuclidianConstant("traj_joint", q_ref[7:])

    orientationRootTask = tsid.TaskSE3Equality("task-orientation-root", robot,
                                               'root_joint')
    mask = np.matrix(np.ones(6)).transpose()
    mask[0:3] = 0
    mask[5] = cfg.YAW_ROT_GAIN
    orientationRootTask.setKp(cfg.kp_rootOrientation * mask)
    orientationRootTask.setKd(2.0 * np.sqrt(cfg.kp_rootOrientation * mask))
    invdyn.addMotionTask(orientationRootTask, cfg.w_rootOrientation,
                         cfg.level_rootOrientation, 0.0)
    root_ref = robot.position(data, robot.model().getJointId('root_joint'))
    trajRoot = tsid.TrajectorySE3Constant("traj-root", root_ref)

    usedEffectors = []
    for eeName in cfg.Robot.dict_limb_joint.values():
        if isContactEverActive(cs, eeName):
            usedEffectors.append(eeName)
    # init effector task objects :
    dic_effectors_tasks = createEffectorTasksDic(cs, robot)
    effectorTraj = tsid.TrajectorySE3Constant(
        "traj-effector", SE3.Identity()
    )  # trajectory doesn't matter as it's only used to get the correct struct and size

    # init empty dic to store effectors trajectories :
    dic_effectors_trajs = {}
    for eeName in usedEffectors:
        dic_effectors_trajs.update({eeName: None})

    # add initial contacts :
    dic_contacts = {}
    for eeName in usedEffectors:
        if isContactActive(cs.contact_phases[0], eeName):
            contact = createContactForEffector(invdyn, robot,
                                               cs.contact_phases[0], eeName)
            dic_contacts.update({eeName: contact})

    if cfg.PLOT:  # init a dict storing all the reference trajectories used (for plotting)
        stored_effectors_ref = {}
        for eeName in dic_effectors_tasks:
            stored_effectors_ref.update({eeName: []})

    solver = tsid.SolverHQuadProg("qp solver")
    solver.resize(invdyn.nVar, invdyn.nEq, invdyn.nIn)

    # define nested function used in control loop
    def storeData(k_t, res, q, v, dv, invdyn, sol):
        # store current state
        res.q_t[:, k_t] = q
        res.dq_t[:, k_t] = v
        res.ddq_t[:, k_t] = dv
        res.tau_t[:, k_t] = invdyn.getActuatorForces(
            sol)  # actuator forces, with external forces (contact forces)
        #store contact info (force and status)
        if cfg.IK_store_contact_forces:
            for eeName, contact in dic_contacts.iteritems():
                if invdyn.checkContact(contact.name, sol):
                    res.contact_forces[eeName][:,
                                               k_t] = invdyn.getContactForce(
                                                   contact.name, sol)
                    res.contact_normal_force[
                        eeName][:, k_t] = contact.getNormalForce(
                            res.contact_forces[eeName][:, k_t])
                    res.contact_activity[eeName][:, k_t] = 1
        # store centroidal info (real one and reference) :
        if cfg.IK_store_centroidal:
            pcom, vcom, acom = pinRobot.com(q, v, dv)
            res.c_t[:, k_t] = pcom
            res.dc_t[:, k_t] = vcom
            res.ddc_t[:, k_t] = acom
            res.L_t[:, k_t] = pinRobot.centroidalMomentum(q, v).angular
            #res.dL_t[:,k_t] = pinRobot.centroidalMomentumVariation(q,v,dv) # FIXME : in robot wrapper, use * instead of .dot() for np matrices
            pin.dccrba(pinRobot.model, pinRobot.data, q, v)
            res.dL_t[:, k_t] = Force(
                pinRobot.data.Ag.dot(dv) + pinRobot.data.dAg.dot(v)).angular
            # same for reference data :
            res.c_reference[:, k_t] = com_desired
            res.dc_reference[:, k_t] = vcom_desired
            res.ddc_reference[:, k_t] = acom_desired
            res.L_reference[:, k_t] = L_desired
            res.dL_reference[:, k_t] = dL_desired
            if cfg.IK_store_zmp:
                tau = pin.rnea(
                    pinRobot.model, pinRobot.data, q, v, dv
                )  # tau without external forces, only used for the 6 first
                #res.tau_t[:6,k_t] = tau[:6]
                phi0 = pinRobot.data.oMi[1].act(Force(tau[:6]))
                res.wrench_t[:, k_t] = phi0.vector
                res.zmp_t[:, k_t] = shiftZMPtoFloorAltitude(
                    cs, res.t_t[k_t], phi0, cfg.EXPORT_OPENHRP)
                # same but from the 'reference' values :
                Mcom = SE3.Identity()
                Mcom.translation = com_desired
                Fcom = Force.Zero()
                Fcom.linear = cfg.MASS * (acom_desired - cfg.GRAVITY)
                Fcom.angular = dL_desired
                F0 = Mcom.act(Fcom)
                res.wrench_reference[:, k_t] = F0.vector
                res.zmp_reference[:, k_t] = shiftZMPtoFloorAltitude(
                    cs, res.t_t[k_t], F0, cfg.EXPORT_OPENHRP)
        if cfg.IK_store_effector:
            for eeName in usedEffectors:  # real position (not reference)
                res.effector_trajectories[eeName][:, k_t] = SE3toVec(
                    getCurrentEffectorPosition(robot, invdyn.data(), eeName))
                res.d_effector_trajectories[eeName][:, k_t] = MotiontoVec(
                    getCurrentEffectorVelocity(robot, invdyn.data(), eeName))
                res.dd_effector_trajectories[eeName][:, k_t] = MotiontoVec(
                    getCurrentEffectorAcceleration(robot, invdyn.data(),
                                                   eeName))

        return res

    def printIntermediate(v, dv, invdyn, sol):
        print "Time %.3f" % (t)
        for eeName, contact in dic_contacts.iteritems():
            if invdyn.checkContact(contact.name, sol):
                f = invdyn.getContactForce(contact.name, sol)
                print "\tnormal force %s: %.1f" % (contact.name.ljust(
                    20, '.'), contact.getNormalForce(f))

        print "\ttracking err %s: %.3f" % (comTask.name.ljust(
            20, '.'), norm(comTask.position_error, 2))
        for eeName, traj in dic_effectors_trajs.iteritems():
            if traj:
                task = dic_effectors_tasks[eeName]
                error = task.position_error
                if cfg.Robot.cType == "_3_DOF":
                    error = error[0:3]
                print "\ttracking err %s: %.3f" % (task.name.ljust(
                    20, '.'), norm(error, 2))
        print "\t||v||: %.3f\t ||dv||: %.3f" % (norm(v, 2), norm(dv))

    def checkDiverge(res, v, dv):
        if norm(dv) > 1e6 or norm(v) > 1e6:
            print "!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!"
            print "/!\ ABORT : controler unstable at t = " + str(t) + "  /!\ "
            print "!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!"
            raise ValueError("ABORT : controler unstable at t = " + str(t))
        if math.isnan(norm(dv)) or math.isnan(norm(v)):
            print "!!!!!!    !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!"
            print "/!\ ABORT : nan   at t = " + str(t) + "  /!\ "
            print "!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!"
            raise ValueError("ABORT : controler unstable at t = " + str(t))

    def stopHere():
        if cfg.WB_ABORT_WHEN_INVALID:
            return res.resize(phase_interval[0]), pinRobot
        elif cfg.WB_RETURN_INVALID:
            return res.resize(k_t), pinRobot

    # time check
    dt = cfg.IK_dt
    if cfg.WB_VERBOSE:
        print "dt : ", dt
    res = Result(robot.nq, robot.nv, cfg.IK_dt, eeNames=usedEffectors, cs=cs)
    N = res.N
    last_display = 0
    if cfg.WB_VERBOSE:
        print "tsid initialized, start control loop"
        #raw_input("Enter to start the motion (motion displayed as it's computed, may be slower than real-time)")
    time_start = time.time()

    # For each phases, create the necessary task and references trajectories :
    for pid in range(cs.size()):
        if cfg.WB_VERBOSE:
            print "## for phase : ", pid
            print "t = ", t
        phase = cs.contact_phases[pid]
        if pid < cs.size() - 1:
            phase_next = cs.contact_phases[pid + 1]
        else:
            phase_next = None
        if pid > 0:
            phase_prev = cs.contact_phases[pid - 1]
        else:
            phase_prev = None
        t_phase_begin = res.phases_intervals[pid][0] * dt
        t_phase_end = res.phases_intervals[pid][-1] * dt
        time_interval = [t_phase_begin, t_phase_end]
        if cfg.WB_VERBOSE:
            print "time_interval ", time_interval
        # generate com ref traj from phase :
        com_init = np.matrix(np.zeros((9, 1)))
        com_init[0:3, 0] = robot.com(invdyn.data())
        com_traj = computeCOMRefFromPhase(phase, time_interval)

        am_traj = computeAMRefFromPhase(phase, time_interval)
        # add root's orientation ref from reference config :
        if cfg.USE_PLANNING_ROOT_ORIENTATION:
            if phase_next:
                root_traj = trajectories.TrajectorySE3LinearInterp(
                    SE3FromConfig(phase.reference_configurations[0]),
                    SE3FromConfig(phase_next.reference_configurations[0]),
                    time_interval)
            else:
                root_traj = trajectories.TrajectorySE3LinearInterp(
                    SE3FromConfig(phase.reference_configurations[0]),
                    SE3FromConfig(phase.reference_configurations[0]),
                    time_interval)
        else:
            # orientation such that the torso orientation is the mean between both feet yaw rotations:
            placement_init, placement_end = rootOrientationFromFeetPlacement(
                phase, phase_next)
            root_traj = trajectories.TrajectorySE3LinearInterp(
                placement_init, placement_end, time_interval)
        # add newly created contacts :
        for eeName in usedEffectors:
            if phase_prev and not isContactActive(
                    phase_prev, eeName) and isContactActive(phase, eeName):
                invdyn.removeTask(dic_effectors_tasks[eeName].name,
                                  0.0)  # remove pin task for this contact
                dic_effectors_trajs.update(
                    {eeName:
                     None})  # delete reference trajectory for this task
                if cfg.WB_VERBOSE:
                    print "remove se3 task : " + dic_effectors_tasks[
                        eeName].name
                contact = createContactForEffector(invdyn, robot, phase,
                                                   eeName)
                dic_contacts.update({eeName: contact})

        # add se3 tasks for end effector not in contact that will be in contact next phase:
        for eeName, task in dic_effectors_tasks.iteritems():
            if phase_next and not isContactActive(
                    phase, eeName) and isContactActive(phase_next, eeName):
                if cfg.WB_VERBOSE:
                    print "add se3 task for " + eeName
                invdyn.addMotionTask(task, cfg.w_eff, cfg.level_eff, 0.0)
                #create reference trajectory for this task :
                placement_init = getCurrentEffectorPosition(
                    robot, invdyn.data(), eeName
                )  #FIXME : adjust orientation in case of 3D contact ...
                if cfg.Robot.cType == "_3_DOF":
                    placement_init.rotation = JointPlacementForEffector(
                        phase, eeName).rotation
                placement_end = JointPlacementForEffector(phase_next, eeName)
                ref_traj = generateEndEffectorTraj(time_interval,
                                                   placement_init,
                                                   placement_end, 0)
                if cfg.WB_VERBOSE:
                    print "t interval : ", time_interval
                    print "placement Init : ", placement_init
                    print "placement End  : ", placement_end
                    # display all the effector trajectories for this phase
                if viewer and cfg.DISPLAY_ALL_FEET_TRAJ:
                    display_tools.displaySE3Traj(
                        ref_traj, viewer.client.gui, viewer.sceneName,
                        eeName + "_traj_" + str(pid),
                        cfg.Robot.dict_limb_color_traj[eeName], time_interval,
                        cfg.Robot.dict_offset[eeName])
                    viewer.client.gui.setVisibility(
                        eeName + "_traj_" + str(pid), 'ALWAYS_ON_TOP')
                dic_effectors_trajs.update({eeName: ref_traj})

        # start removing the contact that will be broken in the next phase :
        # (This tell the solver that it should start minimzing the contact force on this contact, and ideally get to 0 at the given time)
        for eeName, contact in dic_contacts.iteritems():
            if phase_next and isContactActive(
                    phase, eeName) and not isContactActive(phase_next, eeName):
                transition_time = t_phase_end - t - dt / 2.
                if cfg.WB_VERBOSE:
                    print "\nTime %.3f Start breaking contact %s. transition time : %.3f\n" % (
                        t, contact.name, transition_time)
                invdyn.removeRigidContact(contact.name, transition_time)

        if cfg.WB_STOP_AT_EACH_PHASE:
            raw_input('start simulation')
        # save values at the beginning of the current phase
        q_begin = q.copy()
        v_begin = v.copy()
        phaseValid = False
        swingPhase = False  # will be true if an effector move during this phase
        iter_for_phase = -1
        # iterate until a valid motion for this phase is found (ie. collision free and which respect joint-limits)
        while not phaseValid:
            if iter_for_phase >= 0:
                # reset values to their value at the beginning of the current phase
                q = q_begin.copy()
                v = v_begin.copy()
            iter_for_phase += 1
            if cfg.WB_VERBOSE:
                print "Start simulation for phase " + str(
                    pid) + ", try number :  " + str(iter_for_phase)
            # loop to generate states (q,v,a) for the current contact phase :
            if pid == cs.size() - 1:  # last state
                phase_interval = res.phases_intervals[pid]
            else:
                phase_interval = res.phases_intervals[pid][:-1]
            for k_t in phase_interval:
                t = res.t_t[k_t]
                # set traj reference for current time :
                # com
                sampleCom = trajCom.computeNext()
                com_desired = com_traj(t)[0]
                vcom_desired = com_traj(t)[1]
                acom_desired = com_traj(t)[2]
                sampleCom.pos(com_desired)
                sampleCom.vel(vcom_desired)
                sampleCom.acc(acom_desired)
                comTask.setReference(sampleCom)

                # am
                sampleAM = trajAM.computeNext()
                L_desired = am_traj(t)[0]
                dL_desired = am_traj(t)[1]
                sampleAM.pos(L_desired)
                sampleAM.vel(dL_desired)
                amTask.setReference(sampleAM)

                # posture
                samplePosture = trajPosture.computeNext()
                #print "postural task ref : ",samplePosture.pos()
                postureTask.setReference(samplePosture)

                # root orientation :
                sampleRoot = trajRoot.computeNext()
                sampleRoot.pos(SE3toVec(root_traj(t)[0]))
                sampleRoot.vel(MotiontoVec(root_traj(t)[1]))

                orientationRootTask.setReference(sampleRoot)
                quat_waist = Quaternion(root_traj(t)[0].rotation)
                res.waist_orientation_reference[:, k_t] = np.matrix(
                    [quat_waist.x, quat_waist.y, quat_waist.z, quat_waist.w]).T
                if cfg.WB_VERBOSE == 2:
                    print "### references given : ###"
                    print "com  pos : ", sampleCom.pos()
                    print "com  vel : ", sampleCom.vel()
                    print "com  acc : ", sampleCom.acc()
                    print "AM   pos : ", sampleAM.pos()
                    print "AM   vel : ", sampleAM.vel()
                    print "root pos : ", sampleRoot.pos()
                    print "root vel : ", sampleRoot.vel()

                # end effector (if they exists)
                for eeName, traj in dic_effectors_trajs.iteritems():
                    if traj:
                        swingPhase = True  # there is an effector motion in this phase
                        sampleEff = effectorTraj.computeNext()
                        traj_t = traj(t)
                        sampleEff.pos(SE3toVec(traj_t[0]))
                        sampleEff.vel(MotiontoVec(traj_t[1]))
                        dic_effectors_tasks[eeName].setReference(sampleEff)
                        if cfg.WB_VERBOSE == 2:
                            print "effector " + str(eeName) + " pos : " + str(
                                sampleEff.pos())
                            print "effector " + str(eeName) + " vel : " + str(
                                sampleEff.vel())
                        if cfg.IK_store_effector:
                            res.effector_references[eeName][:, k_t] = SE3toVec(
                                traj_t[0])
                            res.d_effector_references[
                                eeName][:, k_t] = MotiontoVec(traj_t[1])
                            res.dd_effector_references[
                                eeName][:, k_t] = MotiontoVec(traj_t[2])
                    elif cfg.IK_store_effector:
                        if k_t == 0:
                            res.effector_references[eeName][:, k_t] = SE3toVec(
                                getCurrentEffectorPosition(
                                    robot, invdyn.data(), eeName))
                        else:
                            res.effector_references[
                                eeName][:, k_t] = res.effector_references[
                                    eeName][:, k_t - 1]
                        res.d_effector_references[eeName][:, k_t] = np.matrix(
                            np.zeros(6)).T
                        res.dd_effector_references[eeName][:, k_t] = np.matrix(
                            np.zeros(6)).T

                # solve HQP for the current time
                HQPData = invdyn.computeProblemData(t, q, v)
                if cfg.WB_VERBOSE and t < phase.time_trajectory[0] + dt:
                    print "final data for phase ", pid
                    HQPData.print_all()

                sol = solver.solve(HQPData)
                dv = invdyn.getAccelerations(sol)
                res = storeData(k_t, res, q, v, dv, invdyn, sol)
                # update state
                v_mean = v + 0.5 * dt * dv
                v += dt * dv
                q = pin.integrate(robot.model(), q, dt * v_mean)

                if cfg.WB_VERBOSE == 2:
                    print "v = ", v
                    print "dv = ", dv

                if cfg.WB_VERBOSE and int(t / dt) % cfg.IK_PRINT_N == 0:
                    printIntermediate(v, dv, invdyn, sol)
                try:
                    checkDiverge(res, v, dv)
                except ValueError:
                    return stopHere()

            # end while t \in phase_t (loop for the current contact phase)
            if swingPhase and cfg.EFF_CHECK_COLLISION:
                phaseValid, t_invalid = validator.check_motion(
                    res.q_t[:, phase_interval[0]:k_t])
                #if iter_for_phase < 3 :# FIXME : debug only, force limb-rrt
                #    phaseValid = False
                if not phaseValid:
                    print "Phase " + str(pid) + " not valid at t = " + str(
                        t_invalid)
                    if t_invalid <= cfg.EFF_T_PREDEF or t_invalid >= (
                        (t_phase_end - t_phase_begin) - cfg.EFF_T_PREDEF):
                        print "Motion is invalid during predefined phases, cannot change this."
                        return stopHere()
                    if effectorCanRetry():
                        print "Try new end effector trajectory."
                        try:
                            for eeName, oldTraj in dic_effectors_trajs.iteritems(
                            ):
                                if oldTraj:  # update the traj in the map
                                    placement_init = JointPlacementForEffector(
                                        phase_prev, eeName)
                                    placement_end = JointPlacementForEffector(
                                        phase_next, eeName)
                                    ref_traj = generateEndEffectorTraj(
                                        time_interval, placement_init,
                                        placement_end, iter_for_phase + 1,
                                        res.q_t[:, phase_interval[0]:k_t],
                                        phase_prev, phase, phase_next,
                                        fullBody, eeName, viewer)
                                    dic_effectors_trajs.update(
                                        {eeName: ref_traj})
                                    if viewer and cfg.DISPLAY_ALL_FEET_TRAJ:
                                        display_tools.displaySE3Traj(
                                            ref_traj, viewer.client.gui,
                                            viewer.sceneName,
                                            eeName + "_traj_" + str(pid), cfg.
                                            Robot.dict_limb_color_traj[eeName],
                                            time_interval,
                                            cfg.Robot.dict_offset[eeName])
                                        viewer.client.gui.setVisibility(
                                            eeName + "_traj_" + str(pid),
                                            'ALWAYS_ON_TOP')
                        except ValueError, e:
                            print "ERROR in generateEndEffectorTraj :"
                            print e.message
                            return stopHere()
                    else:
                        print "End effector method choosen do not allow retries, abort here."
                        return stopHere()
            else:  # no effector motions, phase always valid (or bypass the check)
                phaseValid = True
                if cfg.WB_VERBOSE:
                    print "Phase " + str(pid) + " valid."
            if phaseValid:
                # display all the effector trajectories for this phase
                if viewer and cfg.DISPLAY_FEET_TRAJ and not cfg.DISPLAY_ALL_FEET_TRAJ:
                    for eeName, ref_traj in dic_effectors_trajs.iteritems():
                        if ref_traj:
                            display_tools.displaySE3Traj(
                                ref_traj, viewer.client.gui, viewer.sceneName,
                                eeName + "_traj_" + str(pid),
                                cfg.Robot.dict_limb_color_traj[eeName],
                                time_interval, cfg.Robot.dict_offset[eeName])
                            viewer.client.gui.setVisibility(
                                eeName + "_traj_" + str(pid), 'ALWAYS_ON_TOP')
                            if cfg.PLOT:  # add current ref_traj to the list for plotting
                                stored_effectors_ref[eeName] += [ref_traj]