Skip to content

Commit

Permalink
example/fit: adjust to new api for set_robot_state
Browse files Browse the repository at this point in the history
  • Loading branch information
HiroIshida committed Dec 25, 2024
1 parent 286da4f commit 9bb8b7f
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
5 changes: 3 additions & 2 deletions example/beta/humanoid_lift_and_place_box.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

from plainmp.constraint import EqCompositeCst, IneqCompositeCst
from plainmp.ik import solve_ik
from plainmp.kinematics import BaseType
from plainmp.manifold_rrt.manifold_rrt_solver import ManiRRTConfig, ManiRRTConnectSolver
from plainmp.nlp_solver import SQPBasedSolver, SQPBasedSolverConfig
from plainmp.parallel import ParallelSolver
Expand Down Expand Up @@ -112,7 +113,7 @@
v = PyrenderViewer()
ground = Box([2, 2, 0.01])
robot = jspec.get_robot_model(with_mesh=True)
set_robot_state(robot, jspec.control_joint_names, ik_ret1.q, True)
set_robot_state(robot, jspec.control_joint_names, ik_ret1.q, BaseType.FLOATING)
robot.rarm_end_coords.assoc(box)

v.add(ground)
Expand All @@ -123,7 +124,7 @@
time.sleep(2)

for q in ret.traj:
set_robot_state(robot, jspec.control_joint_names, q, True)
set_robot_state(robot, jspec.control_joint_names, q, BaseType.FLOATING)
v.redraw()
time.sleep(0.1)
time.sleep(10)
5 changes: 3 additions & 2 deletions example/beta/humanoid_planning.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

from plainmp.constraint import EqCompositeCst, IneqCompositeCst
from plainmp.ik import solve_ik
from plainmp.kinematics import BaseType
from plainmp.manifold_rrt.manifold_rrt_solver import ManiRRTConfig, ManiRRTConnectSolver
from plainmp.nlp_solver import SQPBasedSolver, SQPBasedSolverConfig
from plainmp.parallel import ParallelSolver
Expand Down Expand Up @@ -79,15 +80,15 @@
if args.visualize:
v = PyrenderViewer()
robot = jspec.get_robot_model(with_mesh=True)
set_robot_state(robot, jspec.control_joint_names, ik_ret.q, True)
set_robot_state(robot, jspec.control_joint_names, ik_ret.q, BaseType.FLOATING)
ground = Box([2, 2, 0.01])
v.add(ground)
v.add(table)
v.add(robot)
v.show()
time.sleep(2)
for q in ret.traj:
set_robot_state(robot, jspec.control_joint_names, q, True)
set_robot_state(robot, jspec.control_joint_names, q, BaseType.FLOATING)
v.redraw()
time.sleep(0.15)
time.sleep(20)

0 comments on commit 9bb8b7f

Please sign in to comment.