Genesis
Genesis copied to clipboard
[Bug]: Severe frame drop when using emitter in Genesis simulation
Bug Description
Hello,
I'm a robotics developer currently working on simulating a painting robot using Genesis.
I'm experiencing a severe frame drop issue when using the add_emitter feature. Even when I simply add the emitter without actively emitting particles, the simulation frame rate drops significantly.
Here’s a simplified version of the relevant part of my code:
emitter = scene.add_emitter(
material=gs.materials.MPM.Sand(),
max_particles=200000,
surface=gs.surfaces.Rough(
color=(1.0, 0.9, 0.6, 1.0),
),
)
Later in the loop, I call emitter.emit(...) only when a button is toggled. However, the frame drop happens even before any emission occurs, just by registering the emitter.
What I’m trying to achieve is this:
I want the particles to be emitted from the robot’s end-effector and stick to the surface of a target object, simulating paint being sprayed onto a surface.
- Is there anything wrong with how I'm initializing or using the emitter?
- Is there a more performance-friendly way to achieve surface attachment of particles?
- Or is this an expected performance cost of initializing an emitter with many particles?
Any advice or optimization suggestions would be greatly appreciated.
Thank you!
### Steps to Reproduce
import numpy as np
import genesis as gs
from tkinter import Tk, Scale, HORIZONTAL, Button, Label, SUNKEN
import torch
# Initialize Genesis
gs.init(backend=gs.gpu)
# Create a scene
scene = gs.Scene(
viewer_options=gs.options.ViewerOptions(
camera_pos=(3, -1, 1.5),
camera_lookat=(0.0, 0.0, 0.5),
camera_fov=30,
max_FPS=60,
),
mpm_options=gs.options.MPMOptions(
lower_bound=(-3, -3, -3),
upper_bound=(3, 3, 3),
),
sim_options=gs.options.SimOptions(
dt=3e-3,
substeps=10, # for more stable grasping contact
),
show_viewer=True,
)
# Add entities
plane = scene.add_entity(gs.morphs.Plane())
rb = scene.add_entity(
gs.morphs.URDF(
file="/workspace/Genesis/genesis/assets/urdf/rb10/rb10_1300_ori.urdf",
pos=(0.0, 0.0, 0.0),
euler=(0.0, 0.0, 0.0),
fixed=True,
)
)
emitter = scene.add_emitter(
material=gs.materials.MPM.Sand(),
max_particles=200000,
surface=gs.surfaces.Rough(
color=(1.0, 0.9, 0.6, 1.0),
),
)
scene.build()
end_effector = rb.get_link("link6")
# Joint names and indices
jnt_names = ['joint1', 'joint2', 'joint3', 'joint4', 'joint5', 'joint6']
dofs_idx = [rb.get_joint(name).dof_idx_local for name in jnt_names]
# Set control gains
rb.set_dofs_kp(kp=np.array([5000, 10000, 5000, 5000, 5000, 2000]), dofs_idx_local=dofs_idx)
rb.set_dofs_kv(kv=np.array([500, 1500, 500, 500, 500, 500]), dofs_idx_local=dofs_idx)
rb.set_dofs_force_range(lower=np.array([-300, -500, -300, -300, -300, -50]),
upper=np.array([300, 500, 300, 300, 300, 50]), dofs_idx_local=dofs_idx)
# State variable for controlling mode
is_fk_mode = True
emitting = False
def quaternion_to_matrix(quat):
"""Convert quaternion to rotation matrix."""
qw, qx, qy, qz = quat
return np.array([
[1 - 2 * (qy**2 + qz**2), 2 * (qx * qy - qz * qw), 2 * (qx * qz + qy * qw)],
[2 * (qx * qy + qz * qw), 1 - 2 * (qx**2 + qz**2), 2 * (qy * qz - qx * qw)],
[2 * (qx * qz - qy * qw), 2 * (qy * qz + qx * qw), 1 - 2 * (qx**2 + qy**2)]
])
def toggle_emitter():
"""Toggle emitter on/off."""
global emitting
emitting = not emitting
emit_button.config(text="Stop Emitting" if emitting else "Start Emitting")
def emit_particles():
"""Emit particles continuously when the emitter is active."""
if emitting:
# Get end-effector link
end_effector = rb.get_link("link6")
# Get end-effector position and orientation
end_effector_pos_tensor = end_effector.get_pos()
end_effector_pos = end_effector_pos_tensor.cpu().numpy()
end_effector_quat_tensor = end_effector.get_quat()
end_effector_quat = end_effector_quat_tensor.cpu().numpy()
# Calculate direction from quaternion
rotation_matrix = quaternion_to_matrix(end_effector_quat)
direction = -rotation_matrix[:, 1] # Use -Y direction
# Apply offset in the end-effector's local frame
# Offset vector (x_offset, y_offset, z_offset) in the end-effector's local frame
local_offset = np.array([0.0, -0.3, 0.1]) # Adjust this based on nozzle position
world_offset = rotation_matrix @ local_offset # Convert to world frame
# Emit particles
emitter.emit(
pos=end_effector_pos + world_offset, # Corrected position
direction=direction,
speed=30.0,
droplet_shape="circle",
droplet_size=0.05,
)
# print("Particles emitted from:", end_effector_pos + world_offset, "Direction:", direction)
# Toggle FK/IK mode
def toggle_mode():
global is_fk_mode
is_fk_mode = not is_fk_mode
mode_label.config(text=f"Current Mode: {'FK' if is_fk_mode else 'IK'}") # Update mode label
mode_button.config(text="Switch to IK Mode" if is_fk_mode else "Switch to FK Mode")
if is_fk_mode:
for i, slider in enumerate(sliders):
slider.set(current_joint_angles_degrees[i])
else:
end_effector_pos_tensor = end_effector.get_pos()
end_effector_pos = end_effector_pos_tensor.cpu().numpy()
slider_x.set(end_effector_pos[0])
slider_y.set(end_effector_pos[1])
slider_z.set(end_effector_pos[2])
end_effector_quat_tensor = end_effector.get_quat()
end_effector_quat = end_effector_quat_tensor.cpu().numpy()
slider_qw.set(end_effector_quat[0])
slider_qx.set(end_effector_quat[1])
slider_qy.set(end_effector_quat[2])
slider_qz.set(end_effector_quat[3])
# FK Control
def fk_control():
joint_positions = [slider.get() for slider in sliders]
rb.control_dofs_position(np.radians(joint_positions), dofs_idx)
# IK Control
def move_robot():
try:
x = slider_x.get()
y = slider_y.get()
z = slider_z.get()
qw = slider_qw.get()
qx = slider_qx.get()
qy = slider_qy.get()
qz = slider_qz.get()
pos = np.array([x, y, z])
quat = np.array([qw, qx, qy, qz])
qpos = rb.inverse_kinematics(link=end_effector, pos=pos, quat=quat)
if qpos is None:
print("IK solution not found")
return
qpos_numpy = qpos.cpu().numpy()
path = rb.plan_path(qpos_goal=qpos, num_waypoints=300)
for waypoint in path:
rb.control_dofs_position(waypoint, np.arange(6))
scene.step()
# 목표 상태로 안정화
for _ in range(300):
current_pos_tensor = rb.get_dofs_position() # 현재 조인트 위치 (CUDA 텐서)
current_pos = current_pos_tensor.cpu().numpy()
if np.allclose(current_pos, qpos_numpy, atol=1e-1): # 목표 위치에 근접한지 확인
print("목표 위치에 도달!")
break # 목표 위치에 도달하면 루프 종료
scene.step()
update_joint_values(qpos_numpy)
except Exception as e:
print(f"Error in IK control: {e}")
current_joint_angles_degrees = []
def update_joint_values(joint_angles):
"""최종 각도 값을 GUI에 업데이트"""
global current_joint_angles_degrees
joint_angles_degrees = np.degrees(joint_angles) # 라디안 값을 각도로 변환
current_joint_angles_degrees = joint_angles_degrees
joint1_value.config(text=f"{joint_angles_degrees[0]:.2f}")
joint2_value.config(text=f"{joint_angles_degrees[1]:.2f}")
joint3_value.config(text=f"{joint_angles_degrees[2]:.2f}")
joint4_value.config(text=f"{joint_angles_degrees[3]:.2f}")
joint5_value.config(text=f"{joint_angles_degrees[4]:.2f}")
joint6_value.config(text=f"{joint_angles_degrees[5]:.2f}")
# Simulation step
def simulation_step():
if is_fk_mode:
fk_control()
emit_particles()
scene.step()
root.after(10, simulation_step)
# Create GUI
root = Tk()
root.title("Robot Control: FK & IK Modes")
# Mode display
mode_label = Label(root, text=f"Current Mode: {'FK' if is_fk_mode else 'IK'}", font=("Comic Sans MS", 12), relief=SUNKEN)
mode_label.grid(row=4, column=1, columnspan=4, pady=10) # Add mode label below IK sliders
# FK sliders
sliders = []
for i, name in enumerate(jnt_names):
slider = Scale(root, from_=-180, to=180, orient=HORIZONTAL, label=name, resolution=0.01, length=400)
slider.grid(row=i, column=0, padx=5, pady=5)
sliders.append(slider)
# IK controls
Label(root, text="IK Position (x, y, z)").grid(row=0, column=1, columnspan=3)
slider_x = Scale(root, from_=-1.0, to=1.0, resolution=0.01, orient=HORIZONTAL, label="X")
slider_y = Scale(root, from_=-1.0, to=1.0, resolution=0.01, orient=HORIZONTAL, label="Y")
slider_z = Scale(root, from_=0.0, to=3.0, resolution=0.01, orient=HORIZONTAL, label="Z")
slider_x.grid(row=1, column=1, padx=5, pady=5)
slider_y.grid(row=1, column=2, padx=5, pady=5)
slider_z.grid(row=1, column=3, padx=5, pady=5)
Label(root, text="IK Orientation (qw, qx, qy, qz)").grid(row=2, column=1, columnspan=4)
slider_qw = Scale(root, from_=-1.0, to=1.0, resolution=0.01, orient=HORIZONTAL, label="QW")
slider_qx = Scale(root, from_=-1.0, to=1.0, resolution=0.01, orient=HORIZONTAL, label="QX")
slider_qy = Scale(root, from_=-1.0, to=1.0, resolution=0.01, orient=HORIZONTAL, label="QY")
slider_qz = Scale(root, from_=-1.0, to=1.0, resolution=0.01, orient=HORIZONTAL, label="QZ")
slider_qw.grid(row=3, column=1, padx=5, pady=5)
slider_qx.grid(row=3, column=2, padx=5, pady=5)
slider_qy.grid(row=3, column=3, padx=5, pady=5)
slider_qz.grid(row=3, column=4, padx=5, pady=5)
# 현재 각도 표시
Label(root, text="Joint Angles (Degrees):").grid(row=0, column=5, columnspan=3, padx=20, pady=5)
Label(root, text="Joint 1:").grid(row=1, column=5, padx=10, pady=5, sticky="w")
joint1_value = Label(root, text="0.00", width=10, anchor="w", relief=SUNKEN)
joint1_value.grid(row=1, column=6, padx=10, pady=5)
Label(root, text="Joint 2:").grid(row=2, column=5, padx=10, pady=5, sticky="w")
joint2_value = Label(root, text="0.00", width=10, anchor="w", relief=SUNKEN)
joint2_value.grid(row=2, column=6, padx=10, pady=5)
Label(root, text="Joint 3:").grid(row=3, column=5, padx=10, pady=5, sticky="w")
joint3_value = Label(root, text="0.00", width=10, anchor="w", relief=SUNKEN)
joint3_value.grid(row=3, column=6, padx=10, pady=5)
Label(root, text="Joint 4:").grid(row=4, column=5, padx=10, pady=5, sticky="w")
joint4_value = Label(root, text="0.00", width=10, anchor="w", relief=SUNKEN)
joint4_value.grid(row=4, column=6, padx=10, pady=5)
Label(root, text="Joint 5:").grid(row=5, column=5, padx=10, pady=5, sticky="w")
joint5_value = Label(root, text="0.00", width=10, anchor="w", relief=SUNKEN)
joint5_value.grid(row=5, column=6, padx=10, pady=5)
Label(root, text="Joint 6:").grid(row=6, column=5, padx=10, pady=5, sticky="w")
joint6_value = Label(root, text="0.00", width=10, anchor="w", relief=SUNKEN)
joint6_value.grid(row=6, column=6, padx=10, pady=5)
# Mode toggle button
mode_button = Button(root, text="Switch to IK Mode", command=toggle_mode)
mode_button.grid(row=11, column=0, columnspan=2, pady=10)
# Move button for IK
move_button = Button(root, text="Move Robot (IK)", command=move_robot)
move_button.grid(row=11, column=3, columnspan=2, pady=10)
emit_button = Button(root, text="Start Emitting", command=toggle_emitter)
emit_button.grid(row=12, column=0, columnspan=4, pady=10) # grid 사용
# Start simulation loop
root.after(10, simulation_step)
# Run the GUI
root.mainloop()
Expected Behavior
I want particles to be emitted from the robot's end-effector and stick to the surface of a target object — just like spray paint attaching to a surface.
Ideally, I would also like the surface color to change where the particles land, simulating the visual effect of the painted area.
The goal is to realistically simulate a painting process, where the paint not only accumulates on the surface but also visually alters its appearance — all while maintaining acceptable simulation performance.
Environment
- OS: 22.04
- GPU/CPU [RTX 3090]
Release version or Commit ID
main branch