Joint Control
The joint module provides robot arm manipulation and joint control capabilities.
Important Note: Joint trajectories can be stopped reliably using abort signals or the stop methods. The stop button in SDK Playground works throughout the entire trajectory execution.
detectArmJoints(options)
Auto-detect arm joints (excluding grippers, legs, and torso joints). Filters for joints with arm-specific naming (shoulder, elbow, wrist) and auto-selects one side when both arms exist.
Parameters:
options.side(string, optional) - Preferred side:'left','right', ornull(auto-detect, prefers left). Default:nulloptions.maxJoints(number, optional) - Maximum joints to return. Default:7options.armPatterns(Array<RegExp>, optional) - Patterns to identify arm joints. Default:[/(shoulder|elbow|wrist|arm)/i]options.excludePatterns(Array<RegExp>, optional) - Patterns to exclude. Default:[/(finger|hand|grip|gripper|thumb|palm)/i]
Returns: Promise<Array> - Array of detected arm joint names
// Auto-detect (prefers left arm)
const armJoints = await oloClient.joint.detectArmJoints();
// Detect right arm specifically
const rightArm = await oloClient.joint.detectArmJoints({ side: 'right' });getCurrentJointStates()
Get current joint positions and states.
Returns: Promise<Object> - Current joint states
const jointStates = await oloClient.joint.getCurrentJointStates();
console.log('Joint positions:', jointStates.jointStates);moveJointsToPositions(jointNames, positions, options)
Move specified joints to target positions. Supports abort signals for safe cancellation.
Parameters:
jointNames(Array) - Array of joint namespositions(Array) - Array of target positions in radiansoptions(object, optional) - Movement optionsduration(number) - Movement duration in seconds (default: 2)topic(string) - Trajectory topic (optional, will auto-detect)currentPositions(Array) - Current positions (optional, will fetch if not provided)abortSignal(AbortSignal) - Signal to abort movement safely
Returns: Promise - Resolves when trajectory is sent or rejects if aborted
// SDK Playground version (abortSignal automatically provided)
const armJoints = await oloClient.joint.detectArmJoints();
const targetPositions = [0.1, 0.2, -0.1, 0.0, 0.0, 0.0];
try {
await oloClient.joint.moveJointsToPositions(armJoints, targetPositions, {
duration: 3.0,
abortSignal // Automatically provided by playground
});
console.log('✅ Joint movement completed');
} catch (error) {
if (error.message === 'Aborted') {
console.log('🛑 Joint movement cancelled by user');
}
}
// Standalone version (create your own AbortController)
const controller = new AbortController();
await oloClient.joint.moveJointsToPositions(armJoints, targetPositions, {
duration: 3.0,
abortSignal: controller.signal
});
// Emergency stop: controller.abort();detectJointTrajectoryTopic(jointNames)
Auto-detect joint trajectory topic for arm control. When multiple controllers exist and joint names are provided, matches the controller that manages those specific joints.
Parameters:
jointNames(Array<string>, optional) - Joint names to match against controllers. When provided with multiple controllers, the best-matching controller is selected.
Returns: Promise<string> - Trajectory topic name
// Auto-detect (picks first trajectory controller)
const trajectoryTopic = await oloClient.joint.detectJointTrajectoryTopic();
// Match controller to specific joints
const armJoints = await oloClient.joint.detectArmJoints({ side: 'right' });
const topic = await oloClient.joint.detectJointTrajectoryTopic(armJoints);
// Returns: '/g1_right_arm_controller/joint_trajectory'stopJointMovement(topic, jointNames)
Stop joint movement immediately.
Parameters:
topic(string) - Trajectory topic namejointNames(Array) - Array of joint names to stop
Returns: Promise - Resolves when stop command is sent
// Stop arm movement immediately
const armJoints = await oloClient.joint.detectArmJoints();
const trajectoryTopic = await oloClient.joint.detectJointTrajectoryTopic();
await oloClient.joint.stopJointMovement(trajectoryTopic, armJoints);stopAllJoints()
Stop all arm joints immediately (convenience method).
Returns: Promise - Resolves when stop trajectory is sent
// Emergency stop for all arm joints
await oloClient.joint.stopAllJoints();moveEndEffectorToPosition(targetPose, options)
Move end effector to target position using inverse kinematics planning. Supports abort signals for safe cancellation.
Parameters:
targetPose(object) - Target pose for end effectorposition(object) - Target position {x, y, z} in metersorientation(object, optional) - Target orientation {x, y, z, w} (quaternion, defaults to pointing down)
options(object, optional) - Movement optionsplanningGroup(string, optional) - MoveIt planning group (will auto-detect if not provided)endEffectorLink(string, optional) - End effector link name (will auto-detect if not provided)baseFrame(string, optional) - Base frame for pose coordinates (will auto-detect if not provided)timeout(number) - Planning timeout in seconds (default: 5)executeTrajectory(boolean) - Whether to execute the planned trajectory (default: true)speed(number) - Speed multiplier for trajectory execution (default: 1.0)0.25- Very slow, cautious movements0.5- Slow1.0- Normal speed (1.0 rad/sec base velocity)1.5- Fast2.0- Very fast
maxJointDisplacement(number) - Maximum radians each joint can move from current position (default: PI = 180 degrees). Use lower values to prevent sweeping moves:Math.PI(default) - Wide tolerance, allows large reconfigurations1.0(~57 deg) - Moderate constraint0.5(~30 deg) - Tight constraint, forces nearby IK solutions0.3(~17 deg) - Very tight, for small incremental moves
useMotionPlanning(boolean) - Use MoveIt's path planner to compute a collision-free trajectory that avoids obstacles in the planning scene (default: false). When enabled, MoveIt uses OMPL planners (e.g. RRTConnect) to find a multi-waypoint path around collision objects. When disabled, the robot moves directly in joint space from its current position to the target (faster but may collide with obstacles). Obstacles can be added to the planning scene programmatically viaaddCollisionObjects()or through the Cell Editor's "Sync to MoveIt" button.abortSignal(AbortSignal) - Signal to abort movement safely
Returns: Promise<Object> - Resolves with planning result or rejects if failed/aborted
// SDK Playground version (abortSignal automatically provided)
try {
// Move end effector to specific position
const result = await oloClient.joint.moveEndEffectorToPosition({
position: { x: 0.5, y: 0.2, z: 0.3 },
orientation: { x: 0, y: 0, z: 0, w: 1 } // Optional, defaults to pointing down
}, {
timeout: 10,
executeTrajectory: true,
speed: 1.0, // Normal speed (default)
abortSignal // Automatically provided by playground
});
console.log('End effector movement completed:', result);
} catch (error) {
if (error.message === 'Aborted') {
console.log('End effector movement cancelled by user');
} else {
console.error('Movement failed:', error);
}
}
// Fast movement example
const result = await oloClient.joint.moveEndEffectorToPosition({
position: { x: 0.4, y: -0.1, z: 0.25 }
}, {
speed: 1.5, // 1.5x faster than normal
abortSignal
});
// Slow, cautious movement example
await oloClient.joint.moveEndEffectorToPosition({
position: { x: 0.3, y: 0.0, z: 0.4 }
}, {
speed: 0.5, // Half speed for precision
abortSignal
});
// Constrained movement - prevents sweeping/floor-hitting moves
// Useful for small incremental movements like visual servoing
await oloClient.joint.moveEndEffectorToPosition({
position: { x: 0.35, y: 0.05, z: 0.38 }
}, {
maxJointDisplacement: 0.5, // Max 30 degrees per joint
speed: 0.8,
abortSignal
});
// Collision-free movement - plans around obstacles in the scene
// First sync obstacles to MoveIt (via Cell Editor "Sync to MoveIt" or SDK),
// then enable motion planning to avoid them during execution
await oloClient.joint.moveEndEffectorToPosition({
position: { x: 0.4, y: -0.2, z: 0.3 }
}, {
useMotionPlanning: true, // Use OMPL planner to avoid obstacles
timeout: 10, // Allow more time for path planning
speed: 0.8,
abortSignal
});
// Advanced usage with custom parameters
const result = await oloClient.joint.moveEndEffectorToPosition({
position: { x: 0.4, y: -0.1, z: 0.25 }
}, {
planningGroup: 'panda_arm', // Specific planning group
endEffectorLink: 'panda_link8', // Specific end effector link
baseFrame: 'base_link', // Specific base frame
timeout: 15, // Longer timeout for complex moves
executeTrajectory: true, // Execute the planned path
speed: 2.0, // Double speed
useMotionPlanning: true, // Plan around obstacles
abortSignal // Enable cancellation
});
// Position-only movement (orientation will default, speed will be 1.0)
await oloClient.joint.moveEndEffectorToPosition({
position: { x: 0.3, y: 0.0, z: 0.4 }
});
// Standalone version (create your own AbortController)
const controller = new AbortController();
await oloClient.joint.moveEndEffectorToPosition({
position: { x: 0.5, y: 0.2, z: 0.3 }
}, {
speed: 1.0,
abortSignal: controller.signal
});
// Emergency stop: controller.abort();executePlannedTrajectory(planResult, options)
Execute a previously planned trajectory. This enables a two-step workflow: plan first (with executeTrajectory: false), review/validate the plan, then execute it separately. Supports abort signals for safe cancellation.
Parameters:
planResult(object) - The planning result frommoveEndEffectorToPositionwithexecuteTrajectory: falsejoint_names(Array<string>) - Joint names from the planjoint_positions(Array<number>) - Target joint positions from the plan
options(object, optional) - Execution optionsspeed(number, optional) - Speed multiplier: 0.25=slow, 1.0=normal (default), 2.0=fastabortSignal(AbortSignal, optional) - Signal to abort movement safely
Returns: Promise<Object> - Execution result with:
success(boolean) - Whether execution completed successfullyjoint_names(Array<string>) - Joint names that were movedjoint_positions(Array<number>) - Final joint positionsexecution_time(number) - Duration of execution in secondsexecution(object) - Execution details from the appliance
Example - Two-Step Plan-Then-Execute Workflow:
// Step 1: Plan only (no execution)
const targetPose = { position: { x: 0.5, y: 0.1, z: 0.4 } };
console.log('Step 1: Planning trajectory...');
const planResult = await oloClient.joint.moveEndEffectorToPosition(targetPose, {
executeTrajectory: false, // Plan but don't execute
timeout: 5,
abortSignal
});
// Check if planning was successful
if (!planResult.joint_names) {
console.error('No valid IK solution found - target may be unreachable');
return;
}
// Review the planned joint positions
console.log('Planned joint solution:');
planResult.joint_names.forEach((joint, i) => {
const pos = planResult.joint_positions[i];
console.log(` ${joint}: ${pos.toFixed(3)} rad (${(pos * 180/Math.PI).toFixed(1)} deg)`);
});
// Step 2: Execute the planned trajectory
console.log('Step 2: Executing planned trajectory...');
const executionResult = await oloClient.joint.executePlannedTrajectory(planResult, {
speed: 1.0, // Normal speed
abortSignal // Allows cancellation during execution
});
console.log('Execution completed:', executionResult);Example - Pre-plan Multiple Waypoints, Validate All, Then Execute:
const poses = [
{ position: { x: 0.4, y: 0.1, z: 0.5 } },
{ position: { x: 0.5, y: 0.0, z: 0.4 } },
{ position: { x: 0.4, y: -0.1, z: 0.5 } }
];
// Step 1: Plan all poses first (no execution)
console.log('Planning all waypoints...');
const plans = [];
for (const [i, pose] of poses.entries()) {
const plan = await oloClient.joint.moveEndEffectorToPosition(pose, {
executeTrajectory: false,
timeout: 5,
abortSignal
});
if (!plan.joint_names) {
console.error(`Waypoint ${i + 1} is unreachable! Aborting.`);
return;
}
plans.push(plan);
console.log(`Waypoint ${i + 1} planned successfully`);
}
console.log(`All ${plans.length} waypoints are reachable!`);
// Step 2: Execute all planned trajectories
console.log('Executing planned path...');
for (const [i, plan] of plans.entries()) {
console.log(`Executing waypoint ${i + 1}/${plans.length}...`);
await oloClient.joint.executePlannedTrajectory(plan, {
speed: 0.8, // Slightly slower for safety
abortSignal
});
console.log(`Reached waypoint ${i + 1}`);
}
console.log('Path execution complete!');Gripper Control
The joint module provides gripper control capabilities using MoveIt planning. The gripper control methods require both a planning group and controller name to be specified.
getAvailablePlanningGroups()
Get list of available planning groups from robot configuration.
Returns: Promise<Array<string>> - Array of planning group names
const planningGroups = await oloClient.joint.getAvailablePlanningGroups();
console.log('Available planning groups:', planningGroups);
// Returns: ['panda_arm', 'hand', 'panda_arm_hand']getActionServers()
Get list of available action servers from the appliance.
Returns: Promise<Array<string>> - Array of action server names
const actionServers = await oloClient.joint.getActionServers();
console.log('Available action servers:', actionServers);
// Returns: ['/execute_trajectory', '/move_action', '/panda_hand_controller/gripper_cmd']getCurrentEndEffectorPose(options)
Get current end effector pose.
Parameters:
options(object, optional) - OptionsplanningGroup(string) - MoveIt planning group (default: auto-detect)endEffectorLink(string) - End effector link name (default: auto-detect)baseFrame(string) - Base frame for pose coordinates (default: auto-detect)
Returns: Promise<Object> - Current pose with position {x, y, z} and orientation {x, y, z, w}
const pose = await oloClient.joint.getCurrentEndEffectorPose();
console.log('Position:', pose.position);
console.log('Orientation:', pose.orientation);controlGripper(options)
Control gripper using MoveIt planning. Supports abort signals for safe cancellation.
Parameters:
options(object) - Gripper control optionsplanningGroup(string) - Planning group name for gripper (required)controllerName(string) - Controller name for gripper (required)jointNames(Array<string>) - Joint names for the gripper (optional, auto-detected from SRDF if not provided)position(number) - Target position (required). By default: 0.0 = closed, 1.0 = openisNormalized(boolean) - If true (default), position is 0-1 range and will be scaled. If false, position is the actual joint value (in radians or meters)maxEffort(number) - Maximum effort for gripper (default: 20.0)timeout(number) - Command timeout in seconds (default: 5)abortSignal(AbortSignal) - Signal to abort movement safely
Note: Joint names are automatically detected from the SRDF planning group definition. If auto-detection fails or you need to specify different joints, provide jointNames explicitly.
Position Scaling: By default, the SDK uses normalized positions (0.0 = closed, 1.0 = open) and automatically scales to actual joint limits. Joint type (revolute/prismatic) and limits are automatically detected from the URDF for accurate scaling. This works correctly for both:
- Prismatic grippers: positions in meters
- Revolute grippers: positions in radians
When replaying recorded waypoints with actual joint positions, set isNormalized: false to bypass scaling and use the position value directly.
Returns: Promise<Object> - Resolves with gripper control result
// Get available planning groups and action servers
const planningGroups = await oloClient.joint.getAvailablePlanningGroups();
const actionServers = await oloClient.joint.getActionServers();
// Find gripper-related planning group and controller
const gripperGroup = planningGroups.find(group => /gripper|hand/i.test(group));
const gripperController = actionServers.find(action => /gripper_cmd/i.test(action));
// Control gripper with explicit parameters
await oloClient.joint.controlGripper({
planningGroup: gripperGroup, // e.g., 'hand'
controllerName: gripperController, // e.g., '/panda_hand_controller/gripper_cmd'
position: 1.0, // Fully open
maxEffort: 20.0,
timeout: 5,
abortSignal // Automatically provided by SDK Playground
});
// Close gripper
await oloClient.joint.controlGripper({
planningGroup: gripperGroup,
controllerName: gripperController,
position: 0.0, // Fully closed
abortSignal
});openGripper(options)
Open gripper (convenience method). Requires same parameters as controlGripper().
Parameters:
options(object) - Options for gripper control (planningGroup and controllerName required)
Returns: Promise<Object> - Resolves with gripper control result
await oloClient.joint.openGripper({
planningGroup: 'hand',
controllerName: '/panda_hand_controller/gripper_cmd',
timeout: 5,
abortSignal
});closeGripper(options)
Close gripper (convenience method). Requires same parameters as controlGripper().
Parameters:
options(object) - Options for gripper control (planningGroup and controllerName required)
Returns: Promise<Object> - Resolves with gripper control result
await oloClient.joint.closeGripper({
planningGroup: 'hand',
controllerName: '/panda_hand_controller/gripper_cmd',
timeout: 5,
abortSignal
});Important Notes:
- Planning Group: Use
getAvailablePlanningGroups()to find gripper-related groups (typically named 'gripper', 'hand', etc.) - Controller Name: Use
getActionServers()to find gripper controllers (typically ending in '/gripper_cmd') - Position Range: 0.0 = fully closed, 1.0 = fully open, intermediate values for partial opening
- MoveIt Planning: Uses MoveIt2 for safe, planned gripper movements
- Robot Agnostic: Works with any robot that has MoveIt-configured gripper planning groups
End Effector Positioning Notes:
- Auto-detection: If
planningGroup,endEffectorLink, orbaseFrameare not specified, they will be automatically detected from robot configuration - Coordinate system: Position coordinates are in the base frame (typically
base_link) - Planning vs Execution: Set
executeTrajectory: falseto only plan the path without executing it - Safety: Always use abort signals for movements that users might need to cancel
- Robot-specific: The method automatically adapts to different robot types (Panda, UR, etc.)
MoveIt Engine Control
The joint module provides methods to start and stop the MoveIt2 motion planning framework on the appliance. This is useful when MoveIt is not automatically started with the robot or simulation. The appliance will auto-detect the appropriate MoveIt configuration based on the currently connected robot.
listMoveItConfigs()
List available MoveIt configuration packages installed on the appliance.
Returns: Promise<Array> - Array of config objects:
package(string) - Package namelaunchFile(string) - Detected launch file namehasLaunchFile(boolean) - Whether a launch file was found
// List available MoveIt configurations
const configs = await oloClient.joint.listMoveItConfigs();
console.log('Available configs:');
configs.forEach(config => {
console.log(` - ${config.package} (${config.launchFile})`);
});
// Example output:
// Available configs:
// - moveit_resources_panda_moveit_config (demo.launch.py)
// - ur_moveit_config (ur_moveit.launch.py)startMoveItEngine(options)
Start the MoveIt2 motion planning engine on the appliance.
Parameters:
options(object, optional) - Configuration optionsconfigPackage(string) - MoveIt config package name to use (recommended when multiple configs are installed)moveGroupOnly(boolean) - If true, only start move_group node (robot driver must already be running). Use this when your robot's ROS2 driver is running on the robot itself or another computer.robotNamespace(string) - Robot namespace for multi-robot scenariosuseSimTime(boolean) - Use simulation time (auto-detected if not specified)
Returns: Promise<Object> - Result with:
success(boolean) - Whether MoveIt started successfullylaunchPackage(string) - The MoveIt config package usedlaunchFile(string) - The launch file usedalready_running(boolean) - True if MoveIt was already runningwarning(string, optional) - Any warnings during startup
// First, list available configs
const configs = await oloClient.joint.listMoveItConfigs();
// Start move_group only (robot already running elsewhere)
// This is the typical use case for real robots
const result = await oloClient.joint.startMoveItEngine({
configPackage: 'moveit_resources_panda_moveit_config',
moveGroupOnly: true // Robot driver already running
});
// Start full MoveIt demo (includes robot simulation)
// Use this for testing/simulation when no real robot is connected
await oloClient.joint.startMoveItEngine({
configPackage: 'moveit_resources_panda_moveit_config',
moveGroupOnly: false // Launch everything including robot simulation
});
// Auto-detect (only works if one config installed)
await oloClient.joint.startMoveItEngine({ moveGroupOnly: true });stopMoveItEngine()
Stop the MoveIt2 motion planning engine on the appliance.
Returns: Promise<Object> - Result with success status
// Stop MoveIt engine
await oloClient.joint.stopMoveItEngine();getMoveItStatus()
Check the MoveIt engine status on the appliance.
Returns: Promise<Object> - Status object with:
is_running(boolean) - Whether MoveIt processes are runningmoveit_available(boolean) - Whether MoveIt services are availablerunning_components(Array) - List of running component namessource(string) - How the status was determined
// Check if MoveIt is running
const status = await oloClient.joint.getMoveItStatus();
if (status.is_running) {
console.log('MoveIt is running');
console.log('Components:', status.running_components.join(', '));
console.log('Services available:', status.moveit_available);
} else {
console.log('MoveIt is not running');
// Start MoveIt if needed
await oloClient.joint.startMoveItEngine();
}MoveIt Engine Notes:
- List first: Use
listMoveItConfigs()to see available configurations before starting - Specify config: When multiple configs are installed, specify
configPackageto avoid ambiguity - moveGroupOnly mode: Set
moveGroupOnly: truewhen your robot's ROS2 driver is already running (e.g., on the robot's computer). This only starts the move_group node which connects to the existing robot via/joint_statesand/robot_descriptiontopics. - Full demo mode: Set
moveGroupOnly: false(or omit) to launch the complete MoveIt demo including robot simulation - useful for testing when no real robot is connected. - Startup time: MoveIt typically takes 10-30 seconds to fully initialize all components
- Prerequisites: A MoveIt config package must be installed on the appliance for your robot
- Services: Once running, MoveIt provides services like
/compute_ikand/compute_fkfor motion planning
