4.12 Robot Jogging Motion
Overview
The Jogging class provides jog-control APIs in manual teaching mode, including single-axis stepping, single-axis continuous jog, multi-axis continuous jog, and stop operations.
Core Features
- Single-axis step jogging
- Single-axis continuous jogging
- Multi-axis continuous jogging
- Stop continuous jogging
- Direction control with positive/negative axis signs
- Configurable linear step length and rotational step angle
Use Cases
- Robot debugging and teaching process
- Fine position and posture adjustment
- Host-side remote manual pose adjustment
- Robot installation and calibration
- Position confirmation before executing complex trajectories
4.12.1 Single-Axis Step Jogging
| Method Name | Jogging.Move(int ajNum , MoveMode moveMode , double stepLength = 0, double stepAngle = 0) |
|---|---|
| Description | Executes single-axis step jogging ( moveMode = MoveMode.Stepping ). |
| Request Parameters | ajNum : int Axis index (1~6 maps to current coordinate-system axes; in Cartesian mode x/y/z/rx/ry/rz map to 1~6; sign indicates direction). moveMode : Move mode, fixed to MoveMode.Stepping for this scenario. stepLength : double Linear step length in mm (effective in stepping mode). stepAngle : double Rotational step angle in ° (effective in stepping mode). |
| Return Value | StatusCode: Jog operation result |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
using Agilebot.IR.Types;
public class StepJogging
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 获取机器人模式
// [EN] Get robot mode
(UserOpMode opMode, StatusCode opCode) = controller.GetOpMode();
if (opCode == StatusCode.OK)
{
Console.WriteLine($"当前机器人模式/Current robot mode: {opMode}");
if (opMode != UserOpMode.UNLIMITED_MANUAL && opMode != UserOpMode.LIMIT_MANUAL)
{
Console.WriteLine($"示教运动必须在机器人手动模式下/Jogging must be in manual mode");
return StatusCode.OtherReason;
}
}
else
{
Console.WriteLine($"获取机器人模式失败/Failed to get robot mode: {opCode.GetDescription()}");
}
// [ZH] 设置单步示教运动参数
// [EN] Set step jogging parameters
int ajNum = 1; // 轴序号,正数表示正方向运动
MoveMode moveMode = MoveMode.Stepping; // 单步运动模式
double stepLength = 5.0; // 步长,单位为mm或角度
double stepAngle = 5.0; // 轴旋转角度,单位为角度
Console.WriteLine("开始单步示教运动/Starting Step Jogging");
Console.WriteLine($"轴序号/Axis Number: {ajNum}");
Console.WriteLine($"运动模式/Move Mode: {moveMode}");
Console.WriteLine($"步长/Step Length: {stepLength}");
// [ZH] 执行单步示教运动
// [EN] Execute step jogging movement
code = controller.Jogging.Move(ajNum, moveMode, stepLength, stepAngle);
if (code == StatusCode.OK)
{
Console.WriteLine("单步示教运动执行成功/Step Jogging Executed Successfully");
Console.WriteLine(
$"轴{ajNum}向正方向移动{stepLength}单位/Axis {ajNum} moved {stepLength} units in positive direction"
);
}
else
{
Console.WriteLine($"单步示教运动执行失败/Step Jogging Execution Failed: {code.GetDescription()}");
}
// [ZH] 等待一秒后执行反向运动
// [EN] Wait one second then execute reverse movement
Thread.Sleep(1000);
// [ZH] 执行反向单步运动
// [EN] Execute reverse step movement
int reverseAjNum = -ajNum; // 负数表示负方向运动
code = controller.Jogging.Move(reverseAjNum, moveMode, stepLength, stepAngle);
if (code == StatusCode.OK)
{
Console.WriteLine("反向单步示教运动执行成功/Reverse Step Jogging Executed Successfully");
Console.WriteLine(
$"轴{Math.Abs(reverseAjNum)}向负方向移动{stepLength}单位/Axis {Math.Abs(reverseAjNum)} moved {stepLength} units in negative direction"
);
}
else
{
Console.WriteLine(
$"反向单步示教运动执行失败/Reverse Step Jogging Execution Failed: {code.GetDescription()}"
);
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.12.2 Single-Axis Continuous Jogging
| Method Name | Jogging.Move(int ajNum , MoveMode moveMode , double stepLength = 0, double stepAngle = 0) |
|---|---|
| Description | Executes single-axis continuous jogging ( moveMode = MoveMode.Continuous ). |
| Request Parameters | ajNum : int Axis index (1~6 maps to current coordinate-system axes; in Cartesian mode x/y/z/rx/ry/rz map to 1~6; sign indicates direction). moveMode : Move mode, fixed to MoveMode.Continuous for this scenario. stepLength : double Step parameter (typically unused in continuous mode). stepAngle : double Step-angle parameter (typically unused in continuous mode). |
| Return Value | StatusCode: Jog operation result |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
using Agilebot.IR.Types;
public class ContinuousJogging
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 获取机器人模式
// [EN] Get robot mode
(UserOpMode opMode, StatusCode opCode) = controller.GetOpMode();
if (opCode == StatusCode.OK)
{
Console.WriteLine($"当前机器人模式/Current robot mode: {opMode}");
if (opMode != UserOpMode.UNLIMITED_MANUAL && opMode != UserOpMode.LIMIT_MANUAL)
{
Console.WriteLine($"示教运动必须在机器人手动模式下/Jogging must be in manual mode");
return StatusCode.OtherReason;
}
}
else
{
Console.WriteLine($"获取机器人模式失败/Failed to get robot mode: {opCode.GetDescription()}");
}
// [ZH] 设置示教运动参数
// [EN] Set jogging parameters
int ajNum = 3; // 轴序号,正数表示正方向运动
MoveMode moveMode = MoveMode.Continuous; // 连续运动模式
Console.WriteLine("开始连续示教运动/Starting Continuous Jogging");
Console.WriteLine($"轴序号/Axis Number: {ajNum}");
Console.WriteLine($"运动模式/Move Mode: {moveMode}");
// [ZH] 启动连续示教运动
// [EN] Start continuous jogging movement
code = controller.Jogging.Move(ajNum, moveMode);
if (code == StatusCode.OK)
{
Console.WriteLine("连续示教运动启动成功/Continuous Jogging Started Successfully");
Console.WriteLine("运动3秒后自动停止/Moving for 3 seconds then auto stop");
// [ZH] 运动3秒
// [EN] Move for 3 seconds
Thread.Sleep(3000);
// [ZH] 停止示教运动
// [EN] Stop jogging movement
controller.Jogging.Stop();
Console.WriteLine("示教运动已停止/Jogging Movement Stopped");
}
else
{
Console.WriteLine($"连续示教运动启动失败/Continuous Jogging Start Failed: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.12.3 Multi-Axis Continuous Jogging
| Method Name | Jogging.MultiMove(int[] ajNums ) |
|---|---|
| Description | Executes simultaneous continuous jogging on multiple axes. |
| Request Parameters | ajNums : int[] Axis list (1~6 maps to current coordinate-system axes; in Cartesian mode x/y/z/rx/ry/rz map to 1~6; sign indicates each axis direction). |
| Return Value | StatusCode: Jog operation result |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
using Agilebot.IR.Jogging;
using Agilebot.IR.Types;
public class MultiJogging
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 获取机器人模式
// [EN] Get robot mode
(UserOpMode opMode, StatusCode opCode) = controller.GetOpMode();
if (opCode == StatusCode.OK)
{
Console.WriteLine($"当前机器人模式/Current robot mode: {opMode}");
if (opMode != UserOpMode.UNLIMITED_MANUAL && opMode != UserOpMode.LIMIT_MANUAL)
{
Console.WriteLine($"示教运动必须在机器人手动模式下/Jogging must be in manual mode");
return StatusCode.OtherReason;
}
}
else
{
Console.WriteLine($"获取机器人模式失败/Failed to get robot mode: {opCode.GetDescription()}");
}
Console.WriteLine("开始多轴示教运动/Starting Multi-axis Jogging");
Console.WriteLine("演示多轴运动/Demo multi-axis step movements");
// [ZH] 多轴运动
// [EN] Multi-axis step movement
Console.WriteLine("\n=== 多轴运动/Multi-axis Step Movement ===");
int[] axes = { 1, 2, 3 }; // 正方向运动
code = controller.Jogging.MultiMove(axes);
if (code == StatusCode.OK)
{
Console.WriteLine("连续示教运动启动成功/Continuous Jogging Started Successfully");
Console.WriteLine("运动3秒后自动停止/Moving for 3 seconds then auto stop");
// [ZH] 运动3秒
// [EN] Move for 3 seconds
Thread.Sleep(3000);
// [ZH] 停止示教运动
// [EN] Stop jogging movement
controller.Jogging.Stop();
Console.WriteLine("示教运动已停止/Jogging Movement Stopped");
}
else
{
Console.WriteLine($"连续示教运动启动失败/Continuous Jogging Start Failed: {code.GetDescription()}");
}
Console.WriteLine("\n多轴示教运动完成/Multi-axis Jogging Completed");
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}4.12.4 Stop Continuous Jogging
| Method Name | Jogging.Stop() |
|---|---|
| Description | Stops the current continuous jog movement. |
| Request Parameters | None |
| Return Value | void |
| Note | This method is required only in continuous jogging mode. |
| Compatible robot software version | Collaborative (Copper): v7.5.0.0+ Industrial (Bronze): v7.5.0.0+ |
Example Code
cs
using Agilebot.IR;
using Agilebot.IR.Types;
public class ContinuousJogging
{
public static StatusCode Run(string controllerIP, bool useLocalProxy = true)
{
// [ZH] 初始化捷勃特机器人
// [EN] Initialize the Agilebot robot
Arm controller = new Arm(controllerIP, useLocalProxy);
// [ZH] 连接捷勃特机器人
// [EN] Connect to the Agilebot robot
StatusCode code = controller.ConnectSync();
Console.WriteLine(code != StatusCode.OK ? code.GetDescription() : "连接成功/Successfully connected.");
if (code != StatusCode.OK)
{
return code;
}
try
{
// [ZH] 获取机器人模式
// [EN] Get robot mode
(UserOpMode opMode, StatusCode opCode) = controller.GetOpMode();
if (opCode == StatusCode.OK)
{
Console.WriteLine($"当前机器人模式/Current robot mode: {opMode}");
if (opMode != UserOpMode.UNLIMITED_MANUAL && opMode != UserOpMode.LIMIT_MANUAL)
{
Console.WriteLine($"示教运动必须在机器人手动模式下/Jogging must be in manual mode");
return StatusCode.OtherReason;
}
}
else
{
Console.WriteLine($"获取机器人模式失败/Failed to get robot mode: {opCode.GetDescription()}");
}
// [ZH] 设置示教运动参数
// [EN] Set jogging parameters
int ajNum = 3; // 轴序号,正数表示正方向运动
MoveMode moveMode = MoveMode.Continuous; // 连续运动模式
Console.WriteLine("开始连续示教运动/Starting Continuous Jogging");
Console.WriteLine($"轴序号/Axis Number: {ajNum}");
Console.WriteLine($"运动模式/Move Mode: {moveMode}");
// [ZH] 启动连续示教运动
// [EN] Start continuous jogging movement
code = controller.Jogging.Move(ajNum, moveMode);
if (code == StatusCode.OK)
{
Console.WriteLine("连续示教运动启动成功/Continuous Jogging Started Successfully");
Console.WriteLine("运动3秒后自动停止/Moving for 3 seconds then auto stop");
// [ZH] 运动3秒
// [EN] Move for 3 seconds
Thread.Sleep(3000);
// [ZH] 停止示教运动
// [EN] Stop jogging movement
controller.Jogging.Stop();
Console.WriteLine("示教运动已停止/Jogging Movement Stopped");
}
else
{
Console.WriteLine($"连续示教运动启动失败/Continuous Jogging Start Failed: {code.GetDescription()}");
}
}
catch (Exception ex)
{
Console.WriteLine($"执行过程中发生异常/Exception occurred during execution: {ex.Message}");
code = StatusCode.OtherReason;
}
finally
{
// [ZH] 关闭连接
// [EN] Close the connection
StatusCode disconnectCode = controller.Disconnect();
if (disconnectCode != StatusCode.OK)
{
Console.WriteLine(disconnectCode.GetDescription());
if (code == StatusCode.OK)
code = disconnectCode;
}
}
return code;
}
}