8#ifndef AUBO_SDK_MOTION_CONTROL_INTERFACE_H
9#define AUBO_SDK_MOTION_CONTROL_INTERFACE_H
15#include <aubo/global_config.h>
19namespace common_interface {
354 const std::vector<double> &max,
int strategy);
700 const std::vector<double> &mounting_pose);
879 int servoJoint(
const std::vector<double> &q,
double a,
double v,
double t,
880 double lookahead_time,
double gain);
933 double t,
double lookahead_time,
double gain);
946 const std::vector<double> &extq,
double a,
double v,
947 double t,
double lookahead_time,
double gain);
962 const std::vector<double> &extq,
double a,
963 double v,
double t,
double lookahead_time,
981 int trackJoint(
const std::vector<double> &q,
double t,
double smooth_scale,
1003 double smooth_scale,
double delay_sacle);
1071 int speedJoint(
const std::vector<double> &qd,
double a,
double t);
1142 int speedLine(
const std::vector<double> &xd,
double a,
double t);
1250 int moveJoint(
const std::vector<double> &q,
double a,
double v,
1251 double blend_radius,
double duration);
1330 int moveLine(
const std::vector<double> &pose,
double a,
double v,
1331 double blend_radius,
double duration);
1356 double blend_radius);
1437 const std::vector<double> &end_pose,
double a,
double v,
1438 double blend_radius,
double duration);
1555 const std::vector<std::vector<double>> &waypoints);
1590 const std::vector<double> &v,
double t);
1750 double a,
double v,
double main_pipe_radius,
1751 double sub_pipe_radius,
double normal_distance,
1752 double normal_alpha);
1955 int tick_per_revo,
bool rotate_tool);
1971 int tick_per_meter);
2011 double a,
double t);
2065#define MotionControl_DECLARES \
2066 _FUNC(MotionControl, 0, getEqradius) \
2067 _FUNC(MotionControl, 1, setEqradius,eqradius) \
2068 _FUNC(MotionControl, 0, getSpeedFraction) \
2069 _FUNC(MotionControl, 1, setSpeedFraction, fraction) \
2070 _INST(MotionControl, 1, speedFractionCritical, enable) \
2071 _FUNC(MotionControl, 0, isSpeedFractionCritical) \
2072 _FUNC(MotionControl, 0, isBlending) \
2073 _INST(MotionControl, 0, pathOffsetEnable) \
2074 _INST(MotionControl, 2, pathOffsetSet, offset, type) \
2075 _INST(MotionControl, 0, pathOffsetDisable) \
2076 _INST(MotionControl, 0, jointOffsetEnable) \
2077 _INST(MotionControl, 2, jointOffsetSet, offset, type) \
2078 _INST(MotionControl, 0, jointOffsetDisable) \
2079 _FUNC(MotionControl, 0, getTrajectoryQueueSize) \
2080 _FUNC(MotionControl, 0, getQueueSize) \
2081 _FUNC(MotionControl, 0, getExecId) \
2082 _FUNC(MotionControl, 1, getDuration, id) \
2083 _FUNC(MotionControl, 1, getMotionLeftTime, id) \
2084 _FUNC(MotionControl, 0, getProgress) \
2085 _INST(MotionControl, 2, setWorkObjectHold, module_name, mounting_pose) \
2086 _FUNC(MotionControl, 0, getWorkObjectHold) \
2087 _FUNC(MotionControl, 0, getPauseJointPositions) \
2088 _FUNC(MotionControl, 1, setServoMode, enable) \
2089 _FUNC(MotionControl, 0, isServoModeEnabled) \
2090 _FUNC(MotionControl, 1, setServoModeSelect, mode) \
2091 _FUNC(MotionControl, 0, getServoModeSelect) \
2092 _FUNC(MotionControl, 6, servoJoint, q, a, v, t, lookahead_time, gain) \
2093 _FUNC(MotionControl, 6, servoCartesian, pose, a, v, t, lookahead_time, gain)\
2094 _INST(MotionControl, 7, servoJointWithAxes, q, extq, a, v, t, lookahead_time, gain) \
2095 _INST(MotionControl, 7, servoCartesianWithAxes, pose, extq, a, v, t, lookahead_time, gain) \
2096 _INST(MotionControl, 4, trackJoint, q, t, smooth_scale, delay_sacle) \
2097 _INST(MotionControl, 4, trackCartesian, pose, t, smooth_scale, delay_sacle) \
2098 _INST(MotionControl, 1, followJoint, q) \
2099 _INST(MotionControl, 1, followLine, pose) \
2100 _INST(MotionControl, 3, speedJoint, qd, a, t) \
2101 _FUNC(MotionControl, 3, resumeSpeedJoint, qd, a, t) \
2102 _INST(MotionControl, 3, speedLine, xd, a, t) \
2103 _FUNC(MotionControl, 3, resumeSpeedLine, xd, a, t) \
2104 _INST(MotionControl, 4, moveSpline, q, a, v, duration) \
2105 _INST(MotionControl, 5, moveJoint, q, a, v, blend_radius, duration) \
2106 _FUNC(MotionControl, 4, resumeMoveJoint, q, a, v, duration) \
2107 _INST(MotionControl, 5, moveLine, pose, a, v, blend_radius, duration) \
2108 _INST(MotionControl, 4, moveProcess, pose, a, v, blend_radius) \
2109 _FUNC(MotionControl, 4, resumeMoveLine, pose, a, v, duration) \
2110 _INST(MotionControl, 6, moveCircle, via_pose, end_pose, a, v, \
2111 blend_radius, duration) \
2112 _INST(MotionControl, 1, setCirclePathMode, mode) \
2113 _INST(MotionControl, 1, moveCircle2, param) \
2114 _FUNC(MotionControl, 3, pathBufferAlloc, name, type, size) \
2115 _FUNC(MotionControl, 2, pathBufferAppend, name, waypoints) \
2116 _FUNC(MotionControl, 4, pathBufferEval, name, a, v, t) \
2117 _FUNC(MotionControl, 1, pathBufferValid, name) \
2118 _FUNC(MotionControl, 1, pathBufferFree, name) \
2119 _FUNC(MotionControl, 0, pathBufferList) \
2120 _INST(MotionControl, 1, movePathBuffer, name) \
2121 _INST(MotionControl, 7, moveIntersection, poses, a, v, main_pipe_radius, sub_pipe_radius, normal_distance, normal_alpha)\
2122 _FUNC(MotionControl, 1, stopJoint, acc) \
2123 _FUNC(MotionControl, 1, resumeStopJoint, acc) \
2124 _FUNC(MotionControl, 2, stopLine, acc, acc_rot) \
2125 _FUNC(MotionControl, 2, resumeStopLine, acc, acc_rot) \
2126 _INST(MotionControl, 1, weaveStart, params) \
2127 _INST(MotionControl, 0, weaveEnd) \
2128 _FUNC(MotionControl, 1, storePath, keep_sync) \
2129 _FUNC(MotionControl, 2, stopMove, quick, all_tasks) \
2130 _FUNC(MotionControl, 0, startMove) \
2131 _FUNC(MotionControl, 0, clearPath) \
2132 _FUNC(MotionControl, 0, restoPath) \
2133 _FUNC(MotionControl, 1, setFuturePointSamplePeriod, sample_time) \
2134 _FUNC(MotionControl, 0, getFuturePathPointsJoint) \
2135 _INST(MotionControl, 4, conveyorTrackCircle, encoder_id, center, tick_per_revo, rotate_tool) \
2136 _INST(MotionControl, 3, conveyorTrackLine, encoder_id, direction, tick_per_meter) \
2137 _INST(MotionControl, 1, conveyorTrackStop, a) \
2138 _INST(MotionControl, 5, moveSpiral, param, blend_radius, v, a, t) \
2139 _INST(MotionControl, 2, pathOffsetLimits, v, a) \
2140 _INST(MotionControl, 1, pathOffsetCoordinate, ref_coord) \
2141 _FUNC(MotionControl, 0, getLookAheadSize) \
2142 _INST(MotionControl, 1, setLookAheadSize, size) \
2143 _INST(MotionControl, 3, pathOffsetSupv, min, max, strategy) \
2144 _INST(MotionControl, 4, pathBufferFilter, name, order, fd, fs)
int resumeMoveJoint(const std::vector< double > &q, double a, double v, double duration)
通过关节运动移动到暂停点的位置
int pathOffsetLimits(double v, double a)
设置偏移的最大速度和最大加速度 仅对pathOffsetSet中 type=1 有效
int followJoint(const std::vector< double > &q)
关节空间跟随
int setLookAheadSize(int size)
设置前瞻段数 1.
int jointOffsetDisable()
关节偏移失能
int followLine(const std::vector< double > &pose)
笛卡尔空间跟随
int stopJoint(double acc)
关节空间停止运动
int speedJoint(const std::vector< double > &qd, double a, double t)
关节空间速度跟随
int moveCircle2(const CircleParameters ¶m)
高级圆弧或者圆周运动
int getServoModeSelect()
获取伺服运动模式
int pathOffsetSupv(const std::vector< double > &min, const std::vector< double > &max, int strategy)
监控轨迹偏移范围
int getTrajectoryQueueSize()
获取已经入队的运动规划插补点数量
int clearPath()
ClearPath (Clear Path) clears the whole motion path on the current motion path level (base level or S...
std::vector< std::vector< double > > getFuturePathPointsJoint()
获取未来路径上的轨迹点
int conveyorTrackStop(double a)
终止传送带跟随
int jointOffsetSet(const std::vector< double > &offset, int type=1)
设置关节偏移
int resumeSpeedLine(const std::vector< double > &xd, double a, double t)
笛卡尔空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
double getMotionLeftTime(int id)
获取指定ID的运动指令段的剩余执行时间
int pathBufferAlloc(const std::string &name, int type, int size)
新建一个路径点缓存
int servoCartesian(const std::vector< double > &pose, double a, double v, double t, double lookahead_time, double gain)
笛卡尔空间伺服
double getSpeedFraction()
获取速度和加速度比例,默认为 1 可以通过 setSpeedFraction 接口设置
std::vector< double > getPauseJointPositions()
getPauseJointPositions
int startMove()
StartMove is used to resume robot, external axes movement and belonging process after the movement ha...
int storePath(bool keep_sync)
storePath
int moveJoint(const std::vector< double > &q, double a, double v, double blend_radius, double duration)
添加关节运动
int moveSpline(const std::vector< double > &q, double a, double v, double duration)
在关节空间做样条插值
int resumeMoveLine(const std::vector< double > &pose, double a, double v, double duration)
通过直线运动移动到暂停点的位置
int stopLine(double acc, double acc_rot)
笛卡尔空间停止运动
int resumeStopLine(double acc, double acc_rot)
笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)
std::tuple< std::string, std::vector< double > > getWorkObjectHold()
getWorkObjectHold
int moveCircle(const std::vector< double > &via_pose, const std::vector< double > &end_pose, double a, double v, double blend_radius, double duration)
添加圆弧运动
int speedFractionCritical(bool enable)
速度比例设置临界区,使能之后速度比例被强制设定为1.
std::vector< std::string > pathBufferList()
列出所有缓存路径的名字
int stopMove(bool quick, bool all_tasks)
StopMove is used to stop robot and external axes movements and any belonging process temporarily.
int jointOffsetEnable()
关节偏移使能
ARCS_DEPRECATED bool isServoModeEnabled()
判断伺服模式是否使能 使用 getServoModeSelect 替代
int pathOffsetDisable()
路径偏移失能
int conveyorTrackCircle(int encoder_id, const std::vector< double > ¢er, int tick_per_revo, bool rotate_tool)
圆形传送带跟随
int conveyorTrackLine(int encoder_id, const std::vector< double > &direction, int tick_per_meter)
线性传送带跟随
int getQueueSize()
获取已经入队的指令段(INST)数量,运动指令包括 moveJoint/moveLine/moveCircle 等运动指令以及 setPayload 等配置指令
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 pathBufferAppend(const std::string &name, const std::vector< std::vector< double > > &waypoints)
向路径缓存添加路点
int getLookAheadSize()
获取前瞻段数
int moveLine(const std::vector< double > &pose, double a, double v, double blend_radius, double duration)
添加直线运动
int resumeSpeedJoint(const std::vector< double > &qd, double a, double t)
关节空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
int moveProcess(const std::vector< double > &pose, double a, double v, double blend_radius)
添加工艺运动
int pathBufferFilter(const std::string &name, int order, double fd, double fs)
关节空间路径滤波器
bool pathBufferValid(const std::string &name)
指定名字的buffer是否有效
ARCS_DEPRECATED int setServoMode(bool enable)
设置伺服模式 使用 setServoModeSelect 替代
int setCirclePathMode(int mode)
设置圆弧路径模式
int setServoModeSelect(int mode)
设置伺服运动模式
int speedLine(const std::vector< double > &xd, double a, double t)
笛卡尔空间速度跟随
double getDuration(int id)
获取指定ID的运动指令段的预期执行时间
int trackCartesian(const std::vector< double > &pose, double t, double smooth_scale, double delay_sacle)
跟踪运动,用于执行离线轨迹、透传用户规划轨迹等 与 trackJoint 区别在于接收笛卡尔空间位姿而不是关节角度 (由软件内部直接做逆解)
int pathOffsetSet(const std::vector< double > &offset, int type=0)
设置路径偏移
int servoJointWithAxes(const std::vector< double > &q, const std::vector< double > &extq, double a, double v, double t, double lookahead_time, double gain)
伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
double getProgress()
获取当前运动指令段的执行进度
int pathOffsetCoordinate(int ref_coord)
设置偏移的参考坐标系 仅对pathOffsetSet中 type=1 有效
int pathOffsetEnable()
路径偏移使能
int moveSpiral(const SpiralParameters ¶m, double blend_radius, double v, double a, double t)
螺旋线运动
int weaveStart(const std::string ¶ms)
开始摆动: weaveStart 和 weaveEnd 的 moveLine/moveCircle 将根据 params 进行摆动
int pathBufferFree(const std::string &name)
释放路径缓存
int setFuturePointSamplePeriod(double sample_time)
设置未来路径上点的采样时间间隔
double getEqradius()
获取等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动 可以通过 setEqradius 设置,默认为1
int setWorkObjectHold(const std::string &module_name, const std::vector< double > &mounting_pose)
当工件安装在另外一台机器人的末端或者外部轴上时,指定其名字和安装位置
int setEqradius(double eqradius)
设置等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动,数值越大,姿态旋转速度越快
int getExecId()
获取当前正在插补的运动指令段的ID
int setSpeedFraction(double fraction)
动态调整机器人运行速度和加速度比例 (0., 1.
int resumeStopJoint(double acc)
关节空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedJoint接口移动到安全位置后需要停止时调用此接口)
int trackJoint(const std::vector< double > &q, double t, double smooth_scale, double delay_sacle)
跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
bool isSpeedFractionCritical()
是否处于速度比例设置临界区
int servoJoint(const std::vector< double > &q, double a, double v, double t, double lookahead_time, double gain)
关节空间伺服
int pathBufferEval(const std::string &name, const std::vector< double > &a, const std::vector< double > &v, double t)
计算、优化等耗时操作,传入的参数相同时不会重新计算
int servoCartesianWithAxes(const std::vector< double > &pose, const std::vector< double > &extq, double a, double v, double t, double lookahead_time, double gain)
伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等 与 servoJointWithAxes 区别在于接收笛卡尔空间位姿而不是关节角度 (由软件内部直接做逆解)
std::shared_ptr< MotionControl > MotionControlPtr
PathBufferType
pathBuffer类型
@ PathBuffer_JointSpline
3: 关节B样条插值,最少三个点 废弃,建议用5替代,现在实际是关节空间 CUBIC_SPLINE
@ PathBuffer_CubicSpline
2: cubic_spline(录制的轨迹)
@ PathBuffer_TOPPRA
1: toppra 时间最优路径规划
@ PathBuffer_JointSplineC
4:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿 废弃,建议用6替代,现在实际是关节空间 CUBIC_SPLINE
@ PathBuffer_JointBSpline
@ PathBuffer_JointBSplineC
6:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿