def initialize_robot(): robot.set_dof_values(robot.q_halfsit) active_dofs = robot.chest + robot.free active_dofs += robot.left_leg + robot.right_leg robot.set_active_dofs(active_dofs) robot.init_ik(gains={ 'com': 1., 'contact': 1., 'link_pose': 1., }, weights={ 'com': 10., 'contact': 1000., 'link_pose': 100., }) robot.set_dof_values([1.], [robot.TRANS_Z]) # warm-start PG stance = fsm.cur_stance com_task = COMTask(robot, stance.com) robot.ik.add_task(com_task) robot.ik.add_task(ContactTask(robot, robot.left_foot, stance.left_foot)) robot.ik.add_task(ContactTask(robot, robot.right_foot, stance.right_foot)) robot.ik.add_task(MinVelocityTask(robot, weight=1.)) robot.solve_ik(max_it=50) # active_dofs += [robot.L_ELBOW_P, robot.R_ELBOW_P] active_dofs += [robot.L_SHOULDER_R, robot.R_SHOULDER_R] robot.set_dof_limits([+0.15], [+1.], [robot.L_SHOULDER_R]) robot.set_dof_limits([-1.], [-0.15], [robot.R_SHOULDER_R]) robot.set_active_dofs(active_dofs) com_task.update_target(preview_buffer.com) robot.ik.add_task(MinCAMTask(robot, weight=1.)) robot.ik.add_task(DOFTask(robot, robot.CHEST_P, 0.2, gain=0.9, weight=0.05)) robot.ik.add_task(DOFTask(robot, robot.CHEST_Y, 0., gain=0.9, weight=0.05)) robot.ik.add_task(DOFTask(robot, robot.ROT_P, 0., gain=0.9, weight=0.05)) robot.solve_ik()
def setup_ik_from_tasks(): """ Setup the inverse kinematics task by task. Note ----- This function is equivalent to :func:`setup_ik_from_stance` above. Beginners should take a look at that one first. Notes ----- See this `tutorial on inverse kinematics <https://scaron.info/teaching/inverse-kinematics.html>`_ for details. """ from pymanoid.tasks import COMTask, ContactTask, DOFTask, PostureTask # Prepare targets lf_target = Contact(robot.sole_shape, pos=[0, 0.3, 0]) rf_target = Contact(robot.sole_shape, pos=[0, -0.3, 0]) # Initial robot pose robot.set_dof_values([0.8], dof_indices=[robot.TRANS_Z]) com = PointMass(pos=robot.com, mass=robot.mass) # Prepare tasks left_foot_task = ContactTask(robot, robot.left_foot, lf_target, weight=1., gain=0.85) right_foot_task = ContactTask(robot, robot.right_foot, rf_target, weight=1., gain=0.85) com_task = COMTask(robot, com, weight=1e-2, gain=0.85) posture_task = PostureTask(robot, robot.q_halfsit, weight=1e-6, gain=0.85) # Add tasks to the IK solver robot.ik.add(left_foot_task) robot.ik.add(right_foot_task) robot.ik.add(com_task) robot.ik.add(posture_task) # Add shoulder DOF tasks for a nicer posture robot.ik.add( DOFTask(robot, robot.R_SHOULDER_R, -0.5, gain=0.5, weight=1e-5)) robot.ik.add( DOFTask(robot, robot.L_SHOULDER_R, +0.5, gain=0.5, weight=1e-5))
robot.set_dof_values([dof_ref], [dof_id]) q_init[dof_id] = dof_ref robot.set_dof_values([-1], [robot.R_SHOULDER_P]) robot.set_dof_values([-1], [robot.L_SHOULDER_P]) robot.set_dof_values([0.8], dof_indices=[robot.TRANS_Z]) init_com = robot.com.copy() # IK targets com = Cube(0.05, pos=robot.com, color='g') lf_target = Contact(robot.sole_shape, pos=[0, 0.3, 0], visible=True) rf_target = Contact(robot.sole_shape, pos=[0, -0.3, 0], visible=True) # IK tasks lf_task = ContactTask(robot, robot.left_foot, lf_target, weight=1000) rf_task = ContactTask(robot, robot.right_foot, rf_target, weight=1000) com_task = COMTask(robot, com, weight=10) reg_task = PostureTask(robot, robot.q, weight=0.1) # regularization task # IK setup robot.init_ik(active_dofs=robot.whole_body) robot.ik.add_tasks([lf_task, rf_task, com_task, reg_task]) for (dof_id, dof_ref) in dof_targets: robot.ik.add_task( DOFTask(robot, dof_id, dof_ref, gain=0.5, weight=0.1)) # First, generate an initial posture robot.solve_ik(max_it=100, conv_tol=1e-4, debug=True) # Next, we move the COM back and forth for 10 seconds move_com_back_and_forth(10)
outbox = pymanoid.Cube(0.02, color='b') if 'single.json' in fname: outbox.set_pos([0., 0., z_high]) elif 'double.json' in fname or 'triple.json' in fname: outbox.set_pos([0.3, 0.04, z_high]) else: warn("Unknown contact set, you will have to set the COM position.") with robot_lock: robot.set_dof_values(robot.q_halfsit) robot.set_active_dofs(robot.chest + robot.legs + robot.arms + robot.free) robot.init_ik() robot.generate_posture(contacts) robot.ik.add_task(COMTask(robot, com_target)) print """ Static-equilibrium polygon computations ======================================= Legend: - Magenta area: computed using cdd + Qhull - Yellow area: computed using Parma + Qhull - Green area: computed using Bretl and Lall's method - Black area: computed using cdd only""" threads.append(thread.start_new_thread(run_ik_thread, ())) threads.append(thread.start_new_thread(draw_cdd_thread, ())) threads.append(thread.start_new_thread(draw_bretl_thread, ())) threads.append(thread.start_new_thread(draw_pyparma_thread, ()))
# Initial robot pose robot.set_dof_values([0.8], dof_indices=[robot.TRANS_Z]) com = PointMass(pos=robot.com, mass=robot.mass) # IK tasks lf_task = ContactTask(robot, robot.left_foot, lf_target, weight=1., gain=0.85) rf_task = ContactTask(robot, robot.right_foot, rf_target, weight=1., gain=0.85) com_task = COMTask(robot, com, weight=1e-2, gain=0.85) reg_task = PostureTask(robot, robot.q, weight=1e-6, gain=0.85) # IK setup robot.ik.clear_tasks() robot.ik.add_task(lf_task) robot.ik.add_task(rf_task) robot.ik.add_task(com_task) robot.ik.add_task(reg_task) # Add some DOFTasks for a nicer posture robot.ik.add_task( DOFTask(robot, robot.R_SHOULDER_R, -0.5, gain=0.5, weight=1e-5)) robot.ik.add_task( DOFTask(robot, robot.L_SHOULDER_R, +0.5, gain=0.5, weight=1e-5))