def createContactForEffector(invdyn, robot, phase, eeName): contactNormal = np.matrix(cfg.Robot.dict_normal[eeName]).T contactNormal = cfg.Robot.dict_offset[ eeName].rotation * contactNormal # apply offset transform if cfg.Robot.cType == "_3_DOF": contact = tsid.ContactPoint("contact_" + eeName, robot, eeName, contactNormal, cfg.MU, cfg.fMin, cfg.fMax) mask = np.matrix(np.ones(3)).transpose() contact.useLocalFrame(False) else: contact_Points = buildRectangularContactPoints(eeName) contact = tsid.Contact6d("contact_" + eeName, robot, eeName, contact_Points, contactNormal, cfg.MU, cfg.fMin, cfg.fMax) mask = np.matrix(np.ones(6)).transpose() contact.setKp(cfg.kp_contact * mask) contact.setKd(2.0 * np.sqrt(cfg.kp_contact) * mask) ref = getCurrentEffectorPosition(robot, invdyn.data(), eeName) contact.setReference(ref) invdyn.addRigidContact(contact, cfg.w_forceRef) if cfg.WB_VERBOSE: print "create contact for effector ", eeName if cfg.Robot.cType == "_3_DOF": print "create contact point" else: print "create rectangular contact" print "contact points : \n", contact_Points print "contact placement : ", ref print "contact_normal : ", contactNormal return contact
def AttachContact(name): i = contact_frames.index(name) contacts[i] = tsid.ContactPoint(name, robot, name, contactNormal, mu, fMin, fMax) contacts[i].setKp(kp_contact * matlib.ones(3).T) contacts[i].setKd(2.0 * np.sqrt(kp_contact) * matlib.ones(3).T) H_rf_ref = robot.framePosition(data, robot.model().getFrameId(name)) contacts[i].setReference(H_rf_ref) contacts[i].useLocalFrame(False) invdyn.addRigidContact(contacts[i], w_forceRef, 1.0, 1)
def createContactForEffector(cfg, invdyn, robot, eeName, patch, use_force_reg=True): """ Add a contact task in invdyn for the given effector, at it's current placement :param invdyn: :param robot: :param eeName: name of the effector :param patch: the ContactPatch object to use. Take friction coefficient and placement for the contact from this object :param use_force_reg: if True, use the cfg.w_forceRef_init otherwise use cfg.w_forceRef_end :return: the contact task """ contactNormal = np.array(cfg.Robot.dict_normal[eeName]) contactNormal = cfg.Robot.dict_offset[ eeName].rotation @ contactNormal # apply offset transform logger.info("create contact for effector %s", eeName) logger.info("contact placement : %s", patch.placement) logger.info("contact_normal : %s", contactNormal) if patch.contact_model.contact_type == ContactType.CONTACT_POINT: contact = tsid.ContactPoint("contact_" + eeName, robot, eeName, contactNormal, patch.friction, cfg.fMin, cfg.fMax) mask = np.ones(3) force_ref = np.zeros(3) contact.useLocalFrame(False) logger.info("create contact point") elif patch.contact_model.contact_type == ContactType.CONTACT_PLANAR: contact_points = patch.contact_model.contact_points_positions contact = tsid.Contact6d("contact_" + eeName, robot, eeName, contact_points, contactNormal, patch.friction, cfg.fMin, cfg.fMax) mask = np.ones(6) force_ref = np.zeros(6) logger.info("create rectangular contact") logger.info("contact points : \n %s", contact_points) else: raise RuntimeError("Unknown contact type : ", patch.contact_model.contact_type) contact.setKp(cfg.kp_contact * mask) contact.setKd(2.0 * np.sqrt(cfg.kp_contact) * mask) contact.setReference(patch.placement) contact.setForceReference(force_ref) if use_force_reg: w_forceRef = cfg.w_forceRef_init else: w_forceRef = cfg.w_forceRef_end invdyn.addRigidContact(contact, w_forceRef) return contact
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)
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) model = robot.model() data = robot.data() mu = 0.3 fMin = 10.0 fMax = 1000.0 frameName = "RAnkleRoll" contactNormal = np.matrix(np.zeros(3)).transpose() contactNormal[2] = 1.0 contact = tsid.ContactPoint("contactPoint", robot, frameName, contactNormal, mu, fMin, fMax) assert contact.n_motion == 3 assert contact.n_force == 3 Kp = np.matrix(np.ones(3)).transpose() Kd = 2 * Kp contact.setKp(Kp) contact.setKd(Kd) assert np.linalg.norm(contact.Kp - Kp, 2) < tol assert np.linalg.norm(contact.Kd - Kd, 2) < tol q = model.neutralConfiguration v = np.matrix(np.zeros(robot.nv)).transpose() robot.computeAllTerms(data, q, v)
assert [robot.model().existFrame(name) for name in contact_frames] t = 0.0 # time invdyn = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False) invdyn.computeProblemData(t, q, v) data = invdyn.data() # Place the robot onto the ground. id_contact = robot_display.model.getFrameId(contact_frames[0]) q[2] -= robot.framePosition(data, id_contact).translation[2] robot.computeAllTerms(data, q, v) contacts = 4 * [None] for i, name in enumerate(contact_frames): contacts[i] = tsid.ContactPoint(name, robot, name, contactNormal, mu, fMin, fMax) contacts[i].setKp(kp_contact * np.ones(3)) contacts[i].setKd(2.0 * np.sqrt(kp_contact) * np.ones(3)) H_rf_ref = robot.framePosition(data, robot.model().getFrameId(name)) contacts[i].setReference(H_rf_ref) contacts[i].useLocalFrame(False) invdyn.addRigidContact(contacts[i], w_forceRef, 1.0, 1) comTask = tsid.TaskComEquality("task-com", robot) comTask.setKp(kp_com * np.ones(3)) comTask.setKd(2.0 * np.sqrt(kp_com) * np.ones(3)) invdyn.addMotionTask(comTask, w_com, 1, 0.0) postureTask = tsid.TaskJointPosture("task-posture", robot) postureTask.setKp(kp_posture * np.ones(robot.nv - 6)) postureTask.setKd(2.0 * np.sqrt(kp_posture) * np.ones(robot.nv - 6))
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)
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)
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)
def __init__(self, urdf_path, model_path, eff_arr, q0, v0, mu=0.6, fz_max=75): """ Input: urdf_path: path to urdf of robot model_path: path to model of robot (required by TSID) eff_arr : end effector name array q0: initial configuration v0: initial velocity tau_max: vector of maximum torques for each joint mu: coefficient of friction at end-effectors """ self.kp_com = 0.0001 self.kp_contact = 5.0 self.kp_posture = 10.0 self.kp_orientation = 0.002 self.w_com = 1.0 self.w_posture = 1e0 self.w_force = 1.0 self.w_orientation = 1e-6 self.contact_transition = 0.1 self.eff_arr = eff_arr self.curr_cnt_array = np.zeros(len(self.eff_arr)) #self.tau_max = tau_max #self.tau_min = -1*self.tau_max self.tsid_robot = tsid.RobotWrapper(urdf_path, [model_path], pin.JointModelFreeFlyer(), False) self.nq = self.tsid_robot.nq self.nv = self.tsid_robot.nv self.tsid_model = self.tsid_robot.model() self.invdyn = tsid.InverseDynamicsFormulationAccForce( "tsid", self.tsid_robot, False) self.qp_solver = tsid.SolverHQuadProgFast("qp_solver") #Set up initial solve self.invdyn.computeProblemData(0, q0.copy(), v0.copy()) self.inv_dyn_data = self.invdyn.data() self.tsid_robot.computeAllTerms(self.inv_dyn_data, q0, v0) self.mu = mu # Add Contact Tasks (setup as equality constraints) contactNormal = np.array([0., 0., 1.]) self.contact_arr = len(self.eff_arr) * [None] for i, name in enumerate(self.eff_arr): self.contact_arr[i] = tsid.ContactPoint(name, self.tsid_robot, name, contactNormal, self.mu, 0.01, fz_max) self.contact_arr[i].setKp(self.kp_contact * np.ones(3)) self.contact_arr[i].setKd(.03 * np.ones(3)) cnt_ref = self.tsid_robot.framePosition( self.inv_dyn_data, self.tsid_robot.model().getFrameId(name)) self.contact_arr[i].setReference(cnt_ref) self.contact_arr[i].useLocalFrame(False) self.invdyn.addRigidContact(self.contact_arr[i], self.w_force) # Add posture tasks (in the cost function) self.postureTask = tsid.TaskJointPosture("posture_task", self.tsid_robot) self.postureTask.setKp(self.kp_posture * np.ones(self.tsid_robot.nv - 6)) self.postureTask.setKd(.05 * np.ones(3)) self.invdyn.addMotionTask(self.postureTask, self.w_posture, 1, 0.0) #Add CoM task (in the cost function) # self.comTask = tsid.TaskComEquality("task-com", self.tsid_robot) # self.comTask.setKp(self.kp_com * np.ones(6)) # self.comTask.setKd(.01 * np.ones(6)) # self.invdyn.addMotionTask(self.comTask, self.w_com, 1, 0.0) #Add orientation task (in the cost function) # self.oriTask = tsid.TaskSE3Equality("orientation", self.tsid_robot, "base_link") # self.oriTask.setKp(self.kp_orientation * np.ones(6)) # self.oriTask.setKd(2.0 * np.sqrt(self.kp_orientation) * np.ones(6)) # mask = np.ones(6) # mask[:3] = 0 # self.oriTask.setMask(mask) # self.invdyn.addMotionTask(self.oriTask, self.w_orientation, 1, 0.0) #Setup trajectories (des_q, des_v, des_a) # self.com_ref = self.tsid_robot.com(self.inv_dyn_data) # self.trajCom = tsid.TrajectoryEuclidianConstant("trajectory_com", self.com_ref) # self.com_reference = self.trajCom.computeNext() # self.trajPosture = tsid.TrajectoryEuclidianConstant( "trajectory_posture", q0[7:]) self.traj_reference = self.trajPosture.computeNext() self.postureTask.setReference(self.traj_reference) # self.ori_ref = self.tsid_robot.position(self.inv_dyn_data, self.tsid_robot.model().getJointId("base_link")) # self.oriTraj = tsid.TrajectorySE3Constant("trajectory_orientation", self.ori_ref) # self.ori_reference = self.oriTraj.computeNext() ### --- Actuation Bounds --- ### # Get actuator effort limits (i.e. torque limits) from URDF: # tau_max = self.actuator_scaling * self.tsid_model.effortLimit #actuationBounds = tsid.TaskActuationBounds("torque-actuation-bounds", self.tsid_robot) #actuationBounds.setBounds(self.tau_min, self.tau_max) #formulation.addActuationTask(actuationBounds, w_torque_bounds, 0, 0.0) self.qp_solver.resize(self.invdyn.nVar, self.invdyn.nEq, self.invdyn.nIn)
def __init__(self, conf, dt, robot, com_offset, com_frequency, com_amplitude, q0=None, viewer=True): self.conf = conf self.dt = dt self.robot = tsid.RobotWrapper(robot.model, False) if q0 is None: q = robot.model.neutralConfiguration else: q = np.copy(q0) # q = se3.getNeutralConfiguration(robot.model(), conf.srdf, False) # q = robot.model().referenceConfigurations["half_sitting"] v = np.zeros(robot.nv) # for gepetto viewer if (viewer): # se3.RobotWrapper.BuildFromURDF(conf.urdf, [conf.path, ], se3.JointModelFreeFlyer()) self.robot_display = robot prompt = subprocess.getstatusoutput( "ps aux |grep 'gepetto-gui'|grep -v 'grep'|wc -l") if int(prompt[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('gepetto', conf.CAMERA_TRANSFORM) robot = self.robot self.model = robot.model() # assert [robot.model().existFrame(name) for name in conf.contact_frames] formulation = tsid.InverseDynamicsFormulationAccForce( "tsid", robot, False) formulation.computeProblemData(0.0, q, v) data = formulation.data() contacts = len(conf.contact_frames) * [None] self.contact_ids = {} for i, name in enumerate(conf.contact_frames): contacts[i] = tsid.ContactPoint(name, robot, name, conf.contact_normal, conf.mu, conf.fMin, conf.fMax) contacts[i].setKp(conf.kp_contact * np.ones(3)) contacts[i].setKd(2.0 * np.sqrt(conf.kp_contact) * np.ones(3)) self.contact_ids[name] = robot.model().getFrameId(name) H_ref = robot.framePosition(data, robot.model().getFrameId(name)) contacts[i].setReference(H_ref) contacts[i].useLocalFrame(False) formulation.addRigidContact(contacts[i], conf.w_forceRef, 1.0, 1) # modify initial robot configuration so that foot is on the ground (z=0) # q[2] -= H_rf_ref.translation[2,0] # 0.84 # fix this # 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) 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.array(np.ones(6)).T) # self.leftFootTask.setKd(2.0 * np.sqrt(self.conf.kp_foot) * np.array(np.ones(6)).T) # self.trajLF = tsid.TrajectorySE3Constant("traj-left-foot", H_lf_ref) # # self.rightFootTask = tsid.TaskSE3Equality("task-right-foot", self.robot, self.conf.rf_frame_name) # self.rightFootTask.setKp(self.conf.kp_foot * np.array(np.ones(6)).T) # self.rightFootTask.setKd(2.0 * np.sqrt(self.conf.kp_foot) * np.array(np.ones(6)).T) # self.trajRF = tsid.TrajectorySE3Constant("traj-right-foot", H_rf_ref) # com_ref = robot.com(data) trajCom = tsid.TrajectoryEuclidianConstant("traj_com", com_ref) q_ref = q[7:] trajPosture = tsid.TrajectoryEuclidianConstant("traj_joint", q_ref) comTask.setReference(trajCom.computeNext()) postureTask.setReference(trajPosture.computeNext()) solver = tsid.SolverHQuadProgFast("qp solver") solver.resize(formulation.nVar, formulation.nEq, formulation.nIn) self.trajCom = trajCom self.trajPosture = trajPosture self.comTask = comTask self.postureTask = postureTask self.contacts = contacts self.formulation = formulation self.solver = solver self.q = q self.v = v self.contacts_active = {} for name in conf.contact_frames: self.contacts_active[name] = True # com_pos = np.empty((3, N_SIMULATION))*nan # com_vel = np.empty((3, N_SIMULATION))*nan # com_acc = np.empty((3, N_SIMULATION))*nan # com_pos_ref = np.empty((3, N_SIMULATION))*nan # com_vel_ref = np.empty((3, N_SIMULATION))*nan # com_acc_ref = np.empty((3, N_SIMULATION))*nan # # acc_des = acc_ref - Kp*pos_err - Kd*vel_err # com_acc_des = np.empty((3, N_SIMULATION))*nan self.offset = com_offset + self.robot.com(self.formulation.data()) self.two_pi_f = np.copy(com_frequency) self.amp = np.copy(com_amplitude) self.two_pi_f_amp = self.two_pi_f * self.amp self.two_pi_f_squared_amp = self.two_pi_f * self.two_pi_f_amp self.sampleCom = self.trajCom.computeNext() self.reset(q, v, 0.0)