8 #ifndef AUBO_SDK_MOTION_CONTROL_INTERFACE_H 9 #define AUBO_SDK_MOTION_CONTROL_INTERFACE_H 15 #include <aubo/global_config.h> 19 namespace common_interface {
90 int setEqradius(
double eqradius);
118 int setSpeedFraction(
double fraction);
141 double getSpeedFraction();
162 int speedFractionCritical(
bool enable);
178 bool isSpeedFractionCritical();
218 int pathOffsetLimits(
double v,
double a);
240 int pathOffsetCoordinate(
int ref_coord);
265 int pathOffsetEnable();
294 int pathOffsetSet(
const std::vector<double> &offset,
int type = 0);
319 int pathOffsetDisable();
340 int pathOffsetSupv(
const std::vector<double> &min,
341 const std::vector<double> &max,
int strategy);
366 int jointOffsetEnable();
395 int jointOffsetSet(
const std::vector<double> &offset,
int type = 1);
420 int jointOffsetDisable();
468 int getTrajectoryQueueSize();
515 double getDuration(
int id);
538 double getMotionLeftTime(
int id);
560 int stopMove(
bool quick,
bool all_tasks);
599 int storePath(
bool keep_sync);
660 double getProgress();
686 int setWorkObjectHold(
const std::string &module_name,
687 const std::vector<double> &mounting_pose);
712 std::tuple<std::string, std::vector<double>> getWorkObjectHold();
737 std::vector<double> getPauseJointPositions();
764 ARCS_DEPRECATED
int setServoMode(
bool enable);
787 ARCS_DEPRECATED
bool isServoModeEnabled();
806 int setServoModeSelect(
int mode);
820 int getServoModeSelect();
866 int servoJoint(
const std::vector<double> &q,
double a,
double v,
double t,
867 double lookahead_time,
double gain);
919 int servoCartesian(
const std::vector<double> &pose,
double a,
double v,
920 double t,
double lookahead_time,
double gain);
932 int servoJointWithAxes(
const std::vector<double> &q,
933 const std::vector<double> &extq,
double a,
double v,
934 double t,
double lookahead_time,
double gain);
948 int servoCartesianWithAxes(
const std::vector<double> &pose,
949 const std::vector<double> &extq,
double a,
950 double v,
double t,
double lookahead_time,
968 int trackJoint(
const std::vector<double> &q,
double t,
double smooth_scale,
989 int trackCartesian(
const std::vector<double> &pose,
double t,
990 double smooth_scale,
double delay_sacle);
1006 int followJoint(
const std::vector<double> &q);
1022 int followLine(
const std::vector<double> &pose);
1058 int speedJoint(
const std::vector<double> &qd,
double a,
double t);
1094 int resumeSpeedJoint(
const std::vector<double> &qd,
double a,
double t);
1129 int speedLine(
const std::vector<double> &xd,
double a,
double t);
1162 int resumeSpeedLine(
const std::vector<double> &xd,
double a,
double t);
1194 int moveSpline(
const std::vector<double> &q,
double a,
double v,
1237 int moveJoint(
const std::vector<double> &q,
double a,
double v,
1238 double blend_radius,
double duration);
1273 int resumeMoveJoint(
const std::vector<double> &q,
double a,
double v,
1317 int moveLine(
const std::vector<double> &pose,
double a,
double v,
1318 double blend_radius,
double duration);
1342 int moveProcess(
const std::vector<double> &pose,
double a,
double v,
1343 double blend_radius);
1378 int resumeMoveLine(
const std::vector<double> &pose,
double a,
double v,
1423 int moveCircle(
const std::vector<double> &via_pose,
1424 const std::vector<double> &end_pose,
double a,
double v,
1425 double blend_radius,
double duration);
1455 int setCirclePathMode(
int mode);
1514 int pathBufferAlloc(
const std::string &name,
int type,
int size);
1541 int pathBufferAppend(
const std::string &name,
1542 const std::vector<std::vector<double>> &waypoints);
1576 int pathBufferEval(
const std::string &name,
const std::vector<double> &a,
1577 const std::vector<double> &v,
double t);
1605 bool pathBufferValid(
const std::string &name);
1630 int pathBufferFree(
const std::string &name);
1652 std::vector<std::string> pathBufferList();
1677 int movePathBuffer(
const std::string &name);
1712 int moveIntersection(
const std::vector<std::vector<double>> &poses,
1713 double a,
double v,
double main_pipe_radius,
1714 double sub_pipe_radius,
double normal_distance,
1715 double normal_alpha);
1741 int stopJoint(
double acc);
1768 int resumeStopJoint(
double acc);
1796 int stopLine(
double acc,
double acc_rot);
1825 int resumeStopLine(
double acc,
double acc_rot);
1849 int weaveStart(
const std::string ¶ms);
1883 int setFuturePointSamplePeriod(
double sample_time);
1899 std::vector<std::vector<double>> getFuturePathPointsJoint();
1915 int conveyorTrackCircle(
int encoder_id,
const std::vector<double> ¢er,
1916 int tick_per_revo,
bool rotate_tool);
1931 int conveyorTrackLine(
int encoder_id,
const std::vector<double> &direction,
1932 int tick_per_meter);
1945 int conveyorTrackStop(
double a);
1971 int moveSpiral(
const SpiralParameters ¶m,
double blend_radius,
double v,
1972 double a,
double t);
1994 int getLookAheadSize();
2018 int setLookAheadSize(
int size);
2026 #define MotionControl_DECLARES \ 2027 _FUNC(MotionControl, 0, getEqradius) \ 2028 _FUNC(MotionControl, 1, setEqradius,eqradius) \ 2029 _FUNC(MotionControl, 0, getSpeedFraction) \ 2030 _FUNC(MotionControl, 1, setSpeedFraction, fraction) \ 2031 _INST(MotionControl, 1, speedFractionCritical, enable) \ 2032 _FUNC(MotionControl, 0, isSpeedFractionCritical) \ 2033 _FUNC(MotionControl, 0, isBlending) \ 2034 _INST(MotionControl, 0, pathOffsetEnable) \ 2035 _INST(MotionControl, 2, pathOffsetSet, offset, type) \ 2036 _INST(MotionControl, 0, pathOffsetDisable) \ 2037 _INST(MotionControl, 0, jointOffsetEnable) \ 2038 _INST(MotionControl, 2, jointOffsetSet, offset, type) \ 2039 _INST(MotionControl, 0, jointOffsetDisable) \ 2040 _FUNC(MotionControl, 0, getTrajectoryQueueSize) \ 2041 _FUNC(MotionControl, 0, getQueueSize) \ 2042 _FUNC(MotionControl, 0, getExecId) \ 2043 _FUNC(MotionControl, 1, getDuration, id) \ 2044 _FUNC(MotionControl, 1, getMotionLeftTime, id) \ 2045 _FUNC(MotionControl, 0, getProgress) \ 2046 _INST(MotionControl, 2, setWorkObjectHold, module_name, mounting_pose) \ 2047 _FUNC(MotionControl, 0, getWorkObjectHold) \ 2048 _FUNC(MotionControl, 0, getPauseJointPositions) \ 2049 _FUNC(MotionControl, 1, setServoMode, enable) \ 2050 _FUNC(MotionControl, 0, isServoModeEnabled) \ 2051 _FUNC(MotionControl, 1, setServoModeSelect, mode) \ 2052 _FUNC(MotionControl, 0, getServoModeSelect) \ 2053 _FUNC(MotionControl, 6, servoJoint, q, a, v, t, lookahead_time, gain) \ 2054 _FUNC(MotionControl, 6, servoCartesian, pose, a, v, t, lookahead_time, gain)\ 2055 _INST(MotionControl, 7, servoJointWithAxes, q, extq, a, v, t, lookahead_time, gain) \ 2056 _INST(MotionControl, 7, servoCartesianWithAxes, pose, extq, a, v, t, lookahead_time, gain) \ 2057 _INST(MotionControl, 4, trackJoint, q, t, smooth_scale, delay_sacle) \ 2058 _INST(MotionControl, 4, trackCartesian, pose, t, smooth_scale, delay_sacle) \ 2059 _INST(MotionControl, 1, followJoint, q) \ 2060 _INST(MotionControl, 1, followLine, pose) \ 2061 _INST(MotionControl, 3, speedJoint, qd, a, t) \ 2062 _FUNC(MotionControl, 3, resumeSpeedJoint, qd, a, t) \ 2063 _INST(MotionControl, 3, speedLine, xd, a, t) \ 2064 _FUNC(MotionControl, 3, resumeSpeedLine, xd, a, t) \ 2065 _INST(MotionControl, 4, moveSpline, q, a, v, duration) \ 2066 _INST(MotionControl, 5, moveJoint, q, a, v, blend_radius, duration) \ 2067 _FUNC(MotionControl, 4, resumeMoveJoint, q, a, v, duration) \ 2068 _INST(MotionControl, 5, moveLine, pose, a, v, blend_radius, duration) \ 2069 _INST(MotionControl, 4, moveProcess, pose, a, v, blend_radius) \ 2070 _FUNC(MotionControl, 4, resumeMoveLine, pose, a, v, duration) \ 2071 _INST(MotionControl, 6, moveCircle, via_pose, end_pose, a, v, \ 2072 blend_radius, duration) \ 2073 _INST(MotionControl, 1, setCirclePathMode, mode) \ 2074 _INST(MotionControl, 1, moveCircle2, param) \ 2075 _FUNC(MotionControl, 3, pathBufferAlloc, name, type, size) \ 2076 _FUNC(MotionControl, 2, pathBufferAppend, name, waypoints) \ 2077 _FUNC(MotionControl, 4, pathBufferEval, name, a, v, t) \ 2078 _FUNC(MotionControl, 1, pathBufferValid, name) \ 2079 _FUNC(MotionControl, 1, pathBufferFree, name) \ 2080 _FUNC(MotionControl, 0, pathBufferList) \ 2081 _INST(MotionControl, 1, movePathBuffer, name) \ 2082 _INST(MotionControl, 7, moveIntersection, poses, a, v, main_pipe_radius, sub_pipe_radius, normal_distance, normal_alpha)\ 2083 _FUNC(MotionControl, 1, stopJoint, acc) \ 2084 _FUNC(MotionControl, 1, resumeStopJoint, acc) \ 2085 _FUNC(MotionControl, 2, stopLine, acc, acc_rot) \ 2086 _FUNC(MotionControl, 2, resumeStopLine, acc, acc_rot) \ 2087 _INST(MotionControl, 1, weaveStart, params) \ 2088 _INST(MotionControl, 0, weaveEnd) \ 2089 _FUNC(MotionControl, 1, storePath, keep_sync) \ 2090 _FUNC(MotionControl, 2, stopMove, quick, all_tasks) \ 2091 _FUNC(MotionControl, 0, startMove) \ 2092 _FUNC(MotionControl, 0, clearPath) \ 2093 _FUNC(MotionControl, 0, restoPath) \ 2094 _FUNC(MotionControl, 1, setFuturePointSamplePeriod, sample_time) \ 2095 _FUNC(MotionControl, 0, getFuturePathPointsJoint) \ 2096 _INST(MotionControl, 4, conveyorTrackCircle, encoder_id, center, tick_per_revo, rotate_tool) \ 2097 _INST(MotionControl, 3, conveyorTrackLine, encoder_id, direction, tick_per_meter) \ 2098 _INST(MotionControl, 1, conveyorTrackStop, a) \ 2099 _INST(MotionControl, 5, moveSpiral, param, blend_radius, v, a, t) \ 2100 _INST(MotionControl, 2, pathOffsetLimits, v, a) \ 2101 _INST(MotionControl, 1, pathOffsetCoordinate, ref_coord) \ 2102 _FUNC(MotionControl, 0, getLookAheadSize) \ 2103 _INST(MotionControl, 1, setLookAheadSize, size) \ 2104 _INST(MotionControl, 3, pathOffsetSupv, min, max, strategy) 2110 #endif // AUBO_SDK_MOTION_CONTROL_INTERFACE_H
std::shared_ptr< MotionControl > MotionControlPtr
PathBufferType
pathBuffer类型