This project presents a reinforcement learning workflow for Embodied AI manipulation built on the Nero robotic arm, SO-ARM101, and NVIDIA Isaac Lab. It establishes a simulation-driven framework for training and evaluating robotic manipulation policies, with a focus on preparing the system for simulation-to-real transfer.
Project SummaryTech Stack- RL training pipeline
- policy validation process
- robotic manipulation task configuration
- simulation-to-real transfer preparation
Programming Language: Python 3.8+
Hardware: Nero Robotic Arm https://global.agilex.ai/products/nero
Base Framework: SO-ARM101 https://github.com/MuammerBay/isaac_so_arm101
Simulation Platform: NVIDIA Isaac Lab
Open-source implementation:https://github.com/agilexrobotics/Agilex-College/tree/master/isaac_sim/agx_arm_IsaacLab
Follow the official guide to install Isaac Lab:
👉 Isaac Lab Pip Installation Guide
We use the pip-based installation method (recommended).
Environment:- Conda virtual environment
- Python development environment
- NVIDIA Isaac Lab
- Nero robotic arm project dependencies
1.2 Install the uv Package Manager
This project uses uv as its Python package manager.
As a fast, next-generation tool, uv delivers:
- Faster package installation
- Efficient dependency resolution
- Built-in virtual environment management
Compared to traditional tools like pip, uv streamlines setup and reduces environment issues in Python-based robotics and embodied AI workflows.
First, install uv with a single command:
curl -LsSf https://astral.sh/uv/install.sh | shAfter installation, restart your terminal or run the following command to activate the uv environment:
source $HOME/.cargo/env1.3 Clone the Repository and Install DependenciesNext, clone the project repository, enter the project directory, and use `uv` to install all required dependencies with one command:
git clone https://github.com/smalleha/isaac_so_arm101.git
cd isaac_so_arm101
uv syncuv will automatically create a virtual environment and install all necessary dependency packages. The entire process usually takes only a few minutes and is significantly faster than traditional pip-based installation workflows.
To validate the setup for tasks, we first verify that the required simulation environments for the Nero robotic arm and Piper are properly registered:
uv run list_envsThe expected output should include Isaac-Nero-Reach-v0 and Isaac-Piper-Reach-v0, confirming that the environments have been installed successfully.
Next, run a simulation test with a zero-action agent to validate environment execution and ensure the robotic control pipeline works as expected:
# Test the Piper environment with a zero-action command
uv run zero_agent --task Isaac-SO-ARM100-Reach-v0If the simulation window launches and the robotic arm behaves as intended, the environment is confirmed to be ready.
This directory structure provides a clear overview of the project organization, making it easy to extend with new use cases such as Nero robotic arm example.
This project uses the Nero URDF model from the agx_arm_urdf repository. After cloning the repository,
copy the nero directory into the robots folder of the isaac_so_arm101 project:
git clone https://github.com/agilexrobotics/agx_arm_urdf.git
cd agx_arm_urdf/
cp -r nero/ isaac_so_arm101/robotsOnce the model has been copied, modify nero_description.urdf to make it compatible with Isaac Lab. Since the original URDF uses ROS-style package paths, these references must be converted to relative paths so that the link and mesh files can be correctly resolved. The base_link configuration is shown below as an example.
Before Edit
<link name="base_link">
<inertial>
<origin xyz="-0.00319465997 -0.00005467608 0.04321758463" rpy="0 0 0"/>
<mass value="1.06458435"/>
<inertia ixx="0.00102659855152" ixy="0.00000186219753" ixz="-0.00000295298037" iyy="0.00114399299508" iyz="-0.00000078763492" izz="0.00090872933022"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://agx_arm_description/agx_arm_urdf/nero/meshes/dae/base_link.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://agx_arm_description/agx_arm_urdf/nero/meshes/base_link.stl"/>
</geometry>
</collision>
</link>After Edit
<link name="base_link">
<inertial>
<origin xyz="-0.00319465997 -0.00005467608 0.04321758463" rpy="0 0 0"/>
<mass value="1.06458435"/>
<inertia ixx="0.00102659855152" ixy="0.00000186219753" ixz="-0.00000295298037" iyy="0.00114399299508" iyz="-0.00000078763492" izz="0.00090872933022"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="../meshes/dae/base_link.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="../meshes/base_link.stl"/>
</geometry>
</collision>
</link>Step 1.Importing the URDF Model
After modifying the URDF file, you need to write a Python script to import the URDF model and configure the robotic arm’s motor properties, including stiffness, damping, and other relevant parameters.
This script is typically placed at:
src/isaac_so_arm101/robots/nero/nero.py
The content of this file is shown below:
from pathlib import Path
import isaaclab.sim as sim_utils
from isaaclab.actuators import ImplicitActuatorCfg
from isaaclab.assets.articulation import ArticulationCfg
TEMPLATE_ASSETS_DATA_DIR = Path(__file__).resolve().parent
##
# Configuration
##
NERO_CFG = ArticulationCfg(
spawn=sim_utils.UrdfFileCfg(
fix_base=True,
replace_cylinders_with_capsules=True,
asset_path=f"{TEMPLATE_ASSETS_DATA_DIR}/urdf/nero_gripper.urdf",
activate_contact_sensors=False, # Disable contact sensors until capsule collision implementation is complete
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
max_depenetration_velocity=5.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=True,
solver_position_iteration_count=8,
solver_velocity_iteration_count=0,
),
joint_drive=sim_utils.UrdfConverterCfg.JointDriveCfg(
gains=sim_utils.UrdfConverterCfg.JointDriveCfg.PDGainsCfg(stiffness=0, damping=0)
),
),
init_state=ArticulationCfg.InitialStateCfg(
rot=(1.0, 0.0, 0.0, 0.0),
joint_pos={
"joint1": 0.0,
"joint2": 0.0,
"joint3": 0.0,
"joint4": 2.0,
"joint5": 0.0,
"joint6": 0.0,
"joint7": 0.0,
"gripper_joint1": 0.05,
"gripper_joint2": -0.05
},
# Set initial joint velocities to zero
joint_vel={".*": 0.0},
),
actuators={
"arm": ImplicitActuatorCfg(
joint_names_expr=["joint.*"],
effort_limit=25.0, # Moderate effort limit to prevent instantaneous impact shocks
velocity_limit=1.5,
# Stiffness: Optimized for the lightweight Piper robotic arm; prioritizes stability over maximum rigidity
stiffness={
"joint1": 200.0,
"joint2": 170.0,
"joint3": 120.0,
"joint4": 80.0,
"joint5": 50.0,
"joint6": 20.0,
"joint7": 10.0
},
# Damping: Critical damping strategy with ratio set to approximately 10%
damping={
"joint1": 100.0,
"joint2": 60.0,
"joint3": 70.0,
"joint4": 24.0,
"joint5": 20.0,
"joint6": 10.0,
"joint7": 5,
},
),
"gripper": ImplicitActuatorCfg(
joint_names_expr=["gripper_joint1","gripper_joint2"],
effort_limit_sim=22, # Increased from 1.9 to 2.5 for stronger grip
velocity_limit_sim=1.5,
stiffness=800.0, # Increased from 25.0 to 60.0 for more reliable closing
damping=20.0, # Increased from 10.0 to 20.0 for stability
),
},
soft_joint_pos_limit_factor=0.9,
)Next, create an __init__.py file to initialize the directory as a Python module.
Step 2.Create Task Configuration FilesIn the tasks/lift directory, create the following files:
- nero_joint_pos_env_cfg.py
- nero_lift_env_cfg.py
The nero_joint_pos_env_cfg.py file defines the environment configuration for joint position control, including the controllable joints, the robot end-effector link, and the basic task parameters.
# Copyright (c) 2024-2025, Muammer Bay (LycheeAI), Louis Le Lay
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
#
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
import isaaclab_tasks.manager_based.manipulation.lift.mdp as mdp
from isaaclab.assets import RigidObjectCfg
# from isaaclab.managers NotImplementedError
from isaaclab.sensors.frame_transformer.frame_transformer_cfg import (
FrameTransformerCfg,
OffsetCfg,
)
from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg
from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg
from isaaclab.utils import configclass
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR
from isaac_so_arm101.robots import SO_ARM100_CFG, SO_ARM101_CFG # noqa: F401
# from isaac_so_arm101.tasks.lift.lift_env_cfg import LiftEnvCfg
from isaac_so_arm101.tasks.lift.nero_lift_env_cfg import LiftEnvCfg
from isaaclab.markers.config import FRAME_MARKER_CFG # isort: skip
# from isaac_so_arm101.robots.piper_description.piper import PIPER_CFG
from isaac_so_arm101.robots.nero_description.nero import NERO_CFG
@configclass
class NeroLiftCubeEnvCfg(LiftEnvCfg):
def __post_init__(self):
# post init of parent
super().__post_init__()
# Set so arm as robot
self.scene.robot = NERO_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# override actions
self.actions.arm_action = mdp.JointPositionActionCfg(
asset_name="robot",
joint_names=["joint1", "joint2", "joint3", "joint4", "joint5", "joint6","joint7" ],
scale=0.5,
use_default_offset=True,
)
self.actions.gripper_action = mdp.BinaryJointPositionActionCfg(
asset_name="robot",
joint_names=["gripper_joint1","gripper_joint2"],
open_command_expr={"gripper_joint2": -0.05,"gripper_joint1":0.05},
close_command_expr={"gripper_joint2": -0.001,"gripper_joint1":0.0},
)
# Set the body name for the end effector
self.commands.object_pose.body_name = ["gripper_base"]
# Set Cube as object
self.scene.object = RigidObjectCfg(
prim_path="{ENV_REGEX_NS}/Object",
init_state=RigidObjectCfg.InitialStateCfg(pos=[0.2, 0.0, 0.015], rot=[1, 0, 0, 0]),
spawn=UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd",
scale=(0.5, 0.5, 0.5),
rigid_props=RigidBodyPropertiesCfg(
solver_position_iteration_count=16,
solver_velocity_iteration_count=1,
max_angular_velocity=1000.0,
max_linear_velocity=1000.0,
max_depenetration_velocity=5.0,
disable_gravity=False,
),
),
)
# Listens to the required transforms
marker_cfg = FRAME_MARKER_CFG.copy()
marker_cfg.markers["frame"].scale = (0.05, 0.05, 0.05)
marker_cfg.prim_path = "/Visuals/FrameTransformer"
self.scene.ee_frame = FrameTransformerCfg(
prim_path="{ENV_REGEX_NS}/Robot/base_link",
debug_vis=True,
visualizer_cfg=marker_cfg,
target_frames=[
FrameTransformerCfg.FrameCfg(
prim_path="{ENV_REGEX_NS}/Robot/gripper_base",
name="end_effector",
offset=OffsetCfg(
pos=[0.0, 0.0, 0.125],
),
),
],
)
@configclass
class NeroLiftCubeEnvCfg_PLAY(NeroLiftCubeEnvCfg):
def __post_init__(self):
# post init of parent
super().__post_init__()
# make a smaller scene for play
self.scene.num_envs = 50
self.scene.env_spacing = 2.5
# disable randomization for play
self.observations.policy.enable_corruption = FalseThe nero_lift_env_cfg.py file provides the base environment configuration for the lifting task. It specifies the task reward, penalties, policy setup, target point position, and block position, which together define the behavior and objective of the environment.
# Copyright (c) 2024-2025, Muammer Bay (LycheeAI), Louis Le Lay
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
#
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from dataclasses import MISSING
import isaaclab.sim as sim_utils
# from . import mdp
import isaac_so_arm101.tasks.lift.mdp as mdp
from isaaclab.assets import (
ArticulationCfg,
AssetBaseCfg,
DeformableObjectCfg,
RigidObjectCfg,
)
from isaaclab.envs import ManagerBasedRLEnvCfg
from isaaclab.managers import CurriculumTermCfg as CurrTerm
from isaaclab.managers import EventTermCfg as EventTerm
from isaaclab.managers import ObservationGroupCfg as ObsGroup
from isaaclab.managers import ObservationTermCfg as ObsTerm
from isaaclab.managers import RewardTermCfg as RewTerm
from isaaclab.managers import SceneEntityCfg
from isaaclab.managers import TerminationTermCfg as DoneTerm
from isaaclab.scene import InteractiveSceneCfg
from isaaclab.sensors.frame_transformer.frame_transformer_cfg import FrameTransformerCfg
from isaaclab.sim.spawners.from_files.from_files_cfg import GroundPlaneCfg, UsdFileCfg
from isaaclab.utils import configclass
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR
# from isaaclab.utils.offset import OffsetCfg
# from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise
# from isaaclab.utils.visualizer import FRAME_MARKER_CFG
# from isaaclab.utils.assets import RigidBodyPropertiesCfg
##
# Scene definition
##
@configclass
class ObjectTableSceneCfg(InteractiveSceneCfg):
"""Configuration for the lift scene with a robot and a object.
This is the abstract base implementation, the exact scene is defined in the derived classes
which need to set the target object, robot and end-effector frames
"""
# robots: will be populated by agent env cfg
robot: ArticulationCfg = MISSING
# end-effector sensor: will be populated by agent env cfg
ee_frame: FrameTransformerCfg = MISSING
# target object: will be populated by agent env cfg
object: RigidObjectCfg | DeformableObjectCfg = MISSING
# Table
table = AssetBaseCfg(
prim_path="{ENV_REGEX_NS}/Table",
init_state=AssetBaseCfg.InitialStateCfg(pos=[0.5, 0, 0], rot=[0.707, 0, 0, 0.707]),
spawn=UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/SeattleLabTable/table_instanceable.usd"),
)
# plane
plane = AssetBaseCfg(
prim_path="/World/GroundPlane",
init_state=AssetBaseCfg.InitialStateCfg(pos=[0, 0, -1.05]),
spawn=GroundPlaneCfg(),
)
# lights
light = AssetBaseCfg(
prim_path="/World/light",
spawn=sim_utils.DomeLightCfg(color=(0.75, 0.75, 0.75), intensity=3000.0),
)
##
# MDP settings
##
@configclass
class CommandsCfg:
"""Command terms for the MDP."""
object_pose = mdp.UniformPoseCommandCfg(
asset_name="robot",
body_name=MISSING, # will be set by agent env cfg
resampling_time_range=(5.0, 5.0),
debug_vis=True,
ranges=mdp.UniformPoseCommandCfg.Ranges(
pos_x=(0.3, 0.35),
pos_y=(-0.2, 0.2),
pos_z=(0.2, 0.35),
roll=(0.0, 0.0),
pitch=(0.0, 0.0),
yaw=(0.0, 0.0),
),
)
@configclass
class ActionsCfg:
"""Action specifications for the MDP."""
# will be set by agent env cfg
arm_action: mdp.JointPositionActionCfg | mdp.DifferentialInverseKinematicsActionCfg = MISSING
gripper_action: mdp.BinaryJointPositionActionCfg = MISSING
@configclass
class ObservationsCfg:
"""Observation specifications for the MDP."""
@configclass
class PolicyCfg(ObsGroup):
"""Observations for policy group."""
joint_pos = ObsTerm(func=mdp.joint_pos_rel)
joint_vel = ObsTerm(func=mdp.joint_vel_rel)
object_position = ObsTerm(func=mdp.object_position_in_robot_root_frame)
target_object_position = ObsTerm(func=mdp.generated_commands, params={"command_name": "object_pose"})
actions = ObsTerm(func=mdp.last_action)
def __post_init__(self):
self.enable_corruption = True
self.concatenate_terms = True
# observation groups
policy: PolicyCfg = PolicyCfg()
@configclass
class EventCfg:
"""Configuration for events."""
reset_all = EventTerm(func=mdp.reset_scene_to_default, mode="reset")
reset_object_position = EventTerm(
func=mdp.reset_root_state_uniform,
mode="reset",
params={
"pose_range": {"x": (0.1, 0.2), "y": (-0.1, 0.2), "z": (0.0, 0.0)},
"velocity_range": {},
"asset_cfg": SceneEntityCfg("object", body_names="Object"),
},
)
@configclass
class RewardsCfg:
"""Reward terms for the MDP."""
reaching_object = RewTerm(func=mdp.object_ee_distance, params={"std": 0.05}, weight=1.0)
lifting_object = RewTerm(func=mdp.object_is_lifted, params={"minimal_height": 0.025}, weight=15.0)
object_goal_tracking = RewTerm(
func=mdp.object_goal_distance,
params={"std": 0.3, "minimal_height": 0.025, "command_name": "object_pose"},
weight=16.0,
)
object_goal_tracking_fine_grained = RewTerm(
func=mdp.object_goal_distance,
params={"std": 0.05, "minimal_height": 0.025, "command_name": "object_pose"},
weight=5.0,
)
# action penalty
action_rate = RewTerm(func=mdp.action_rate_l2, weight=-1e-4)
joint_vel = RewTerm(
func=mdp.joint_vel_l2,
weight=-1e-4,
params={"asset_cfg": SceneEntityCfg("robot")},
)
@configclass
class TerminationsCfg:
"""Termination terms for the MDP."""
time_out = DoneTerm(func=mdp.time_out, time_out=True)
object_dropping = DoneTerm(
func=mdp.root_height_below_minimum, params={"minimum_height": -0.05, "asset_cfg": SceneEntityCfg("object")}
)
@configclass
class CurriculumCfg:
"""Curriculum terms for the MDP."""
action_rate = CurrTerm(
func=mdp.modify_reward_weight, params={"term_name": "action_rate", "weight": -1e-1, "num_steps": 10000}
)
joint_vel = CurrTerm(
func=mdp.modify_reward_weight, params={"term_name": "joint_vel", "weight": -1e-1, "num_steps": 10000}
)
##
# Environment configuration
##
@configclass
class LiftEnvCfg(ManagerBasedRLEnvCfg):
"""Configuration for the lifting environment."""
# Scene settings
scene: ObjectTableSceneCfg = ObjectTableSceneCfg(num_envs=4096, env_spacing=2.5)
# Basic settings
observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg()
commands: CommandsCfg = CommandsCfg()
# MDP settings
rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg()
events: EventCfg = EventCfg()
curriculum: CurriculumCfg = CurriculumCfg()
def __post_init__(self):
"""Post initialization."""
# general settings
self.decimation = 2
self.episode_length_s = 5.0
self.viewer.eye = (2.5, 2.5, 1.5)
# simulation settings
self.sim.dt = 0.01 # 100Hz
self.sim.render_interval = self.decimation
self.sim.physx.bounce_threshold_velocity = 0.2
self.sim.physx.bounce_threshold_velocity = 0.01
self.sim.physx.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4
self.sim.physx.gpu_total_aggregate_pairs_capacity = 16 * 1024
self.sim.physx.friction_correlation_distance = 0.00625Then, the nero reach task needs to be registered in src/isaac_so_arm101/tasks/reach/__init__.py
# Copyright (c) 2024-2025, Muammer Bay (LycheeAI), Louis Le Lay
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
#
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
import gymnasium as gym
from . import agents
##
# Register Gym environments.
##
gym.register(
id="Isaac-SO-ARM100-Lift-Cube-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:SoArm100LiftCubeEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:LiftCubePPORunnerCfg",
},
disable_env_checker=True,
)
gym.register(
id="Isaac-SO-ARM100-Lift-Cube-Play-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:SoArm100LiftCubeEnvCfg_PLAY",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:LiftCubePPORunnerCfg",
},
disable_env_checker=True,
)
gym.register(
id="Isaac-SO-ARM101-Lift-Cube-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:SoArm101LiftCubeEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:LiftCubePPORunnerCfg",
},
disable_env_checker=True,
)
gym.register(
id="Isaac-SO-ARM101-Lift-Cube-Play-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
kwargs={
"env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:SoArm101LiftCubeEnvCfg_PLAY",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:LiftCubePPORunnerCfg",
},
disable_env_checker=True,
)
gym.register(
id="Isaac-Nero-Lift-Cube-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
kwargs={
"env_cfg_entry_point": f"{__name__}.nero_joint_pos_env_cfg:NeroLiftCubeEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:LiftCubePPORunnerCfg",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
},
disable_env_checker=True,
)6. An Isaac Lab Training and Evaluation PipelineFirst, activate the Conda environment:
conda activate env_isaaclabThen switch to the project directory:
cd isaac_so_arm101Start training the Isaac-Nero-Lift-Cube-v0 task in headless mode to reduce GPU and display overhead:
uv run train --task Isaac-Nero-Lift-Cube-v0 --headlessIf your hardware is strong enough, you can also run training with visualization enabled to observe the learning process directly:
uv run train --task Isaac-Nero-Lift-Cube-v0This task is trained for 1, 000 iterations. Once training is finished, use the following command to evaluate the learned policy:
uv run play --task Isaac-Nero-Lift-Cube-v0Key outcomes of this work include:
- URDF Model Integration
- Reproducible RL Training Pipeline
- Environment Validation
The workflow can also be extended to more complex manipulation scenarios, including multi-object grasping and obstacle avoidance, with the Nero robotic arm serving as the deployment target for simulation-to-real transfer.
💬 FAQWhat is inverse kinematics in robotics?Inverse kinematics (IK) calculates the required joint angles for a robotic arm to reach a target position and orientation.
How does ROS2 help with robot arm control?ROS2 provides communication, motion control, and integration tools for robotic manipulators, including MoveIt2 and RViz.
What is the difference between FK and IK?Forward kinematics calculates the end-effector position from joint angles, while inverse kinematics calculates joint angles from a target pose.
Why use MoveIt2 for robot arms?MoveIt2 simplifies robot arm motion planning, collision checking, and trajectory execution in ROS2 environments.
Can this IK solver run on a real robot arm?Yes. The parametric IK solver can be deployed on physical robot arms after proper calibration and controller integration.
Does NERO Arm support Gazebo simulation?Yes. The NERO Arm can be simulated in Gazebo and visualized in RViz for testing and development.
StillHave Question? If you encounter any issues with environment installation, parameter configuration, or RL training, feel free to leave your questions for further discussion.



Comments