Motion Generator#
The MotionGenerator class in EmbodiChain provides a unified and extensible interface for robot trajectory planning. It supports time-optimal trajectory generation (currently via TOPPRA), joint/Cartesian interpolation, and is designed for easy integration with RL, imitation learning, and classical control scenarios.
Key Features#
Unified API: One interface for multiple planning strategies (time-optimal, interpolation, etc.)
Constraint Support: Velocity/acceleration constraints configurable per joint
Flexible Input: Supports both joint space and Cartesian space waypoints
Extensible: Easy to add new planners (RRT, PRM, etc.)
Integration Ready: Can be used in RL, imitation learning, or classical pipelines
The Code#
The tutorial corresponds to the motion_generator.py script in the scripts/tutorials/sim directory.
Code for motion_generator.py
1# ----------------------------------------------------------------------------
2# Copyright (c) 2021-2025 DexForce Technology Co., Ltd.
3#
4# Licensed under the Apache License, Version 2.0 (the "License");
5# you may not use this file except in compliance with the License.
6# You may obtain a copy of the License at
7#
8# http://www.apache.org/licenses/LICENSE-2.0
9#
10# Unless required by applicable law or agreed to in writing, software
11# distributed under the License is distributed on an "AS IS" BASIS,
12# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13# See the License for the specific language governing permissions and
14# limitations under the License.
15# ----------------------------------------------------------------------------
16
17import time
18import torch
19import numpy as np
20from copy import deepcopy
21from embodichain.lab.sim import SimulationManager, SimulationManagerCfg
22from embodichain.lab.sim.objects import Robot
23from embodichain.lab.sim.robots import CobotMagicCfg
24from embodichain.lab.sim.planners.utils import TrajectorySampleMethod
25from embodichain.lab.sim.planners.motion_generator import MotionGenerator
26
27
28def move_robot_along_trajectory(
29 robot: Robot, arm_name: str, qpos_list: list[torch.Tensor], delay: float = 0.1
30):
31 """
32 Set the robot joint positions sequentially along the given joint trajectory.
33 Args:
34 robot: Robot instance.
35 arm_name: Name of the robot arm.
36 qpos_list: List of joint positions (torch.Tensor).
37 delay: Time delay between each step (seconds).
38 """
39 for q in qpos_list:
40 robot.set_qpos(qpos=q.unsqueeze(0), joint_ids=robot.get_joint_ids(arm_name))
41 time.sleep(delay)
42
43
44def create_demo_trajectory(
45 robot: Robot, arm_name: str
46) -> tuple[list[torch.Tensor], list[np.ndarray]]:
47 """
48 Generate a three-point trajectory (start, middle, end) for demonstration.
49 Args:
50 robot: Robot instance.
51 arm_name: Name of the robot arm.
52 Returns:
53 qpos_list: List of joint positions (torch.Tensor).
54 xpos_list: List of end-effector poses (numpy arrays).
55 """
56 qpos_fk = torch.tensor(
57 [[0.0, np.pi / 4, -np.pi / 4, 0.0, np.pi / 4, 0.0]], dtype=torch.float32
58 )
59 xpos_begin = robot.compute_fk(name=arm_name, qpos=qpos_fk, to_matrix=True)
60 xpos_mid = deepcopy(xpos_begin)
61 xpos_mid[0, 2, 3] -= 0.1 # Move down by 0.1m in Z direction
62 xpos_final = deepcopy(xpos_mid)
63 xpos_final[0, 0, 3] += 0.2 # Move forward by 0.2m in X direction
64
65 qpos_begin = robot.compute_ik(pose=xpos_begin, name=arm_name)[1][0]
66 qpos_mid = robot.compute_ik(pose=xpos_mid, name=arm_name)[1][0]
67 qpos_final = robot.compute_ik(pose=xpos_final, name=arm_name)[1][0]
68 return [qpos_begin, qpos_mid, qpos_final], [
69 xpos_begin[0],
70 xpos_mid[0],
71 xpos_final[0],
72 ]
73
74
75def main():
76 np.set_printoptions(precision=5, suppress=True)
77 torch.set_printoptions(precision=5, sci_mode=False)
78
79 # Initialize simulation
80 sim = SimulationManager(SimulationManagerCfg(headless=False, sim_device="cpu"))
81 sim.build_multiple_arenas(1)
82 sim.set_manual_update(False)
83
84 # Robot configuration
85 cfg_dict = {"uid": "CobotMagic"}
86 robot: Robot = sim.add_robot(cfg=CobotMagicCfg.from_dict(cfg_dict))
87 arm_name = "left_arm"
88
89 # # Generate trajectory points
90 qpos_list, xpos_list = create_demo_trajectory(robot, arm_name)
91
92 # Initialize motion generator
93 motion_generator = MotionGenerator(
94 robot=robot,
95 uid=arm_name,
96 planner_type="toppra",
97 default_velocity=0.2,
98 default_acceleration=0.5,
99 )
100
101 # Joint space trajectory
102 out_qpos_list, _ = motion_generator.create_discrete_trajectory(
103 qpos_list=[q.numpy() for q in qpos_list],
104 is_linear=False,
105 sample_method=TrajectorySampleMethod.QUANTITY,
106 sample_num=20,
107 )
108 move_robot_along_trajectory(robot, arm_name, out_qpos_list)
109
110 # Cartesian space trajectory
111 out_qpos_list, _ = motion_generator.create_discrete_trajectory(
112 xpos_list=[x.numpy() for x in xpos_list],
113 is_linear=True,
114 sample_method=TrajectorySampleMethod.QUANTITY,
115 sample_num=20,
116 )
117 move_robot_along_trajectory(robot, arm_name, out_qpos_list)
118
119
120if __name__ == "__main__":
121 main()
Typical Usage#
from embodichain.lab.sim.planners.motion_generator import MotionGenerator
# Assume you have a robot instance and uid
motion_gen = MotionGenerator(
robot=robot,
uid="arm",
default_velocity=0.2,
default_acceleration=0.5
)
# Plan a joint-space trajectory
current_state = {"position": [0, 0, 0, 0, 0, 0]}
target_states = [{"position": [0.5, 0.2, 0, 0, 0, 0]}]
success, positions, velocities, accelerations, times, duration = motion_gen.plan(
current_state=current_state,
target_states=target_states
)
# Generate a discrete trajectory (joint or Cartesian)
qpos_list, xpos_list = motion_gen.create_discrete_trajectory(
qpos_list=[[0,0,0,0,0,0],[0.5,0.2,0,0,0,0]],
sample_num=20
)
API Reference#
Initialization
MotionGenerator(
robot: Robot,
uid: str,
sim=None,
planner_type="toppra",
default_velocity=0.2,
default_acceleration=0.5,
collision_margin=0.01,
**kwargs
)
robot: Robot instance, must support get_joint_ids, compute_fk, compute_ikuid: Unique robot identifier (e.g., “arm”)planner_type: Planner type (default: “toppra”)default_velocity,default_acceleration: Default joint constraints
plan
plan(
current_state: Dict,
target_states: List[Dict],
sample_method=TrajectorySampleMethod.TIME,
sample_interval=0.01,
**kwargs
) -> Tuple[bool, positions, velocities, accelerations, times, duration]
Plans a time-optimal trajectory (joint space), returns trajectory arrays and duration.
create_discrete_trajectory
create_discrete_trajectory(
xpos_list=None,
qpos_list=None,
is_use_current_qpos=True,
is_linear=False,
sample_method=TrajectorySampleMethod.QUANTITY,
sample_num=20,
qpos_seed=None,
**kwargs
) -> Tuple[List[np.ndarray], List[np.ndarray]]
Generates a discrete trajectory between waypoints (joint or Cartesian), auto-handles FK/IK.
estimate_trajectory_sample_count
estimate_trajectory_sample_count(
xpos_list=None,
qpos_list=None,
step_size=0.01,
angle_step=np.pi/90,
**kwargs
) -> int
Estimates the number of samples needed for a trajectory.
plan_with_collision
plan_with_collision(...)
(Reserved) Plan trajectory with collision checking (not yet implemented).
Notes & Best Practices#
Only collision-free planning is currently supported; collision checking is a placeholder.
Input/outputs are numpy arrays or torch tensors; ensure type consistency.
Robot instance must implement get_joint_ids, compute_fk, compute_ik, get_proprioception, etc.
For custom planners, extend the PlannerType Enum and _create_planner methods.