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 {
74 int setEqradius(
double eqradius);
96 int setSpeedFraction(
double fraction);
113 double getSpeedFraction();
128 int speedFractionCritical(
bool enable);
138 bool isSpeedFractionCritical();
172 int pathOffsetLimits(
double v,
double a);
188 int pathOffsetCoordinate(
int ref_coord);
207 int pathOffsetEnable();
230 int pathOffsetSet(
const std::vector<double> &offset,
int type = 0);
249 int pathOffsetDisable();
268 int jointOffsetEnable();
291 int jointOffsetSet(
const std::vector<double> &offset,
int type = 1);
310 int jointOffsetDisable();
346 int getTrajectoryQueueSize();
381 double getDuration(
int id);
398 double getMotionLeftTime(
int id);
420 int stopMove(
bool quick,
bool all_tasks);
453 int storePath(
bool keep_sync);
496 double getProgress();
522 int setWorkObjectHold(
const std::string &module_name,
523 const std::vector<double> &mounting_pose);
542 std::tuple<std::string, std::vector<double>> getWorkObjectHold();
560 std::vector<double> getPauseJointPositions();
581 ARCS_DEPRECATED
int setServoMode(
bool enable);
598 ARCS_DEPRECATED
bool isServoModeEnabled();
606 int setServoModeSelect(
int mode);
613 int getServoModeSelect();
653 int servoJoint(
const std::vector<double> &q,
double a,
double v,
double t,
654 double lookahead_time,
double gain);
700 int servoCartesian(
const std::vector<double> &pose,
double a,
double v,
701 double t,
double lookahead_time,
double gain);
713 int servoJointWithAxes(
const std::vector<double> &q,
714 const std::vector<double> &extq,
double a,
double v,
715 double t,
double lookahead_time,
double gain);
729 int servoCartesianWithAxes(
const std::vector<double> &pose,
730 const std::vector<double> &extq,
double a,
731 double v,
double t,
double lookahead_time,
742 int trackJoint(
const std::vector<double> &q,
double t,
double smooth_scale,
756 int trackCartesian(
const std::vector<double> &pose,
double t,
757 double smooth_scale,
double delay_sacle);
773 int followJoint(
const std::vector<double> &q);
789 int followLine(
const std::vector<double> &pose);
819 int speedJoint(
const std::vector<double> &qd,
double a,
double t);
849 int resumeSpeedJoint(
const std::vector<double> &qd,
double a,
double t);
878 int speedLine(
const std::vector<double> &xd,
double a,
double t);
905 int resumeSpeedLine(
const std::vector<double> &xd,
double a,
double t);
931 int moveSpline(
const std::vector<double> &q,
double a,
double v,
973 int moveJoint(
const std::vector<double> &q,
double a,
double v,
974 double blend_radius,
double duration);
1003 int resumeMoveJoint(
const std::vector<double> &q,
double a,
double v,
1041 int moveLine(
const std::vector<double> &pose,
double a,
double v,
1042 double blend_radius,
double duration);
1060 int moveProcess(
const std::vector<double> &pose,
double a,
double v,
1061 double blend_radius);
1090 int resumeMoveLine(
const std::vector<double> &pose,
double a,
double v,
1129 int moveCircle(
const std::vector<double> &via_pose,
1130 const std::vector<double> &end_pose,
double a,
double v,
1131 double blend_radius,
double duration);
1155 int setCirclePathMode(
int mode);
1200 int pathBufferAlloc(
const std::string &name,
int type,
int size);
1221 int pathBufferAppend(
const std::string &name,
1222 const std::vector<std::vector<double>> &waypoints);
1250 int pathBufferEval(
const std::string &name,
const std::vector<double> &a,
1251 const std::vector<double> &v,
double t);
1273 bool pathBufferValid(
const std::string &name);
1292 int pathBufferFree(
const std::string &name);
1308 std::vector<std::string> pathBufferList();
1327 int movePathBuffer(
const std::string &name);
1362 int moveIntersection(
const std::vector<std::vector<double>> &poses,
1363 double a,
double v,
double main_pipe_radius,
1364 double sub_pipe_radius,
double normal_distance,
1365 double normal_alpha);
1385 int stopJoint(
double acc);
1406 int resumeStopJoint(
double acc);
1428 int stopLine(
double acc,
double acc_rot);
1451 int resumeStopLine(
double acc,
double acc_rot);
1475 int weaveStart(
const std::string ¶ms);
1503 int setFuturePointSamplePeriod(
double sample_time);
1513 std::vector<std::vector<double>> getFuturePathPointsJoint();
1529 int conveyorTrackCircle(
int encoder_id,
const std::vector<double> ¢er,
1530 int tick_per_revo,
bool rotate_tool);
1545 int conveyorTrackLine(
int encoder_id,
const std::vector<double> &direction,
1546 int tick_per_meter);
1559 int conveyorTrackStop(
double a);
1578 int moveSpiral(
const SpiralParameters ¶m,
double blend_radius,
double v,
1579 double a,
double t);
1594 int getLookAheadSize();
1611 int setLookAheadSize(
int size);
1619 #define MotionControl_DECLARES \ 1620 _FUNC(MotionControl, 0, getEqradius) \ 1621 _FUNC(MotionControl, 1, setEqradius,eqradius) \ 1622 _FUNC(MotionControl, 0, getSpeedFraction) \ 1623 _FUNC(MotionControl, 1, setSpeedFraction, fraction) \ 1624 _INST(MotionControl, 1, speedFractionCritical, enable) \ 1625 _FUNC(MotionControl, 0, isSpeedFractionCritical) \ 1626 _FUNC(MotionControl, 0, isBlending) \ 1627 _INST(MotionControl, 0, pathOffsetEnable) \ 1628 _INST(MotionControl, 2, pathOffsetSet, offset, type) \ 1629 _INST(MotionControl, 0, pathOffsetDisable) \ 1630 _INST(MotionControl, 0, jointOffsetEnable) \ 1631 _INST(MotionControl, 2, jointOffsetSet, offset, type) \ 1632 _INST(MotionControl, 0, jointOffsetDisable) \ 1633 _FUNC(MotionControl, 0, getTrajectoryQueueSize) \ 1634 _FUNC(MotionControl, 0, getQueueSize) \ 1635 _FUNC(MotionControl, 0, getExecId) \ 1636 _FUNC(MotionControl, 1, getDuration, id) \ 1637 _FUNC(MotionControl, 1, getMotionLeftTime, id) \ 1638 _FUNC(MotionControl, 0, getProgress) \ 1639 _INST(MotionControl, 2, setWorkObjectHold, module_name, mounting_pose) \ 1640 _FUNC(MotionControl, 0, getWorkObjectHold) \ 1641 _FUNC(MotionControl, 0, getPauseJointPositions) \ 1642 _FUNC(MotionControl, 1, setServoMode, enable) \ 1643 _FUNC(MotionControl, 0, isServoModeEnabled) \ 1644 _FUNC(MotionControl, 1, setServoModeSelect, mode) \ 1645 _FUNC(MotionControl, 0, getServoModeSelect) \ 1646 _FUNC(MotionControl, 6, servoJoint, q, a, v, t, lookahead_time, gain) \ 1647 _FUNC(MotionControl, 6, servoCartesian, pose, a, v, t, lookahead_time, gain)\ 1648 _INST(MotionControl, 7, servoJointWithAxes, q, extq, a, v, t, lookahead_time, gain) \ 1649 _INST(MotionControl, 7, servoCartesianWithAxes, pose, extq, a, v, t, lookahead_time, gain) \ 1650 _INST(MotionControl, 4, trackJoint, q, t, smooth_scale, delay_sacle) \ 1651 _INST(MotionControl, 4, trackCartesian, pose, t, smooth_scale, delay_sacle) \ 1652 _INST(MotionControl, 1, followJoint, q) \ 1653 _INST(MotionControl, 1, followLine, pose) \ 1654 _INST(MotionControl, 3, speedJoint, qd, a, t) \ 1655 _FUNC(MotionControl, 3, resumeSpeedJoint, qd, a, t) \ 1656 _INST(MotionControl, 3, speedLine, xd, a, t) \ 1657 _FUNC(MotionControl, 3, resumeSpeedLine, xd, a, t) \ 1658 _INST(MotionControl, 4, moveSpline, q, a, v, duration) \ 1659 _INST(MotionControl, 5, moveJoint, q, a, v, blend_radius, duration) \ 1660 _FUNC(MotionControl, 4, resumeMoveJoint, q, a, v, duration) \ 1661 _INST(MotionControl, 5, moveLine, pose, a, v, blend_radius, duration) \ 1662 _INST(MotionControl, 4, moveProcess, pose, a, v, blend_radius) \ 1663 _FUNC(MotionControl, 4, resumeMoveLine, pose, a, v, duration) \ 1664 _INST(MotionControl, 6, moveCircle, via_pose, end_pose, a, v, \ 1665 blend_radius, duration) \ 1666 _INST(MotionControl, 1, setCirclePathMode, mode) \ 1667 _INST(MotionControl, 1, moveCircle2, param) \ 1668 _FUNC(MotionControl, 3, pathBufferAlloc, name, type, size) \ 1669 _FUNC(MotionControl, 2, pathBufferAppend, name, waypoints) \ 1670 _FUNC(MotionControl, 4, pathBufferEval, name, a, v, t) \ 1671 _FUNC(MotionControl, 1, pathBufferValid, name) \ 1672 _FUNC(MotionControl, 1, pathBufferFree, name) \ 1673 _FUNC(MotionControl, 0, pathBufferList) \ 1674 _INST(MotionControl, 1, movePathBuffer, name) \ 1675 _INST(MotionControl, 7, moveIntersection, poses, a, v, main_pipe_radius, sub_pipe_radius, normal_distance, normal_alpha)\ 1676 _FUNC(MotionControl, 1, stopJoint, acc) \ 1677 _FUNC(MotionControl, 1, resumeStopJoint, acc) \ 1678 _FUNC(MotionControl, 2, stopLine, acc, acc_rot) \ 1679 _FUNC(MotionControl, 2, resumeStopLine, acc, acc_rot) \ 1680 _INST(MotionControl, 1, weaveStart, params) \ 1681 _INST(MotionControl, 0, weaveEnd) \ 1682 _FUNC(MotionControl, 1, storePath, keep_sync) \ 1683 _FUNC(MotionControl, 2, stopMove, quick, all_tasks) \ 1684 _FUNC(MotionControl, 0, startMove) \ 1685 _FUNC(MotionControl, 0, clearPath) \ 1686 _FUNC(MotionControl, 0, restoPath) \ 1687 _FUNC(MotionControl, 1, setFuturePointSamplePeriod, sample_time) \ 1688 _FUNC(MotionControl, 0, getFuturePathPointsJoint) \ 1689 _INST(MotionControl, 4, conveyorTrackCircle, encoder_id, center, tick_per_revo, rotate_tool) \ 1690 _INST(MotionControl, 3, conveyorTrackLine, encoder_id, direction, tick_per_meter) \ 1691 _INST(MotionControl, 1, conveyorTrackStop, a) \ 1692 _INST(MotionControl, 5, moveSpiral, param, blend_radius, v, a, t) \ 1693 _INST(MotionControl, 2, pathOffsetLimits, v, a) \ 1694 _INST(MotionControl, 1, pathOffsetCoordinate, ref_coord) \ 1695 _FUNC(MotionControl, 0, getLookAheadSize) \ 1696 _INST(MotionControl, 1, setLookAheadSize, size) 1702 #endif // AUBO_SDK_MOTION_CONTROL_INTERFACE_H
std::shared_ptr< MotionControl > MotionControlPtr
PathBufferType
pathBuffer类型