AUBO SDK  0.25.0
载入中...
搜索中...
未找到
arcs::common_interface::MotionControl类 参考

MotionControl 更多...

#include <motion_control.h>

Public 成员函数

 MotionControl ()
 
virtual ~MotionControl ()
 
double getEqradius ()
 获取等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动 可以通过 setEqradius 设置,默认为1
 
int setEqradius (double eqradius)
 设置等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动,数值越大,姿态旋转速度越快
 
int setSpeedFraction (double fraction)
 动态调整机器人运行速度和加速度比例 (0., 1.
 
double getSpeedFraction ()
 获取速度和加速度比例,默认为 1 可以通过 setSpeedFraction 接口设置
 
int speedFractionCritical (bool enable)
 速度比例设置临界区,使能之后速度比例被强制设定为1.
 
bool isSpeedFractionCritical ()
 是否处于速度比例设置临界区
 
bool isBlending ()
 是否处交融区
 
int pathOffsetLimits (double v, double a)
 设置偏移的最大速度和最大加速度 仅对pathOffsetSet中 type=1 有效
 
int pathOffsetCoordinate (int ref_coord)
 设置偏移的参考坐标系 仅对pathOffsetSet中 type=1 有效
 
int pathOffsetEnable ()
 路径偏移使能
 
int pathOffsetSet (const std::vector< double > &offset, int type=0)
 设置路径偏移
 
int pathOffsetDisable ()
 路径偏移失能
 
int pathOffsetSupv (const std::vector< double > &min, const std::vector< double > &max, int strategy)
 
int jointOffsetEnable ()
 关节偏移使能
 
int jointOffsetSet (const std::vector< double > &offset, int type=1)
 设置关节偏移
 
int jointOffsetDisable ()
 关节偏移失能
 
int getQueueSize ()
 获取已经入队的指令段(INST)数量,运动指令包括 moveJoint/moveLine/moveCircle 等运动指令以及 setPayload 等配置指令
 
int getTrajectoryQueueSize ()
 获取已经入队的运动规划插补点数量
 
int getExecId ()
 获取当前正在插补的运动指令段的ID
 
double getDuration (int id)
 获取指定ID的运动指令段的预期执行时间
 
double getMotionLeftTime (int id)
 获取指定ID的运动指令段的剩余执行时间
 
int stopMove (bool quick, bool all_tasks)
 StopMove 用于临时停止机器人和外部轴的运动以及相关工艺进程。如果调用 StartMove 指令,则运动和工艺进程将恢复。
 
int startMove ()
 StartMove 用于在以下情况下恢复机器人、外部轴的运动以及相关工艺进程: • 通过 StopMove 指令停止后。 • 执行 StorePath ... RestoPath 序列后。 • 发生异步运动错误(如 ERR_PATH_STOP)或特定工艺错误并在 ERROR 处理器中处理后。
 
int storePath (bool keep_sync)
 storePath
 
int clearPath ()
 ClearPath (清除路径) 清除当前运动路径层级(基础层级或 StorePath 层级)上的所有运动路径。
 
int restoPath ()
 restoPath
 
double getProgress ()
 获取当前运动指令段的执行进度
 
int setWorkObjectHold (const std::string &module_name, const std::vector< double > &mounting_pose)
 当工件安装在另外一台机器人的末端或者外部轴上时,指定其名字和安装位置
 
std::tuple< std::string, std::vector< double > > getWorkObjectHold ()
 获取工件安装信息
 
std::vector< double > getPauseJointPositions ()
 获取暂停点关节位置
 
int setResumeStartPoint (const std::vector< double > &q, int move_type, double blend_radius, const std::vector< double > &qdmax, const std::vector< double > &qddmax, const std::vector< double > &vmax, const std::vector< double > &amax)
 设置继续运动参数
 
int getResumeMode ()
 获取继续运动模式
 
ARCS_DEPRECATED int setServoMode (bool enable)
 设置伺服模式 使用 setServoModeSelect 替代
 
ARCS_DEPRECATED bool isServoModeEnabled ()
 判断伺服模式是否使能 使用 getServoModeSelect 替代
 
int setServoModeSelect (int mode)
 设置伺服运动模式
 
int getServoModeSelect ()
 获取伺服运动模式
 
int servoJoint (const std::vector< double > &q, double a, double v, double t, double lookahead_time, double gain)
 关节空间伺服
 
int servoCartesian (const std::vector< double > &pose, double a, double v, double t, double lookahead_time, double gain)
 笛卡尔空间伺服
 
int servoJointWithAxes (const std::vector< double > &q, const std::vector< double > &extq, double a, double v, double t, double lookahead_time, double gain)
 伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
 
int servoJointWithAxisGroup (const std::vector< double > &q, double a, double v, double t, double lookahead_time, double gain, const std::string &group_name, const std::vector< double > &extq)
 
int servoCartesianWithAxes (const std::vector< double > &pose, const std::vector< double > &extq, double a, double v, double t, double lookahead_time, double gain)
 伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等 与 servoJointWithAxes 区别在于接收笛卡尔空间位姿而不是关节角度 (由软件内部直接做逆解)
 
int servoCartesianWithAxisGroup (const std::vector< double > &pose, double a, double v, double t, double lookahead_time, double gain, const std::string &group_name, const std::vector< double > &extq)
 
int trackJoint (const std::vector< double > &q, double t, double smooth_scale, double delay_sacle)
 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
 
int trackCartesian (const std::vector< double > &pose, double t, double smooth_scale, double delay_sacle)
 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等 与 trackJoint 区别在于接收笛卡尔空间位姿而不是关节角度 (由软件内部直接做逆解)
 
int followJoint (const std::vector< double > &q)
 关节空间跟随
 
int followLine (const std::vector< double > &pose)
 笛卡尔空间跟随
 
int speedJoint (const std::vector< double > &qd, double a, double t)
 关节空间速度跟随
 
int resumeSpeedJoint (const std::vector< double > &qd, double a, double t)
 关节空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
 
int speedLine (const std::vector< double > &xd, double a, double t)
 笛卡尔空间速度跟随
 
int resumeSpeedLine (const std::vector< double > &xd, double a, double t)
 笛卡尔空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
 
int moveSpline (const std::vector< double > &q, double a, double v, double duration)
 在关节空间做样条插值
 
int moveJoint (const std::vector< double > &q, double a, double v, double blend_radius, double duration)
 添加关节运动
 
int moveJointWithAxisGroup (const std::vector< double > &q, double a, double v, double blend_radius, double duration, const std::string &group_name, const std::vector< double > &extq)
 机器人与外部轴同步运动
 
int resumeMoveJoint (const std::vector< double > &q, double a, double v, double duration)
 通过关节运动移动到暂停点的位置
 
int moveLine (const std::vector< double > &pose, double a, double v, double blend_radius, double duration)
 添加直线运动
 
int moveLineWithAxisGroup (const std::vector< double > &pose, double a, double v, double blend_radius, double duration, const std::string &group_name, const std::vector< double > &extq)
 直线运动与外部轴同步运动
 
int moveProcess (const std::vector< double > &pose, double a, double v, double blend_radius)
 添加工艺运动
 
int resumeMoveLine (const std::vector< double > &pose, double a, double v, double duration)
 通过直线运动移动到暂停点的位置
 
int moveCircle (const std::vector< double > &via_pose, const std::vector< double > &end_pose, double a, double v, double blend_radius, double duration)
 添加圆弧运动
 
int moveCircleWithAxisGroup (const std::vector< double > &via_pose, const std::vector< double > &end_pose, double a, double v, double blend_radius, double duration, const std::string &group_name, const std::vector< double > &extq)
 moveCircle 与外部轴同步运动
 
int setCirclePathMode (int mode)
 设置圆弧路径模式
 
int moveCircle2 (const CircleParameters &param)
 高级圆弧或者圆周运动
 
int pathBufferAlloc (const std::string &name, int type, int size)
 新建一个路径点缓存
 
int pathBufferAppend (const std::string &name, const std::vector< std::vector< double > > &waypoints)
 向路径缓存添加路点
 
int pathBufferEval (const std::string &name, const std::vector< double > &a, const std::vector< double > &v, double t)
 计算、优化等耗时操作,传入的参数相同时不会重新计算
 
bool pathBufferValid (const std::string &name)
 指定名字的buffer是否有效
 
int pathBufferFree (const std::string &name)
 释放路径缓存
 
int pathBufferFilter (const std::string &name, int order, double fd, double fs)
 关节空间路径滤波器
 
std::vector< std::string > pathBufferList ()
 列出所有缓存路径的名字
 
int movePathBuffer (const std::string &name)
 执行缓存的路径
 
int moveIntersection (const std::vector< std::vector< double > > &poses, double a, double v, double main_pipe_radius, double sub_pipe_radius, double normal_distance, double normal_alpha)
 相贯线接口
 
int stopJoint (double acc)
 关节空间停止运动
 
int resumeStopJoint (double acc)
 关节空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedJoint接口移动到安全位置后需要停止时调用此接口)
 
int stopLine (double acc, double acc_rot)
 笛卡尔空间停止运动
 
int resumeStopLine (double acc, double acc_rot)
 笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)
 
int weaveStart (const std::string &params)
 开始摆动: weaveStart 和 weaveEnd 的 moveLine/moveCircle 将根据 params 进行摆动
 
int weaveEnd ()
 结束摆动
 
int setFuturePointSamplePeriod (double sample_time)
 设置未来路径上点的采样时间间隔
 
std::vector< std::vector< double > > getFuturePathPointsJoint ()
 获取未来路径上的轨迹点
 
int setConveyorTrackEncoder (int encoder_id, int tick_per_meter)
 设置传送带编码器参数
 
int conveyorTrackCircle (int encoder_id, const std::vector< double > &center, bool rotate_tool)
 圆形传送带跟随
 
int conveyorTrackLine (int encoder_id, const std::vector< double > &direction)
 线性传送带跟随
 
int conveyorTrackStop (int encoder_id, double a)
 终止传送带跟随
 
bool conveyorTrackSwitch (int encoder_id)
 切换传送带追踪物品 如果当前物品正在处于跟踪状态,则将该物品出队,不再跟踪,返回true 如果没有物品正在处于跟踪状态,返回false
 
bool hasItemOnConveyorToTrack (int encoder_id)
 传送带上是否有物品可以跟踪
 
int conveyorTrackCreatItem (int encoder_id, int item_id, const std::vector< double > &offset)
 增加传送带队列
 
int setConveyorTrackCompensate (int encoder_id, double comp)
 设置传送带跟踪的补偿值
 
bool isConveyorTrackSync (int encoder_id)
 判断传送带与机械臂之间是否达到相对静止
 
int setConveyorTrackLimit (int encoder_id, double limit)
 设置传送带跟踪的最大距离限制
 
int setConveyorTrackStartWindow (int encoder_id, double window_min, double window_max)
 设置传送带跟踪的启动窗口
 
int setConveyorTrackSensorOffset (int encoder_id, double offset)
 设置传送带示教位置到同步开关之间的距离
 
int setConveyorTrackSyncSeparation (int encoder_id, double distance, double time)
 设置传送带同步分离,用于过滤掉同步开关中不需要的信号
 
bool isConveyorTrackExceed (int encoder_id)
 传送带上工件的移动距离是否超过最大限值
 
int conveyorTrackClearItems (int encoder_id)
 清空传动带队列中的所有对象
 
std::vector< int > getConveyorTrackQueue (int encoder_id)
 获取传送带队列的编码器值
 
int getConveyorTrackNextItem (int encoder_id)
 获取下一个跟踪的传送带物品的id
 
int moveSpiral (const SpiralParameters &param, double blend_radius, double v, double a, double t)
 螺旋线运动
 
int getLookAheadSize ()
 获取前瞻段数
 
int setLookAheadSize (int size)
 设置前瞻段数 1.
 
int weaveUpdateParameters (const std::string &params)
 更新摆动过程中的频率和振幅
 
int enableJointSoftServo (const std::vector< double > &stiffness)
 设置关节电流环刚度系数
 
int disableJointSoftServo ()
 关闭关节电流环刚度系数
 
bool isJointSoftServoEnabled ()
 判断关节电流环刚度系数是否使能
 

Protected 属性

void * d_
 

详细描述

MotionControl

在文件 motion_control.h56 行定义.

构造及析构函数说明

◆ MotionControl()

arcs::common_interface::MotionControl::MotionControl ( )

◆ ~MotionControl()

virtual arcs::common_interface::MotionControl::~MotionControl ( )
virtual

成员函数说明

◆ clearPath()

int arcs::common_interface::MotionControl::clearPath ( )

ClearPath (清除路径) 清除当前运动路径层级(基础层级或 StorePath 层级)上的所有运动路径。

返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.clearPath","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ conveyorTrackCircle()

int arcs::common_interface::MotionControl::conveyorTrackCircle ( int  encoder_id,
const std::vector< double > &  center,
bool  rotate_tool 
)

圆形传送带跟随

注解
暂未实现
参数
encoder_id0-集成传感器
rotate_tool
返回
异常
arcs::common_interface::AuboException

◆ conveyorTrackClearItems()

int arcs::common_interface::MotionControl::conveyorTrackClearItems ( int  encoder_id)

清空传动带队列中的所有对象

参数
encoder_id预留
返回
异常
arcs::common_interface::AuboException
Python函数原型
conveyorTrackClearItems(self: pyaubo_sdk.MotionControl, arg0: int) -> int
Lua函数原型
conveyorTrackClearItems(encoder_id: number) -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackClearItems","params":[0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ conveyorTrackCreatItem()

int arcs::common_interface::MotionControl::conveyorTrackCreatItem ( int  encoder_id,
int  item_id,
const std::vector< double > &  offset 
)

增加传送带队列

参数
encoder_id预留
offset当前物品点位相对于模板物品点位的偏移值
返回
异常
arcs::common_interface::AuboException
Python函数原型
conveyorTrackCreatItem(self: pyaubo_sdk.MotionControl, arg0: int, arg1:int, arg2: List[float]) -> int
Lua函数原型
conveyorTrackCreatItem(encoder_id: number, item_id: number, offset: table) -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackCreatItem","params":[0,2, {0.0,0.0,0.0,0.0,0.0,0.0}],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0.0}

◆ conveyorTrackLine()

int arcs::common_interface::MotionControl::conveyorTrackLine ( int  encoder_id,
const std::vector< double > &  direction 
)

线性传送带跟随

参数
encoder_id预留
direction传送带相对机器人基坐标系的移动方向
返回
异常
arcs::common_interface::AuboException
Python函数原型
conveyorTrackLine(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
conveyorTrackLine -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackLine","params":[1,[1.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ conveyorTrackStop()

int arcs::common_interface::MotionControl::conveyorTrackStop ( int  encoder_id,
double  a 
)

终止传送带跟随

参数
encoder_id预留
a预留
返回
异常
arcs::common_interface::AuboException
Python函数原型
conveyorTrackStop(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
conveyorTrackStop -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackStop","params":[0,1.0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ conveyorTrackSwitch()

bool arcs::common_interface::MotionControl::conveyorTrackSwitch ( int  encoder_id)

切换传送带追踪物品 如果当前物品正在处于跟踪状态,则将该物品出队,不再跟踪,返回true 如果没有物品正在处于跟踪状态,返回false

返回
异常
arcs::common_interface::AuboException
参数
encoder_id预留
Python函数原型
conveyorTrackSwitch(self: pyaubo_sdk.MotionControl) -> bool
Lua函数原型
conveyorTrackSwitch() -> boolean
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackSwitch","params":[0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":true}

◆ disableJointSoftServo()

int arcs::common_interface::MotionControl::disableJointSoftServo ( )

关闭关节电流环刚度系数

返回
返回0表示成功,其他为错误码
异常
arcs::common_interface::AuboException
Python函数原型
disableJointSoftServo(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
disableJointSoftServo() -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.disableJointSoftServo","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":1}

◆ enableJointSoftServo()

int arcs::common_interface::MotionControl::enableJointSoftServo ( const std::vector< double > &  stiffness)

设置关节电流环刚度系数

参数
stiffness各个关节刚度系数,百分比。[0 -> 1],值越大,表现为越硬。
返回
异常
arcs::common_interface::AuboException
Python函数原型
enableJointSoftServo(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
Lua函数原型
enableJointSoftServo(stiffness: table) -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.RobotConfig.enableJointSoftServo","params":[[0.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ followJoint()

int arcs::common_interface::MotionControl::followJoint ( const std::vector< double > &  q)

关节空间跟随

注解
暂未实现
异常
arcs::common_interface::AuboException
Python函数原型
followJoint(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
Lua函数原型
followJoint(q: table) -> nil

◆ followLine()

int arcs::common_interface::MotionControl::followLine ( const std::vector< double > &  pose)

笛卡尔空间跟随

注解
暂未实现
异常
arcs::common_interface::AuboException
Python函数原型
followLine(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
Lua函数原型
followLine(pose: table) -> nil

◆ getConveyorTrackNextItem()

int arcs::common_interface::MotionControl::getConveyorTrackNextItem ( int  encoder_id)

获取下一个跟踪的传送带物品的id

参数
encoder_id预留
返回
返回物品id,没有next item返回 -1
异常
arcs::common_interface::AuboException
Python函数原型
getConveyorTrackNextItem(self: pyaubo_sdk.MotionControl, arg0: int) -> int
Lua函数原型
getConveyorTrackNextItem(encoder_id: number) -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackNextItem","params":[0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":{10}}

◆ getConveyorTrackQueue()

std::vector< int > arcs::common_interface::MotionControl::getConveyorTrackQueue ( int  encoder_id)

获取传送带队列的编码器值

参数
encoder_id预留
返回
异常
arcs::common_interface::AuboException
Python函数原型
getConveyorTrackQueue(self: pyaubo_sdk.MotionControl, arg0: int) -> List[int]
Lua函数原型
getConveyorTrackQueue(encoder_id: number) -> table
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackQueue","params":[0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":{[-500,-200,150,-50]}}

◆ getDuration()

double arcs::common_interface::MotionControl::getDuration ( int  id)

获取指定ID的运动指令段的预期执行时间

参数
id运动指令段ID
返回
返回预期执行时间
异常
arcs::common_interface::AuboException
Python函数原型
getDuration(self: pyaubo_sdk.MotionControl, arg0: int) -> float
Lua函数原型
getDuration(id: number) -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getDuration","params":[16],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0.0}

◆ getEqradius()

double arcs::common_interface::MotionControl::getEqradius ( )

获取等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动 可以通过 setEqradius 设置,默认为1

返回
返回等效半径
异常
arcs::common_interface::AuboException
Python函数原型
getEqradius(self: pyaubo_sdk.MotionControl) -> float
Lua函数原型
getEqradius() -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getEqradius","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":1.0}

◆ getExecId()

int arcs::common_interface::MotionControl::getExecId ( )

获取当前正在插补的运动指令段的ID

返回
当前正在插补的运动指令段的ID
返回值
-1表示轨迹队列为空
像movePathBuffer运动中的buffer或者规划器(moveJoint和moveLine等)里的队列都属于轨迹队列
异常
arcs::common_interface::AuboException
Python函数原型
getExecId(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
getExecId() -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getExecId","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":-1}

◆ getFuturePathPointsJoint()

std::vector< std::vector< double > > arcs::common_interface::MotionControl::getFuturePathPointsJoint ( )

获取未来路径上的轨迹点

返回
路点(100ms * 10)
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getFuturePathPointsJoint","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[]}

◆ getLookAheadSize()

int arcs::common_interface::MotionControl::getLookAheadSize ( )

获取前瞻段数

返回
返回前瞻段数
异常
arcs::common_interface::AuboException
Python函数原型
getLookAheadSize(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
getLookAheadSize() -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getLookAheadSize","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":1}

◆ getMotionLeftTime()

double arcs::common_interface::MotionControl::getMotionLeftTime ( int  id)

获取指定ID的运动指令段的剩余执行时间

参数
id运动指令段ID
返回
返回剩余执行时间
异常
arcs::common_interface::AuboException
Python函数原型
getMotionLeftTime(self: pyaubo_sdk.MotionControl, arg0: int) -> float
Lua函数原型
getMotionLeftTime(id: number) -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getMotionLeftTime","params":[16],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0.0}

◆ getPauseJointPositions()

std::vector< double > arcs::common_interface::MotionControl::getPauseJointPositions ( )

获取暂停点关节位置

常用于运行工程时发生碰撞后继续运动过程中(先通过resumeMoveJoint或resumeMoveLine运动到暂停位置,再恢复工程)

返回
暂停关节位置
异常
arcs::common_interface::AuboException
Python函数原型
getPauseJointPositions(self: pyaubo_sdk.MotionControl) -> List[float]
Lua函数原型
getPauseJointPositions() -> table
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getPauseJointPositions","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[8.2321e-13,-0.200999,1.33999,0.334999,1.206,-6.39383e-12]}

◆ getProgress()

double arcs::common_interface::MotionControl::getProgress ( )

获取当前运动指令段的执行进度

返回
返回执行进度
异常
arcs::common_interface::AuboException
Python函数原型
getProgress(self: pyaubo_sdk.MotionControl) -> float
Lua函数原型
getProgress() -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getProgress","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0.0}

◆ getQueueSize()

int arcs::common_interface::MotionControl::getQueueSize ( )

获取已经入队的指令段(INST)数量,运动指令包括 moveJoint/moveLine/moveCircle 等运动指令以及 setPayload 等配置指令

指令一般会在接口宏定义里面用 _INST 指示, 比如 moveJoint _INST(MotionControl, 5, moveJoint, q, a, v, blend_radius, duration)

返回
已经入队的指令段数量
异常
arcs::common_interface::AuboException
Python函数原型
getQueueSize(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
getQueueSize() -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getQueueSize","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ getResumeMode()

int arcs::common_interface::MotionControl::getResumeMode ( )

获取继续运动模式

返回
0:继续运动起始点为暂停点 1:继续运动起始点为指定点
异常
arcs::common_interface::AuboException
Python函数原型
getResumeMode(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
getResumeMode() -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getResumeMode","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":false}

◆ getServoModeSelect()

int arcs::common_interface::MotionControl::getServoModeSelect ( )

获取伺服运动模式

返回
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getServoModeSelect","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ getSpeedFraction()

double arcs::common_interface::MotionControl::getSpeedFraction ( )

获取速度和加速度比例,默认为 1 可以通过 setSpeedFraction 接口设置

返回
返回速度和加速度比例
异常
arcs::common_interface::AuboException
Python函数原型
getSpeedFraction(self: pyaubo_sdk.MotionControl) -> float
Lua函数原型
getSpeedFraction() -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getSpeedFraction","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":1.0}

◆ getTrajectoryQueueSize()

int arcs::common_interface::MotionControl::getTrajectoryQueueSize ( )

获取已经入队的运动规划插补点数量

返回
已经入队的运动规划插补点数量
异常
arcs::common_interface::AuboException
Python函数原型
getTrajectoryQueueSize(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
getTrajectoryQueueSize() -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getTrajectoryQueueSize","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ getWorkObjectHold()

std::tuple< std::string, std::vector< double > > arcs::common_interface::MotionControl::getWorkObjectHold ( )

获取工件安装信息

注解
暂未实现
返回
返回一个包含控制模块名字和安装位姿的元组
异常
arcs::common_interface::AuboException
Python函数原型
getWorkObjectHold(self: pyaubo_sdk.MotionControl) -> Tuple[str, List[float]]
Lua函数原型
getWorkObjectHold() -> table
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.getWorkObjectHold","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":["",[]]}

◆ hasItemOnConveyorToTrack()

bool arcs::common_interface::MotionControl::hasItemOnConveyorToTrack ( int  encoder_id)

传送带上是否有物品可以跟踪

参数
encoder_id预留
返回
如果队列第一个物品为跟踪状态,返回true 如果队列第一个物品不为跟踪状态,则对队列中其余物品进行是否在启动窗口内的判断 超出启动窗口则出队,直到有物品处于启动窗口内,使其变为跟踪状态返回true, 队列中没有一个物品在启动窗口内返回false
异常
arcs::common_interface::AuboException
Python函数原型
hasItemOnConveyorToTrack(self: pyaubo_sdk.MotionControl) -> bool
Lua函数原型
hasItemOnConveyorToTrack() -> boolean
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.hasItemOnConveyorToTrack","params":[0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":{true}}

◆ isBlending()

bool arcs::common_interface::MotionControl::isBlending ( )

是否处交融区

返回
处交融区返回 true; 反之返回 false
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.isBlending","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":false}

◆ isConveyorTrackExceed()

bool arcs::common_interface::MotionControl::isConveyorTrackExceed ( int  encoder_id)

传送带上工件的移动距离是否超过最大限值

参数
encoder_id预留
返回
true : 移动距离超过了最大限值 false : 移动距离没有超过了最大限值
异常
arcs::common_interface::AuboException
Python函数原型
isConveyorTrackExceed(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
Lua函数原型
isConveyorTrackExceed(encoder_id: number) -> bool
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackExceed","params":[0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":false}

◆ isConveyorTrackSync()

bool arcs::common_interface::MotionControl::isConveyorTrackSync ( int  encoder_id)

判断传送带与机械臂之间是否达到相对静止

参数
encoder_id预留
返回
异常
arcs::common_interface::AuboException
Python函数原型
isConveyorTrackSync(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
Lua函数原型
isConveyorTrackSync(encoder_id: number) -> bool
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackSync","params":[0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":false}

◆ isJointSoftServoEnabled()

bool arcs::common_interface::MotionControl::isJointSoftServoEnabled ( )

判断关节电流环刚度系数是否使能

返回
已使能返回true,反之则返回false
异常
arcs::common_interface::AuboException
Python函数原型
isJointSoftServoEnabled(self: pyaubo_sdk.MotionControl) -> bool
Lua函数原型
isJointSoftServoEnabled() -> boolean
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.isJointSoftServoEnabled","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":1}

◆ isServoModeEnabled()

ARCS_DEPRECATED bool arcs::common_interface::MotionControl::isServoModeEnabled ( )

判断伺服模式是否使能 使用 getServoModeSelect 替代

返回
已使能返回true,反之则返回false
异常
arcs::common_interface::AuboException
Python函数原型
isServoModeEnabled(self: pyaubo_sdk.MotionControl) -> bool
Lua函数原型
isServoModeEnabled() -> boolean
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.isServoModeEnabled","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":false}

◆ isSpeedFractionCritical()

bool arcs::common_interface::MotionControl::isSpeedFractionCritical ( )

是否处于速度比例设置临界区

返回
处于速度比例设置临界区返回 true; 反之返回 false
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.isSpeedFractionCritical","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":true}

◆ jointOffsetDisable()

int arcs::common_interface::MotionControl::jointOffsetDisable ( )

关节偏移失能

返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
jointOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
jointOffsetDisable() -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetDisable","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ jointOffsetEnable()

int arcs::common_interface::MotionControl::jointOffsetEnable ( )

关节偏移使能

返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
jointOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
jointOffsetEnable() -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetEnable","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ jointOffsetSet()

int arcs::common_interface::MotionControl::jointOffsetSet ( const std::vector< double > &  offset,
int  type = 1 
)

设置关节偏移

参数
offset在各关节的位姿偏移
type
返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
jointOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: int) -> int
Lua函数原型
jointOffsetSet(offset: table, type: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetSet","params":[[0.1,0,0,0,0],1],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ moveCircle()

int arcs::common_interface::MotionControl::moveCircle ( const std::vector< double > &  via_pose,
const std::vector< double > &  end_pose,
double  a,
double  v,
double  blend_radius,
double  duration 
)

添加圆弧运动

参数
via_pose圆弧运动途中点的位姿
end_pose圆弧运动结束点的位姿
a加速度(如果via_pose与上一个路点位置变化小于1mm,姿态变化大于 1e-4 rad, 此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
v速度(如果via_pose与上一个路点位置变化小于1mm, 姿态变化大于 1e-4 rad, 此速度会被作为角速度, 单位 rad / s.否则为线速度, 单位 m / s)
blend_radius交融半径,单位: m
duration运行时间,单位: s
通常当给定了速度和加速度,便能够确定轨迹的运行时间。 如果想延长轨迹的运行时间,便要设置 duration 这个参数。 duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。
当 duration = 0 的时候, 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。 如果duration不等于0,a 和 v 的值将被忽略。
返回
成功返回0;失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
moveCircle(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: List[float], arg2: float, arg3: float, arg4: float, arg5: float) -> int
Lua函数原型
moveCircle(via_pose: table, end_pose: table, a: number, v: number, blend_radius: number, duration: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.moveCircle","params":[[0.440164,-0.00249391,0.398658,2.45651,0,1.5708],[0.440164,0.166256,0.297599,2.45651,0,1.5708],1.2,0.25,0,0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ moveCircle2()

int arcs::common_interface::MotionControl::moveCircle2 ( const CircleParameters param)

高级圆弧或者圆周运动

参数
param圆周运动参数
返回
成功返回0;失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
moveCircle2(self: pyaubo_sdk.MotionControl, arg0: arcs::common_interface::CircleParameters) -> int
Lua函数原型
moveCircle2(param: table) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.moveCircle2","params":[{"pose_via":[0.440164,-0.00249391,0.398658,2.45651,0,1.570], "pose_to":[0.440164,0.166256,0.297599,2.45651,0,1.5708],"a":1.2,"v":0.25,"blend_radius":0,"duration":0,"helix":0, "spiral":0,"direction":0,"loop_times":0}],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ moveCircleWithAxisGroup()

int arcs::common_interface::MotionControl::moveCircleWithAxisGroup ( const std::vector< double > &  via_pose,
const std::vector< double > &  end_pose,
double  a,
double  v,
double  blend_radius,
double  duration,
const std::string &  group_name,
const std::vector< double > &  extq 
)

moveCircle 与外部轴同步运动

参数
group_name外部轴组名称
via_pose圆弧运动途中点的位姿
end_pose圆弧运动结束点的位姿
a加速度
v速度
blend_radius交融半径
duration运行时间
返回

◆ moveIntersection()

int arcs::common_interface::MotionControl::moveIntersection ( const std::vector< std::vector< double > > &  poses,
double  a,
double  v,
double  main_pipe_radius,
double  sub_pipe_radius,
double  normal_distance,
double  normal_alpha 
)

相贯线接口

参数
pose由三个示教位姿组成(首先需要运动到起始点,起始点的要求:过主圆柱 柱体轴心且与子圆柱体轴线平行的平面与子圆柱体在底部的交点) p1:过子圆柱体轴线且与大圆柱体轴线平行的平面,与小圆柱体在左侧顶部的交点 p2:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在左侧底部的交点 p3:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在右侧底部的交点
v速度
a加速度
main_pipe_radius主圆柱体半径
sub_pipe_radius子圆柱体半径
normal_distance两圆柱体轴线距离
normal_alpha两圆柱体轴线的夹角
返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
moveIntersection(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float, arg4: float, arg5: float, arg6: float) -> int
Lua函数原型
moveIntersection(poses: table, a: number, v: number, main_pipe_radius: number, sub_pipe_radius: number, normal_distance: number, normal_alpha: number) -> nil

◆ moveJoint()

int arcs::common_interface::MotionControl::moveJoint ( const std::vector< double > &  q,
double  a,
double  v,
double  blend_radius,
double  duration 
)

添加关节运动

参数
q关节角, 单位 rad
a加速度, 单位 rad/s^2, 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
v速度, 单位 rad/s, 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
blend_radius交融半径, 单位 m
duration运行时间,单位 s
通常当给定了速度和加速度,便能够确定轨迹的运行时间。 如果想延长轨迹的运行时间,便要设置 duration 这个参数。 duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。
当 duration = 0的时候, 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。 如果duration不等于0,a 和 v 的值将被忽略。
返回值
0成功
AUBO_BAD_STATE(1)当前安全模式处于非 Normal、ReducedMode、Recovery 状态
AUBO_QUEUE_FULL(2)规划队列已满
AUBO_BUSY(3)上一条指令正在执行中
-AUBO_BAD_STATE(-1)可能的原因包括但不限于:线程已分离、线程被终止、task_id 未找到,或者当前机器人模式非 Running
-AUBO_TIMEOUT(-4)调用接口超时
-AUBO_INVL_ARGUMENT(-5)参数数组q的长度小于当前机器臂的自由度
异常
arcs::common_interface::AuboException
Python函数原型
moveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float, arg4: float) -> int
Lua函数原型
moveJoint(q: table, a: number, v: number, blend_radius: number, duration: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.moveJoint","params":[[-2.05177, -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0,0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ moveJointWithAxisGroup()

int arcs::common_interface::MotionControl::moveJointWithAxisGroup ( const std::vector< double > &  q,
double  a,
double  v,
double  blend_radius,
double  duration,
const std::string &  group_name,
const std::vector< double > &  extq 
)

机器人与外部轴同步运动

参数
group_name
q
a
v
blend_radius
duration
返回

◆ moveLine()

int arcs::common_interface::MotionControl::moveLine ( const std::vector< double > &  pose,
double  a,
double  v,
double  blend_radius,
double  duration 
)

添加直线运动

参数
pose目标位姿
a加速度(如果位置变化小于1mm,姿态变化大于 1e-4 rad,此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2) 最大值可通过RobotConfig类中的接口getTcpMaxAccelerations()来获取
v速度(如果位置变化小于1mm,姿态变化大于 1e-4 rad,此速度会被作为角速度,单位 rad/s.否则为线速度,单位 m/s) 最大值可通过RobotConfig类中的接口getTcpMaxSpeeds()来获取
blend_radius交融半径,单位 m,值介于0.001和1之间
duration运行时间,单位 s
通常当给定了速度和加速度,便能够确定轨迹的运行时间。 如果想延长轨迹的运行时间,便要设置 duration 这个参数。 duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。
当 duration = 0的时候, 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。 如果duration不等于0,a 和 v 的值将被忽略。
返回值
0成功
AUBO_BAD_STATE(1)当前安全模式处于非 Normal、ReducedMode、Recovery 状态
AUBO_QUEUE_FULL(2)轨迹队列已满
AUBO_BUSY(3)上一条指令正在执行中
-AUBO_BAD_STATE(-1)可能的原因包括但不限于:线程已分离、线程被终止、task_id 未找到,或者当前机器人模式非 Running
-AUBO_TIMEOUT(-4)调用接口超时
-AUBO_INVL_ARGUMENT(-5)参数数组 pose 的长度小于当前机器臂的自由度
异常
arcs::common_interface::AuboException
Python函数原型
moveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float, arg4: float) -> int
Lua函数原型
moveLine(pose: table, a: number, v: number, blend_radius: number, duration: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.moveLine","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],1.2,0.25,0,0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ moveLineWithAxisGroup()

int arcs::common_interface::MotionControl::moveLineWithAxisGroup ( const std::vector< double > &  pose,
double  a,
double  v,
double  blend_radius,
double  duration,
const std::string &  group_name,
const std::vector< double > &  extq 
)

直线运动与外部轴同步运动

参数
group_name外部轴组名称
pose目标位姿
a加速度
v速度
blend_radius交融半径
duration运行时间
返回

◆ movePathBuffer()

int arcs::common_interface::MotionControl::movePathBuffer ( const std::string &  name)

执行缓存的路径

参数
name缓存路径的名字
返回
成功返回0;失败返回错误码 -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
movePathBuffer(self: pyaubo_sdk.MotionControl, arg0: str) -> int
Lua函数原型
movePathBuffer(name: string) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.movePathBuffer","params":["rec"],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ moveProcess()

int arcs::common_interface::MotionControl::moveProcess ( const std::vector< double > &  pose,
double  a,
double  v,
double  blend_radius 
)

添加工艺运动

参数
pose
a
v
blend_radius
返回
成功返回0;失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.moveProcess","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],1.2,0.25,0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ moveSpiral()

int arcs::common_interface::MotionControl::moveSpiral ( const SpiralParameters param,
double  blend_radius,
double  v,
double  a,
double  t 
)

螺旋线运动

参数
param封装的参数
blend_radius
v
a
t
返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpiral", "params":[{"spiral":0.005,"helix":0.005,"angle":18.84,"plane":0,"frame":[0,0,0,0,0,0]},0,0.25,1.2,0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ moveSpline()

int arcs::common_interface::MotionControl::moveSpline ( const std::vector< double > &  q,
double  a,
double  v,
double  duration 
)

在关节空间做样条插值

参数
q关节角度,如果传入参数维度为0,表示样条运动结束
a加速度, 单位 rad/s^2, 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
v速度, 单位 rad/s, 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
duration
返回
成功返回0; 失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
moveSpline(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float) -> int
Lua函数原型
moveSpline(q: table, a: number, v: number, duration: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpline","params":[[0,0,0,0,0,0],1,1,0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathBufferAlloc()

int arcs::common_interface::MotionControl::pathBufferAlloc ( const std::string &  name,
int  type,
int  size 
)

新建一个路径点缓存

参数
name指定路径的名字
type路径的类型
1: toppra 时间最优路径规划
2: cubic_spline(录制的轨迹)
3: 关节B样条插值,最少三个点
size缓存区大小
返回
新建成功返回 AUBO_OK(0)
异常
arcs::common_interface::AuboException
Python函数原型
pathBufferAlloc(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int, arg2: int) -> int
Lua函数原型
pathBufferAlloc(name: string, type: number, size: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAlloc","params":["rec",2,3],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathBufferAppend()

int arcs::common_interface::MotionControl::pathBufferAppend ( const std::string &  name,
const std::vector< std::vector< double > > &  waypoints 
)

向路径缓存添加路点

参数
name路径缓存的名字
waypoints路点
返回
成功返回0;失败返回错误码 -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
pathBufferAppend(self: pyaubo_sdk.MotionControl, arg0: str, arg1: List[List[float]]) -> int
Lua函数原型
pathBufferAppend(name: string, waypoints: table) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAppend","params":["rec",[[-0.000000,0.000009,-0.000001,0.000002,0.000002,0.000000],[-0.000001,0.000010,-0.000002,0.000000,0.000003,0.000002]]],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathBufferEval()

int arcs::common_interface::MotionControl::pathBufferEval ( const std::string &  name,
const std::vector< double > &  a,
const std::vector< double > &  v,
double  t 
)

计算、优化等耗时操作,传入的参数相同时不会重新计算

参数
name通过pathBufferAlloc新建的路径点缓存的名字
a关节加速度限制,需要和机器人自由度大小相同,单位 rad/s^2
v关节速度限制,需要和机器人自由度大小相同,单位 rad/s
t时间
pathBufferAlloc 这个接口分配内存的时候要指定类型, 根据pathBufferAlloc这个接口的类型:
类型为1时,表示运动持续时间
类型为2时,表示采样时间间隔
类型为3时:t表示运动持续时间
若 t=0, 则由使用软件内部默认的时间(推荐使用)
若 t!=0, t需要设置为 路径点数*相邻点时间间隔(points * interval,interval >= 0.01)
返回
成功返回0;失败返回错误码 -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
pathBufferEval(self: pyaubo_sdk.MotionControl, arg0: str, arg1: List[float], arg2: List[float], arg3: float) -> int
Lua函数原型
pathBufferEval(name: string, a: table, v: table, t: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferEval","params":["rec",[1,1,1,1,1,1],[1,1,1,1,1,1],0.02],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathBufferFilter()

int arcs::common_interface::MotionControl::pathBufferFilter ( const std::string &  name,
int  order,
double  fd,
double  fs 
)

关节空间路径滤波器

pathBufferFilter

参数
name缓存路径的名称
order 滤波器阶数(一般取2)
fd 截止频率,越小越光滑,但是延迟会大(一般取3-20)
fs 离散数据的采样频率(一般取20-500)
返回
成功返回0
异常
arcs::common_interface::AuboException
Python函数原型
pathBufferFilter(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int, arg2: float, arg3: float) -> int
Lua函数原型
pathBufferFilter(name: string, order: number, fd: number, fs:number) -> nil

◆ pathBufferFree()

int arcs::common_interface::MotionControl::pathBufferFree ( const std::string &  name)

释放路径缓存

参数
name缓存路径的名字
返回
成功返回0;失败返回错误码 -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
pathBufferFree(self: pyaubo_sdk.MotionControl, arg0: str) -> int
Lua函数原型
pathBufferFree(name: string) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferFree","params":["rec"],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":-5}

◆ pathBufferList()

std::vector< std::string > arcs::common_interface::MotionControl::pathBufferList ( )

列出所有缓存路径的名字

返回
返回所有缓存路径的名字
异常
arcs::common_interface::AuboException
Python函数原型
pathBufferList(self: pyaubo_sdk.MotionControl) -> List[str]
Lua函数原型
pathBufferList() -> table
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferList","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":[]}

◆ pathBufferValid()

bool arcs::common_interface::MotionControl::pathBufferValid ( const std::string &  name)

指定名字的buffer是否有效

buffer需要满足三个条件有效:
1、buffer存在,已经分配过内存
2、传进buffer的点要大于等于buffer的大小
3、要执行一次pathBufferEval

参数
namebuffer的名字
返回
有效返回true; 无效返回false
异常
arcs::common_interface::AuboException
Python函数原型
pathBufferValid(self: pyaubo_sdk.MotionControl, arg0: str) -> bool
Lua函数原型
pathBufferValid(name: string) -> boolean
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferValid","params":["rec"],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":false}

◆ pathOffsetCoordinate()

int arcs::common_interface::MotionControl::pathOffsetCoordinate ( int  ref_coord)

设置偏移的参考坐标系 仅对pathOffsetSet中 type=1 有效

参数
ref_coord参考坐标系 0-基坐标系 1-TCP
异常
arcs::common_interface::AuboException
Python函数原型
pathOffsetCoordinate(self: pyaubo_sdk.MotionControl, arg0: int) -> float
Lua函数原型
pathOffsetCoordinate(ref_coord: number) -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetCoordinate","params":[0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathOffsetDisable()

int arcs::common_interface::MotionControl::pathOffsetDisable ( )

路径偏移失能

返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
pathOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
pathOffsetDisable() -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetDisable","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathOffsetEnable()

int arcs::common_interface::MotionControl::pathOffsetEnable ( )

路径偏移使能

返回
成功返回0; 失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
pathOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
pathOffsetEnable() -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetEnable","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathOffsetLimits()

int arcs::common_interface::MotionControl::pathOffsetLimits ( double  v,
double  a 
)

设置偏移的最大速度和最大加速度 仅对pathOffsetSet中 type=1 有效

参数
v最大速度
a最大加速度
返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
pathOffsetLimits(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
Lua函数原型
pathOffsetLimits(v: number, a: number) -> nil

◆ pathOffsetSet()

int arcs::common_interface::MotionControl::pathOffsetSet ( const std::vector< double > &  offset,
int  type = 0 
)

设置路径偏移

参数
offset在各方向的位姿偏移
type运动类型 0-位置规划 1-速度规划
返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
pathOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: int) -> int
Lua函数原型
pathOffsetSet(offset: table, type: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetSet","params":[[0,0,0.01,0,0,0],0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathOffsetSupv()

int arcs::common_interface::MotionControl::pathOffsetSupv ( const std::vector< double > &  min,
const std::vector< double > &  max,
int  strategy 
)

监控轨迹偏移范围

参数
min沿坐标轴负方向最大偏移量
max沿坐标轴正方向最大偏移量
strategy达到最大偏移量后监控策略     0-禁用监控     1-饱和限制,即维持最大姿态     2-保护停止
返回
异常
arcs::common_interface::AuboException
Python函数原型
pathOffsetSupv(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: List[float], arg2: int) -> int
Lua函数原型
pathOffsetSupv(min: table, max: table, strategy: number) -> number

◆ restoPath()

int arcs::common_interface::MotionControl::restoPath ( )

restoPath

返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.restoPath","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ resumeMoveJoint()

int arcs::common_interface::MotionControl::resumeMoveJoint ( const std::vector< double > &  q,
double  a,
double  v,
double  duration 
)

通过关节运动移动到暂停点的位置

参数
q关节角, 单位 rad
a加速度, 单位 rad/s^2
v速度, 单位 rad/s
duration运行时间,单位 s
通常当给定了速度和加速度,便能够确定轨迹的运行时间。 如果想延长轨迹的运行时间,便要设置 duration 这个参数。 duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。
当 duration = 0的时候, 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。 如果duration不等于0,a 和 v 的值将被忽略。
返回
成功返回0;失败返回错误码 -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
resumeMoveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float) -> int
Lua函数原型
resumeMoveJoint(q: table, a: number, v: number, duration: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.resumeMoveJoint","params":[[-2.05177, -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":-1}

◆ resumeMoveLine()

int arcs::common_interface::MotionControl::resumeMoveLine ( const std::vector< double > &  pose,
double  a,
double  v,
double  duration 
)

通过直线运动移动到暂停点的位置

参数
pose目标位姿
a加速度, 单位 m/s^2
v速度, 单位 m/s
duration运行时间,单位 s
通常当给定了速度和加速度,便能够确定轨迹的运行时间。 如果想延长轨迹的运行时间,便要设置 duration 这个参数。 duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。
当 duration = 0的时候, 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。 如果duration不等于0,a 和 v 的值将被忽略。
返回
成功返回0;失败返回错误码 -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
resumeMoveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float) -> int
Lua函数原型
resumeMoveLine(pose: table, a: number, v: number,duration: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.resumeMoveLine","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],1.2,0.25,0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ resumeSpeedJoint()

int arcs::common_interface::MotionControl::resumeSpeedJoint ( const std::vector< double > &  qd,
double  a,
double  t 
)

关节空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)

当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度

参数
qd目标关节速度, 单位 rad/s
a主轴的加速度, 单位 rad/s^2
t函数返回所需要的时间, 单位 s 如果 t = 0,当达到目标速度的时候,函数将返回; 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。 如果没有达到目标速度,会减速到零。 如果达到了目标速度就是按照目标速度匀速运动。
返回
成功返回0; 失败返回错误码 AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
resumeSpeedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float) -> int
Lua函数原型
resumeSpeedJoint(q: table, a: number, t: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":-1}

◆ resumeSpeedLine()

int arcs::common_interface::MotionControl::resumeSpeedLine ( const std::vector< double > &  xd,
double  a,
double  t 
)

笛卡尔空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)

当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度

参数
xd工具速度, 单位 m/s
a工具位置加速度, 单位 m/s^2
t函数返回所需要的时间, 单位 s
如果 t = 0,当达到目标速度的时候,函数将返回; 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。 如果没有达到目标速度,会减速到零。 如果达到了目标速度就是按照目标速度匀速运动。
返回
成功返回0; 失败返回错误码 -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
resumeSpeedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float) -> int
Lua函数原型
resumeSpeedLine(pose: table, a: number, t: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":-1}

◆ resumeStopJoint()

int arcs::common_interface::MotionControl::resumeStopJoint ( double  acc)

关节空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedJoint接口移动到安全位置后需要停止时调用此接口)

参数
acc关节加速度,单位: rad/s^2
返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
resumeStopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
Lua函数原型
resumeStopJoint(acc: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopJoint","params":[31],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":-1}

◆ resumeStopLine()

int arcs::common_interface::MotionControl::resumeStopLine ( double  acc,
double  acc_rot 
)

笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)

参数
acc位置加速度, 单位: m/s^2
acc_rot姿态加速度,单位: rad/s^2
返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
resumeStopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
Lua函数原型
resumeStopLine(acc: number, acc_rot: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopLine","params":[10,10],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":-1}

◆ servoCartesian()

int arcs::common_interface::MotionControl::servoCartesian ( const std::vector< double > &  pose,
double  a,
double  v,
double  t,
double  lookahead_time,
double  gain 
)

笛卡尔空间伺服

目前可用参数只有 pose 和 t;

参数
pose位姿, 单位 m,
a加速度, 单位 m/s^2,
v速度,单位 m/s,
t运行时间,单位 s
t 值越大,机器臂运动越慢,反之,运动越快; 该参数最优值为连续调用 servoCartesian 接口的间隔时间。
lookahead_time前瞻时间,单位 s
指定机器臂开始减速前要运动的时长,用前瞻时间来平滑轨迹[0.03, 0.2], 当 lookahead_time 小于一个控制周期时,越小则超调量越大, 该参数最优值为一个控制周期。
gain比例增益 跟踪目标位置的比例增益[100, 200], 用于控制运动的顺滑性和精度, 比例增益越大,到达目标位置的时间越长,超调量越小。
返回值
0成功
AUBO_BAD_STATE(1)当前安全模式处于非 Normal、ReducedMode、Recovery 状态
AUBO_QUEUE_FULL(2)规划队列已满
AUBO_BUSY(3)上一条指令正在执行中
-AUBO_BAD_STATE(-1)可能的原因包括但不限于:线程已分离、线程被终止、task_id 未找到,或者当前机器人模式非 Running
-AUBO_TIMEOUT(-4)调用接口超时
-AUBO_INVL_ARGUMENT(-5)轨迹位置超限或速度超限
-AUBO_REQUEST_IGNORE(-13)当前处于非 servo 模式
-AUBO_IK_NO_CONVERGE(-23)逆解计算不收敛,计算出错;
-AUBO_IK_OUT_OF_RANGE(-24)逆解计算超出机器人最大限制;
AUBO_IK_CONFIG_DISMATCH(-25)逆解输入配置存在错误;
-AUBO_IK_JACOBIAN_FAILED(-26)逆解雅可比矩阵计算失败;
-AUBO_IK_NO_SOLU(-27)目标点存在解析解,但均不满足选解条件;
-AUBO_IK_UNKOWN_ERROR(-28)逆解返回未知类型错误;
异常
arcs::common_interface::AuboException
Python函数原型
servoCartesian(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
Lua函数原型
servoCartesian(pose: table, a: number, v: number, t: number, lookahead_time: number, gain: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.servoCartesian","params":[[0.58712,-0.15775,0.48703,2.76,0.344,1.432],0,0,10,0,0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":-13}

◆ servoCartesianWithAxes()

int arcs::common_interface::MotionControl::servoCartesianWithAxes ( const std::vector< double > &  pose,
const std::vector< double > &  extq,
double  a,
double  v,
double  t,
double  lookahead_time,
double  gain 
)

伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等 与 servoJointWithAxes 区别在于接收笛卡尔空间位姿而不是关节角度 (由软件内部直接做逆解)

参数
pose
extq
t
smooth_scale
delay_sacle
返回

◆ servoCartesianWithAxisGroup()

int arcs::common_interface::MotionControl::servoCartesianWithAxisGroup ( const std::vector< double > &  pose,
double  a,
double  v,
double  t,
double  lookahead_time,
double  gain,
const std::string &  group_name,
const std::vector< double > &  extq 
)

◆ servoJoint()

int arcs::common_interface::MotionControl::servoJoint ( const std::vector< double > &  q,
double  a,
double  v,
double  t,
double  lookahead_time,
double  gain 
)

关节空间伺服

目前可用参数只有 q 和 t;

参数
q关节角, 单位 rad,
a加速度, 单位 rad/s^2,
v速度,单位 rad/s,
t运行时间,单位 s
t 值越大,机器臂运动越慢,反之,运动越快; 该参数最优值为连续调用 servoJoint 接口的间隔时间。
lookahead_time前瞻时间,单位 s
指定机器臂开始减速前要运动的时长,用前瞻时间来平滑轨迹[0.03, 0.2], 当 lookahead_time 小于一个控制周期时,越小则超调量越大, 该参数最优值为一个控制周期。
gain比例增益 跟踪目标位置的比例增益[100, 200], 用于控制运动的顺滑性和精度, 比例增益越大,到达目标位置的时间越长,超调量越小。
返回值
0成功
AUBO_BAD_STATE(1)当前安全模式处于非 Normal、ReducedMode、Recovery 状态
AUBO_QUEUE_FULL(2)规划队列已满
AUBO_BUSY(3)上一条指令正在执行中
-AUBO_BAD_STATE(-1)可能的原因包括但不限于:线程已分离、线程被终止、task_id 未找到,或者当前机器人模式非 Running
-AUBO_TIMEOUT(-4)调用接口超时
-AUBO_INVL_ARGUMENT(-5)轨迹位置超限或速度超限
-AUBO_REQUEST_IGNORE(-13)当前处于非 servo 模式
异常
arcs::common_interface::AuboException
Python函数原型
servoJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
Lua函数原型
servoJoint(q: table, a: number, v: number, t: number, lookahead_time: number, gain: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.servoJoint","params":[[0,0,0,0,0,0],0,0,10,0,0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":-13}

◆ servoJointWithAxes()

int arcs::common_interface::MotionControl::servoJointWithAxes ( const std::vector< double > &  q,
const std::vector< double > &  extq,
double  a,
double  v,
double  t,
double  lookahead_time,
double  gain 
)

伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等

参数
q
extq
t
smooth_scale
delay_sacle
返回

◆ servoJointWithAxisGroup()

int arcs::common_interface::MotionControl::servoJointWithAxisGroup ( const std::vector< double > &  q,
double  a,
double  v,
double  t,
double  lookahead_time,
double  gain,
const std::string &  group_name,
const std::vector< double > &  extq 
)

◆ setCirclePathMode()

int arcs::common_interface::MotionControl::setCirclePathMode ( int  mode)

设置圆弧路径模式

参数
mode模式
0:工具姿态相对于圆弧路径点坐标系保持不变
1:姿态线性变化,绕着空间定轴转动,从起始点姿态变化到目标点姿态
2:从起点姿态开始经过中间点姿态,变化到目标点姿态
返回
成功返回0;失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
setCirclePathMode(self: pyaubo_sdk.MotionControl, arg0: int) -> int
Lua函数原型
setCirclePathMode(mode: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setCirclePathMode","params":[0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackCompensate()

int arcs::common_interface::MotionControl::setConveyorTrackCompensate ( int  encoder_id,
double  comp 
)

设置传送带跟踪的补偿值

参数
encoder_id预留
comp传送带补偿值
返回
异常
arcs::common_interface::AuboException
Python函数原型
setConveyorTrackCompensate(self: pyaubo_sdk.MotionControl, arg0: int, arg1: float) -> int
Lua函数原型
setConveyorTrackCompensate(comp: number) -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackCompensate","params":[0, 0.1],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackEncoder()

int arcs::common_interface::MotionControl::setConveyorTrackEncoder ( int  encoder_id,
int  tick_per_meter 
)

设置传送带编码器参数

参数
encoder_id预留
tick_per_meter线性传送带===>一米的脉冲值 环形传送带===>一圈的脉冲值
返回
异常
arcs::common_interface::AuboException
Python函数原型
setConveyorTrackEncoder(self: pyaubo_sdk.MotionControl) -> int
Lua函数原型
setConveyorTrackEncoder -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackEncoder","params":[1,40000],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackLimit()

int arcs::common_interface::MotionControl::setConveyorTrackLimit ( int  encoder_id,
double  limit 
)

设置传送带跟踪的最大距离限制

参数
encoder_id预留
limit传送带跟踪的最大距离限制,单位:米
返回
异常
arcs::common_interface::AuboException
Python函数原型
setConveyorTrackLimit(self: pyaubo_sdk.MotionControl, arg0: int, arg1: double) -> int
Lua函数原型
setConveyorTrackLimit(encoder_id: number, limit: number) -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackLimit","params":[0, 1.5],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackSensorOffset()

int arcs::common_interface::MotionControl::setConveyorTrackSensorOffset ( int  encoder_id,
double  offset 
)

设置传送带示教位置到同步开关之间的距离

参数
encoder_id预留
offset传送带示教位置到同步开关之间的距离,单位:米
返回
异常
arcs::common_interface::AuboException
Python函数原型
setConveyorTrackSensorOffset(self: pyaubo_sdk.MotionControl, arg0: int, arg1: double) -> int
Lua函数原型
setConveyorTrackSensorOffset(encoder_id: number, offset: number) -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSensorOffset","params":[0, 0.2],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackStartWindow()

int arcs::common_interface::MotionControl::setConveyorTrackStartWindow ( int  encoder_id,
double  window_min,
double  window_max 
)

设置传送带跟踪的启动窗口

参数
encoder_id预留
min_window启动窗口的起始位置,单位:米
max_window启动窗口的结束位置,单位:米
返回
异常
arcs::common_interface::AuboException
Python函数原型
setConveyorTrackStartWindow(self: pyaubo_sdk.MotionControl, arg0: int, arg1: double, arg2: double) -> int
Lua函数原型
setConveyorTrackStartWindow(encoder_id: number, min_window: number, max_window: number) -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackStartWindow","params":[0, 0.2, 1.0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackSyncSeparation()

int arcs::common_interface::MotionControl::setConveyorTrackSyncSeparation ( int  encoder_id,
double  distance,
double  time 
)

设置传送带同步分离,用于过滤掉同步开关中不需要的信号

参数
encoder_id预留
distance从出现一个同步信号后到把一个新的同步信号接受为一个有效对象前走的最短距离,单位:米
time从出现一个同步信号后到把一个新的同步信号接受为一个有效对象前走的最短时间,单位:秒

distance和time设置数值大于0即为生效 当distance与time同时设置时,优先生效distance

返回
异常
arcs::common_interface::AuboException
Python函数原型
setConveyorTrackSyncSeparation(self: pyaubo_sdk.MotionControl, arg0: int, arg1: double, arg2: double) -> int
Lua函数原型
setConveyorTrackSyncSeparation(encoder_id: number, distance: number, time: number) -> int
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSyncSeparation","params":[0, 0.05, 0.2],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setEqradius()

int arcs::common_interface::MotionControl::setEqradius ( double  eqradius)

设置等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动,数值越大,姿态旋转速度越快

参数
eqradius0表示只规划移动,姿态旋转跟随移动
返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setEqradius","params":[0.8],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}
Python函数原型
setEqradius(self: pyaubo_sdk.MotionControl, arg0: float) -> int
Lua函数原型
setEqradius(eqradius: number) -> number

◆ setFuturePointSamplePeriod()

int arcs::common_interface::MotionControl::setFuturePointSamplePeriod ( double  sample_time)

设置未来路径上点的采样时间间隔

参数
sample_time采样时间间隔 单位: m/s^2
返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException

◆ setLookAheadSize()

int arcs::common_interface::MotionControl::setLookAheadSize ( int  size)

设置前瞻段数 1.

对于有较高速度平稳性要求的任务,如数控加工,涂胶,焊接等匀速需求,较长的前瞻段数可以提供更优的速度规划,产生的运动会更加平滑; 2.对于快速响应的抓取类任务,更倾向于较短的前瞻段数,以提高反应速度,但可能因为进给的路径不够及时导致速度波动很大.

返回
成功返回0
异常
arcs::common_interface::AuboException
Python函数原型
setLookAheadSize(self: pyaubo_sdk.MotionControl, arg0: int) -> int
Lua函数原型
setLookAheadSize(eqradius: number) -> number
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setLookAheadSize","params":[1],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setResumeStartPoint()

int arcs::common_interface::MotionControl::setResumeStartPoint ( const std::vector< double > &  q,
int  move_type,
double  blend_radius,
const std::vector< double > &  qdmax,
const std::vector< double > &  qddmax,
const std::vector< double > &  vmax,
const std::vector< double > &  amax 
)

设置继续运动参数

参数
q继续运动起始位置
move_type0:关节空间 1:笛卡尔空间
blend_radius交融半径
qdmax关节运动最大速度(6维度数据)
qddmax关节运动最大加速度(6维度数据)
vmax直线运动最大线速度,角速度(2维度数据)
amax直线运动最大线加速度,角加速度(2维度数据)
返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
setResumeStartPoint(self: pyaubo_sdk.MotionControl, arg0:List[float],arg1: int, arg2: float,arg3: List[float], arg4: List[float],arg5:float,arg5:float) -> int
Lua函数原型
setResumeStartPoint(q : table, move_type: number,blend_radius: number, qdmax: table, qddmax: table,vmax:number,amax:number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setResumeStartPoint","params":[[0,0,0,0,0,0],1,1,[0,0,0,0,0,0],[0,0,0,0,0,0],1,1],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setServoMode()

ARCS_DEPRECATED int arcs::common_interface::MotionControl::setServoMode ( bool  enable)

设置伺服模式 使用 setServoModeSelect 替代

参数
enable是否使能
返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
setServoMode(self: pyaubo_sdk.MotionControl, arg0: bool) -> int
Lua函数原型
setServoMode(enable: boolean) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setServoMode","params":[true],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setServoModeSelect()

int arcs::common_interface::MotionControl::setServoModeSelect ( int  mode)

设置伺服运动模式

参数
mode0-退出伺服模式 1-规划伺服模式 2-透传模式(直接下发) 3-透传模式(缓存)
返回
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setServoModeSelect","params":[0],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setSpeedFraction()

int arcs::common_interface::MotionControl::setSpeedFraction ( double  fraction)

动态调整机器人运行速度和加速度比例 (0., 1.

]

参数
fraction机器人运行速度和加速度比例
返回
成功返回0; 失败返回错误码 AUBO_INVL_ARGUMENT AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
setSpeedFraction(self: pyaubo_sdk.MotionControl, arg0: float) -> int
Lua函数原型
setSpeedFraction(fraction: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.setSpeedFraction","params":[0.8],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ setWorkObjectHold()

int arcs::common_interface::MotionControl::setWorkObjectHold ( const std::string &  module_name,
const std::vector< double > &  mounting_pose 
)

当工件安装在另外一台机器人的末端或者外部轴上时,指定其名字和安装位置

注解
暂未实现
参数
module_name控制模块名字
mounting_pose抓取的相对位置, 如果是机器人,则相对于机器人末端中心点(非TCP点)
返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
setWorkObjectHold(self: pyaubo_sdk.MotionControl, arg0: str, arg1: List[float]) -> int
Lua函数原型
setWorkObjectHold(module_name: string, mounting_pose: table) -> nil

◆ speedFractionCritical()

int arcs::common_interface::MotionControl::speedFractionCritical ( bool  enable)

速度比例设置临界区,使能之后速度比例被强制设定为1.

, 失能之后恢复之前的速度比例

参数
enable
返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.speedFractionCritical","params":[true],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ speedJoint()

int arcs::common_interface::MotionControl::speedJoint ( const std::vector< double > &  qd,
double  a,
double  t 
)

关节空间速度跟随

当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度

参数
qd目标关节速度, 单位 rad/s
a主轴的加速度, 单位 rad/s^2
t函数返回所需要的时间, 单位 s
如果 t = 0,当达到目标速度的时候,函数将返回; 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
如果没有达到目标速度,会减速到零。 如果达到了目标速度就是按照目标速度匀速运动。
返回值
0成功
AUBO_BAD_STATE(1)当前安全模式处于非 Normal、ReducedMode、Recovery 状态
AUBO_BUSY(3)上一条指令正在执行中
-AUBO_BAD_STATE(-1)可能的原因包括但不限于:线程已分离、线程被终止、task_id 未找到,或者当前机器人模式非 Running
-AUBO_TIMEOUT(-4)调用接口超时
-AUBO_INVL_ARGUMENT(-5)参数数组qd的长度小于当前机器臂的自由度
异常
arcs::common_interface::AuboException
Python函数原型
speedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float) -> int
Lua函数原型
speedJoint(qd: table, a: number, t: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.speedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ speedLine()

int arcs::common_interface::MotionControl::speedLine ( const std::vector< double > &  xd,
double  a,
double  t 
)

笛卡尔空间速度跟随

当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度

参数
xd工具速度, 单位 m/s
a工具位置加速度, 单位 m/s^2
t函数返回所需要的时间, 单位 s
如果 t = 0,当达到目标速度的时候,函数将返回; 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。 如果没有达到目标速度,会减速到零。 如果达到了目标速度就是按照目标速度匀速运动。
返回值
0成功
AUBO_BAD_STATE(1)当前安全模式处于非 Normal、ReducedMode、Recovery 状态
AUBO_BUSY(3)上一条指令正在执行中
-AUBO_BAD_STATE(-1)可能的原因包括但不限于:线程已分离、线程被终止、task_id 未找到,或者当前机器人模式非 Running
-AUBO_TIMEOUT(-4)调用接口超时
异常
arcs::common_interface::AuboException
Python函数原型
speedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float) -> int
Lua函数原型
speedLine(pose: table, a: number, t: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.speedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ startMove()

int arcs::common_interface::MotionControl::startMove ( )

StartMove 用于在以下情况下恢复机器人、外部轴的运动以及相关工艺进程: • 通过 StopMove 指令停止后。 • 执行 StorePath ... RestoPath 序列后。 • 发生异步运动错误(如 ERR_PATH_STOP)或特定工艺错误并在 ERROR 处理器中处理后。

返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.startMove","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ stopJoint()

int arcs::common_interface::MotionControl::stopJoint ( double  acc)

关节空间停止运动

参数
acc关节加速度,单位: rad/s^2
返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
stopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
Lua函数原型
stopJoint(acc: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.stopJoint","params":[31],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ stopLine()

int arcs::common_interface::MotionControl::stopLine ( double  acc,
double  acc_rot 
)

笛卡尔空间停止运动

参数
acc工具加速度, 单位: m/s^2
acc_rot
返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
Python函数原型
stopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
Lua函数原型
stopLine(acc: number, acc_rot: number) -> nil
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.stopLine","params":[10,10],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ stopMove()

int arcs::common_interface::MotionControl::stopMove ( bool  quick,
bool  all_tasks 
)

StopMove 用于临时停止机器人和外部轴的运动以及相关工艺进程。如果调用 StartMove 指令,则运动和工艺进程将恢复。

该指令可用于中断处理程序中,在发生中断时临时停止机器人。

参数
quicktrue: 以最快速度在路径上停止机器人。未指定 quick 参数时,机器人将在路径上停止,但制动距离较长(与普通程序停止相同)。
返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException

◆ storePath()

int arcs::common_interface::MotionControl::storePath ( bool  keep_sync)

storePath

参数
keep_sync
返回
成功返回0; 失败返回错误码 AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException

◆ trackCartesian()

int arcs::common_interface::MotionControl::trackCartesian ( const std::vector< double > &  pose,
double  t,
double  smooth_scale,
double  delay_sacle 
)

跟踪运动,用于执行离线轨迹、透传用户规划轨迹等 与 trackJoint 区别在于接收笛卡尔空间位姿而不是关节角度 (由软件内部直接做逆解)

参数
pose
t
smooth_scale
delay_sacle
返回
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.trackCartesian","params":[[0.58712,-0.15775,0.48703,2.76,0.344,1.432],0.01,0.5,1],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ trackJoint()

int arcs::common_interface::MotionControl::trackJoint ( const std::vector< double > &  q,
double  t,
double  smooth_scale,
double  delay_sacle 
)

跟踪运动,用于执行离线轨迹、透传用户规划轨迹等

参数
q
smooth_scale
delay_sacle
返回
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.trackJoint","params":[[0,0,0,0,0,0],0.01,0.5,1],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ weaveEnd()

int arcs::common_interface::MotionControl::weaveEnd ( )

结束摆动

返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException
JSON-RPC请求示例
{"jsonrpc":"2.0","method":"rob1.MotionControl.weaveEnd","params":[],"id":1}
JSON-RPC响应示例
{"id":1,"jsonrpc":"2.0","result":0}

◆ weaveStart()

int arcs::common_interface::MotionControl::weaveStart ( const std::string &  params)

开始摆动: weaveStart 和 weaveEnd 的 moveLine/moveCircle 将根据 params 进行摆动

参数
paramsJson字符串用于定义摆动参数 { "type": <string>, // "SINE" "SPIRAL" "TRIANGLE" "TRAPEZOIDAL" "step": <num>, "amplitude": {<num>,<num>}, "hold_distance": {<num>,<num>}, "angle": <num> "direction": <num> }
返回
成功返回0;失败返回错误码 AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
异常
arcs::common_interface::AuboException

◆ weaveUpdateParameters()

int arcs::common_interface::MotionControl::weaveUpdateParameters ( const std::string &  params)

更新摆动过程中的频率和振幅

参数
paramsJson字符串用于定义摆动参数 { "frequency": <num>, "amplitude": {<num>,<num>} }
返回
成功返回0
异常
arcs::common_interface::AuboException

类成员变量说明

◆ d_

void* arcs::common_interface::MotionControl::d_
protected

在文件 motion_control.h5084 行定义.


该类的文档由以下文件生成: