![]() |
AUBO SDK
0.26.0
|
#include <motion_control.h>
Public Member Functions | |
| MotionControl () | |
| virtual | ~MotionControl () |
| double | getEqradius () |
| Get the equivalent radius, in meters. | |
| int | setEqradius (double eqradius) |
| Set the equivalent radius, in meters. | |
| int | setSpeedFraction (double fraction) |
| Dynamically adjust the robot's speed and acceleration ratio (0., 1. | |
| double | getSpeedFraction () |
| Get the speed and acceleration ratio, default is 1. | |
| int | speedFractionCritical (bool enable) |
| Speed fraction critical section. | |
| bool | isSpeedFractionCritical () |
| Whether it is in the speed fraction critical section | |
| bool | isBlending () |
| Whether it is in the blending area | |
| int | pathOffsetLimits (double v, double a) |
| Set the maximum speed and maximum acceleration for offset. | |
| int | pathOffsetCoordinate (int ref_coord) |
| Set the reference coordinate system for offset. | |
| int | pathOffsetEnable () |
| Enable path offset | |
| int | pathOffsetSet (const std::vector< double > &offset, int type=0) |
| Set path offset | |
| int | pathOffsetDisable () |
| Disable path offset | |
| int | pathOffsetSupv (const std::vector< double > &min, const std::vector< double > &max, int strategy) |
| int | jointOffsetEnable () |
| Enable joint offset | |
| int | jointOffsetSet (const std::vector< double > &offset, int type=1) |
| Set joint offset | |
| int | jointOffsetDisable () |
| Disable joint offset | |
| int | getQueueSize () |
| Get the number of enqueued instruction segments (INST), including motion instructions such as moveJoint/moveLine/moveCircle and configuration instructions such as setPayload. | |
| int | getTrajectoryQueueSize () |
| Get the number of enqueued motion planning interpolation points | |
| int | getExecId () |
| Get the ID of the currently interpolating motion instruction segment. | |
| double | getDuration (int id) |
| Get the expected execution duration of the motion segment with the specified ID. | |
| double | getMotionLeftTime (int id) |
| Get the remaining execution time of the motion segment with the specified ID. | |
| int | stopMove (bool quick, bool all_tasks) |
| StopMove is used to stop robot and external axes movements and any belonging process temporarily. | |
| int | startMove () |
| StartMove is used to resume robot, external axes movement and belonging process after the movement has been stopped | |
| int | storePath (bool keep_sync) |
| storePath | |
| int | clearPath () |
| ClearPath clears the whole motion path on the current motion path level (base level or StorePath level). | |
| int | restoPath () |
| restoPath | |
| double | getProgress () |
| Get the execution progress of the current motion instruction segment. | |
| int | setWorkObjectHold (const std::string &module_name, const std::vector< double > &mounting_pose) |
| Specify the name and mounting position when the workpiece is installed on the end of another robot or external axis. | |
| std::tuple< std::string, std::vector< double > > | getWorkObjectHold () |
| 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) |
| Set resume motion parameters | |
| int | getResumeMode () |
| Get resume motion mode | |
| ARCS_DEPRECATED int | setServoMode (bool enable) |
| Set servo mode Use setServoModeSelect instead | |
| ARCS_DEPRECATED bool | isServoModeEnabled () |
| Determine whether the servo mode is enabled. | |
| int | setServoModeSelect (int mode) |
| Set servo motion mode | |
| int | getServoModeSelect () |
| Get the servo motion mode | |
| int | servoJoint (const std::vector< double > &q, double a, double v, double t, double lookahead_time, double gain) |
| Joint space servo | |
| int | servoCartesian (const std::vector< double > &pose, double a, double v, double t, double lookahead_time, double gain) |
| Cartesian space servo | |
| int | servoJointWithAxes (const std::vector< double > &q, const std::vector< double > &extq, double a, double v, double t, double lookahead_time, double gain) |
| Servo motion (with external axes), used for executing offline trajectories, pass-through user planned trajectories, etc. | |
| 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) |
| Servo motion (with external axes), used for executing offline trajectories, pass-through user planned trajectories, etc. | |
| 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) |
| Tracking motion, used for executing offline trajectories or passing through user-planned trajectories, etc. | |
| int | trackCartesian (const std::vector< double > &pose, double t, double smooth_scale, double delay_sacle) |
| Tracking motion, used for executing offline trajectories or passing through user-planned trajectories, etc. | |
| int | followJoint (const std::vector< double > &q) |
| Joint space following | |
| int | followLine (const std::vector< double > &pose) |
| Cartesian space following | |
| int | speedJoint (const std::vector< double > &qd, double a, double t) |
| Joint space velocity following | |
| int | resumeSpeedJoint (const std::vector< double > &qd, double a, double t) |
| Joint space velocity following (used to move to a safe position after a collision during process execution) | |
| int | speedLine (const std::vector< double > &xd, double a, double t) |
| Cartesian space velocity following | |
| int | resumeSpeedLine (const std::vector< double > &xd, double a, double t) |
| Cartesian space velocity following (used to move to a safe position after a collision during process execution) | |
| int | moveSpline (const std::vector< double > &q, double a, double v, double duration) |
| Perform spline interpolation in joint space | |
| int | moveJoint (const std::vector< double > &q, double a, double v, double blend_radius, double duration) |
| Add joint motion | |
| 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) |
| Synchronous motion of robot and external axes | |
| int | resumeMoveJoint (const std::vector< double > &q, double a, double v, double duration) |
| Move to the pause point using joint motion. | |
| int | moveLine (const std::vector< double > &pose, double a, double v, double blend_radius, double duration) |
| Add linear motion | |
| 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) |
| Linear motion synchronized with external axes | |
| int | moveProcess (const std::vector< double > &pose, double a, double v, double blend_radius) |
| Add process motion | |
| int | resumeMoveLine (const std::vector< double > &pose, double a, double v, double duration) |
| Move to the pause point using linear motion. | |
| int | moveCircle (const std::vector< double > &via_pose, const std::vector< double > &end_pose, double a, double v, double blend_radius, double duration) |
| Add circular arc motion | |
| 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 with external axes synchronized motion | |
| int | setCirclePathMode (int mode) |
| Set circle path mode | |
| int | moveCircle2 (const CircleParameters ¶m) |
| Advanced arc or circular motion | |
| int | pathBufferAlloc (const std::string &name, int type, int size) |
| Create a new path point buffer | |
| int | pathBufferAppend (const std::string &name, const std::vector< std::vector< double > > &waypoints) |
| Add waypoints to the path buffer | |
| int | pathBufferEval (const std::string &name, const std::vector< double > &a, const std::vector< double > &v, double t) |
| Perform computation and optimization (time-consuming operations). | |
| bool | pathBufferValid (const std::string &name) |
| Whether the buffer with the specified name is valid | |
| int | pathBufferFree (const std::string &name) |
| Release path buffer | |
| int | pathBufferFilter (const std::string &name, int order, double fd, double fs) |
| Joint space path filter | |
| std::vector< std::string > | pathBufferList () |
| List all cached path names | |
| int | movePathBuffer (const std::string &name) |
| Execute the cached path | |
| 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) |
| Intersection interface | |
| int | stopJoint (double acc) |
| Stop motion in joint space | |
| int | resumeStopJoint (double acc) |
| Stop motion in joint space (used after moving to a safe position via resumeSpeedJoint following a collision during process execution) | |
| int | stopLine (double acc, double acc_rot) |
| Stop motions in Cartesian space such as moveLine/moveCircle. | |
| int | resumeStopLine (double acc, double acc_rot) |
| Stop motion in Cartesian space (used after moving to a safe position via resumeSpeedLine following a collision during process execution) | |
| int | weaveStart (const std::string ¶ms) |
| Start weaving: between weaveStart and weaveEnd, moveLine/moveCircle/moveProcess follows params. | |
| int | weaveEnd () |
| End weaving | |
| int | setFuturePointSamplePeriod (double sample_time) |
| Set the sampling interval for points on the future path | |
| std::vector< std::vector< double > > | getFuturePathPointsJoint () |
| Get trajectory points on the future path | |
| int | setConveyorTrackEncoder (int encoder_id, int tick_per_meter) |
| Set conveyor encoder parameters | |
| int | conveyorTrackCircle (int encoder_id, const std::vector< double > ¢er, bool rotate_tool) |
| Circular conveyor tracking | |
| int | conveyorTrackLine (int encoder_id, const std::vector< double > &direction) |
| Linear conveyor tracking | |
| int | conveyorTrackStop (int encoder_id, double a) |
| Stop conveyor tracking | |
| bool | conveyorTrackSwitch (int encoder_id) |
| Switch conveyor tracking item. | |
| bool | hasItemOnConveyorToTrack (int encoder_id) |
| Whether there is an item on the conveyor that can be tracked | |
| int | conveyorTrackCreatItem (int encoder_id, int item_id, const std::vector< double > &offset) |
| Add an item to the conveyor queue | |
| int | setConveyorTrackCompensate (int encoder_id, double comp) |
| Set the compensation value for conveyor tracking | |
| bool | isConveyorTrackSync (int encoder_id) |
| Determine whether the conveyor and the robot arm have reached relative rest | |
| int | setConveyorTrackLimit (int encoder_id, double limit) |
| Set the maximum distance limit for conveyor tracking | |
| int | setConveyorTrackStartWindow (int encoder_id, double window_min, double window_max) |
| Set the start window for conveyor tracking | |
| int | setConveyorTrackSensorOffset (int encoder_id, double offset) |
| Set the distance from the conveyor teaching position to the sync switch | |
| int | setConveyorTrackSyncSeparation (int encoder_id, double distance, double time) |
| Set conveyor sync separation, used to filter out unwanted signals from the sync switch. | |
| bool | isConveyorTrackExceed (int encoder_id) |
| Whether the workpiece on the conveyor has moved beyond the maximum limit | |
| int | conveyorTrackClearItems (int encoder_id) |
| Clear all items in the conveyor queue | |
| std::vector< int > | getConveyorTrackQueue (int encoder_id) |
| Get encoder values of the conveyor queue | |
| int | getConveyorTrackNextItem (int encoder_id) |
| Get the ID of the next item on the conveyor to be tracked | |
| int | moveSpiral (const SpiralParameters ¶m, double blend_radius, double v, double a, double t) |
| Spiral motion | |
| int | getLookAheadSize () |
| Get look-ahead segment size | |
| int | setLookAheadSize (int size) |
| Set look-ahead segment size | |
| int | weaveUpdateParameters (const std::string ¶ms) |
| Update frequency and amplitude during weaving process | |
| int | enableJointSoftServo (const std::vector< double > &stiffness) |
| Set joint current loop stiffness coefficient | |
| int | disableJointSoftServo () |
| Disable joint current loop stiffness coefficient | |
| bool | isJointSoftServoEnabled () |
| Determine whether the joint current loop stiffness coefficient is enabled. | |
| int | enableVibrationSuppress (const std::vector< double > &omega, const std::vector< double > &zeta, int level) |
| int | disbaleVibrationSuppress () |
| int | setTimeOptimalEnable (bool enable) |
| bool | isTimeOptimalEnabled () |
| Get the time optimal algorithm state: true - enable false - disable | |
| bool | isSupportedTimeOptimal () |
| Check whether the time optimal algorithm is supported true - supported false - not supported | |
Protected Attributes | |
| void * | d_ |
Definition at line 67 of file motion_control.h.
| arcs::common_interface::MotionControl::MotionControl | ( | ) |
|
virtual |
| int arcs::common_interface::MotionControl::clearPath | ( | ) |
ClearPath clears the whole motion path on the current motion path level (base level or StorePath level).
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::conveyorTrackCircle | ( | int | encoder_id, |
| const std::vector< double > & | center, | ||
| bool | rotate_tool | ||
| ) |
Circular conveyor tracking
| encoder_id | 0 - integrated sensor |
| rotate_tool |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::conveyorTrackClearItems | ( | int | encoder_id | ) |
Clear all items in the conveyor queue
| encoder_id | Reserved |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::conveyorTrackCreatItem | ( | int | encoder_id, |
| int | item_id, | ||
| const std::vector< double > & | offset | ||
| ) |
Add an item to the conveyor queue
| encoder_id | Reserved |
| item_id | Item ID |
| offset | Offset of the current item position relative to the template item position |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::conveyorTrackLine | ( | int | encoder_id, |
| const std::vector< double > & | direction | ||
| ) |
Linear conveyor tracking
| encoder_id | Reserved |
| direction | The movement direction of the conveyor relative to the robot base coordinate system |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::conveyorTrackStop | ( | int | encoder_id, |
| double | a | ||
| ) |
Stop conveyor tracking
| encoder_id | Reserved |
| a | Reserved |
| arcs::common_interface::AuboException |
| bool arcs::common_interface::MotionControl::conveyorTrackSwitch | ( | int | encoder_id | ) |
Switch conveyor tracking item.
If the current item is being tracked, it will be dequeued and no longer tracked, returning true. If no item is currently being tracked, returns false.
| arcs::common_interface::AuboException |
| encoder_id | Reserved |
| int arcs::common_interface::MotionControl::disableJointSoftServo | ( | ) |
Disable joint current loop stiffness coefficient
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::disbaleVibrationSuppress | ( | ) |
| int arcs::common_interface::MotionControl::enableJointSoftServo | ( | const std::vector< double > & | stiffness | ) |
Set joint current loop stiffness coefficient
| stiffness | Stiffness coefficient for each joint, as a percentage [0 -> 1]. The larger the value, the stiffer the joint. |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::enableVibrationSuppress | ( | const std::vector< double > & | omega, |
| const std::vector< double > & | zeta, | ||
| int | level | ||
| ) |
| int arcs::common_interface::MotionControl::followJoint | ( | const std::vector< double > & | q | ) |
Joint space following
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::followLine | ( | const std::vector< double > & | pose | ) |
Cartesian space following
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::getConveyorTrackNextItem | ( | int | encoder_id | ) |
Get the ID of the next item on the conveyor to be tracked
| encoder_id | Reserved |
| arcs::common_interface::AuboException |
| std::vector< int > arcs::common_interface::MotionControl::getConveyorTrackQueue | ( | int | encoder_id | ) |
Get encoder values of the conveyor queue
| encoder_id | Reserved |
| arcs::common_interface::AuboException |
| double arcs::common_interface::MotionControl::getDuration | ( | int | id | ) |
Get the expected execution duration of the motion segment with the specified ID.
| id | Motion segment ID |
| arcs::common_interface::AuboException |
| double arcs::common_interface::MotionControl::getEqradius | ( | ) |
Get the equivalent radius, in meters.
When using moveLine/moveCircle, the rotation angle of the end effector's pose is converted to an equivalent end position movement. Can be set via setEqradius, default is 1.
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::getExecId | ( | ) |
Get the ID of the currently interpolating motion instruction segment.
| -1 | Indicates the trajectory queue is empty. Both the buffer in movePathBuffer motion and the queue in the planner (such as moveJoint and moveLine) belong to the trajectory queue. |
| arcs::common_interface::AuboException |
| std::vector< std::vector< double > > arcs::common_interface::MotionControl::getFuturePathPointsJoint | ( | ) |
Get trajectory points on the future path
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::getLookAheadSize | ( | ) |
Get look-ahead segment size
| arcs::common_interface::AuboException |
| double arcs::common_interface::MotionControl::getMotionLeftTime | ( | int | id | ) |
Get the remaining execution time of the motion segment with the specified ID.
| id | Motion segment ID |
| arcs::common_interface::AuboException |
| std::vector< double > arcs::common_interface::MotionControl::getPauseJointPositions | ( | ) |
Commonly used during process recovery after a collision occurs (first move to the pause position using resumeMoveJoint or resumeMoveLine, then resume the process).
| arcs::common_interface::AuboException |
| double arcs::common_interface::MotionControl::getProgress | ( | ) |
Get the execution progress of the current motion instruction segment.
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::getQueueSize | ( | ) |
Get the number of enqueued instruction segments (INST), including motion instructions such as moveJoint/moveLine/moveCircle and configuration instructions such as setPayload.
Instructions are generally indicated with _INST in macro definitions, for example: _INST(MotionControl, 5, moveJoint, q, a, v, blend_radius, duration)
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::getResumeMode | ( | ) |
Get resume motion mode
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::getServoModeSelect | ( | ) |
Get the servo motion mode
| double arcs::common_interface::MotionControl::getSpeedFraction | ( | ) |
Get the speed and acceleration ratio, default is 1.
Can be set via setSpeedFraction interface.
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::getTrajectoryQueueSize | ( | ) |
Get the number of enqueued motion planning interpolation points
| arcs::common_interface::AuboException |
| std::tuple< std::string, std::vector< double > > arcs::common_interface::MotionControl::getWorkObjectHold | ( | ) |
getWorkObjectHold
| arcs::common_interface::AuboException |
| bool arcs::common_interface::MotionControl::hasItemOnConveyorToTrack | ( | int | encoder_id | ) |
Whether there is an item on the conveyor that can be tracked
| encoder_id | Reserved |
| arcs::common_interface::AuboException |
| bool arcs::common_interface::MotionControl::isBlending | ( | ) |
Whether it is in the blending area
| arcs::common_interface::AuboException |
| bool arcs::common_interface::MotionControl::isConveyorTrackExceed | ( | int | encoder_id | ) |
Whether the workpiece on the conveyor has moved beyond the maximum limit
| encoder_id | Reserved |
| arcs::common_interface::AuboException |
| bool arcs::common_interface::MotionControl::isConveyorTrackSync | ( | int | encoder_id | ) |
Determine whether the conveyor and the robot arm have reached relative rest
| encoder_id | Reserved |
| arcs::common_interface::AuboException |
| bool arcs::common_interface::MotionControl::isJointSoftServoEnabled | ( | ) |
Determine whether the joint current loop stiffness coefficient is enabled.
| arcs::common_interface::AuboException |
| ARCS_DEPRECATED bool arcs::common_interface::MotionControl::isServoModeEnabled | ( | ) |
Determine whether the servo mode is enabled.
Use getServoModeSelect instead.
| arcs::common_interface::AuboException |
| bool arcs::common_interface::MotionControl::isSpeedFractionCritical | ( | ) |
Whether it is in the speed fraction critical section
| arcs::common_interface::AuboException |
| bool arcs::common_interface::MotionControl::isSupportedTimeOptimal | ( | ) |
Check whether the time optimal algorithm is supported true - supported false - not supported
| arcs::common_interface::AuboException |
| bool arcs::common_interface::MotionControl::isTimeOptimalEnabled | ( | ) |
Get the time optimal algorithm state: true - enable false - disable
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::jointOffsetDisable | ( | ) |
Disable joint offset
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::jointOffsetEnable | ( | ) |
Enable joint offset
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::jointOffsetSet | ( | const std::vector< double > & | offset, |
| int | type = 1 |
||
| ) |
Set joint offset
| offset | Pose offset for each joint |
| type |
| arcs::common_interface::AuboException |
| 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 | ||
| ) |
Add circular arc motion
| via_pose | The pose of the via point during the arc motion |
| end_pose | The pose of the end point of the arc motion |
| a | Acceleration (if the position change between via_pose and the previous waypoint is less than 1mm and the posture change is greater than 1e-4 rad, this acceleration is treated as angular acceleration in rad/s^2; otherwise, as linear acceleration in m/s^2) |
| v | Velocity (if the position change between via_pose and the previous waypoint is less than 1mm and the posture change is greater than 1e-4 rad, this velocity is treated as angular velocity in rad/s; otherwise, as linear velocity in m/s) |
| blend_radius | Blend radius, unit: m |
| duration | Execution time, unit: s Normally, when speed and acceleration are given, the trajectory duration can be determined. If you want to extend the trajectory duration, set the duration parameter. Duration can extend the trajectory time, but cannot shorten it. When duration = 0, it means the execution time is not specified, and the time will be calculated based on speed and acceleration. If duration is not 0, a and v values will be ignored. |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::moveCircle2 | ( | const CircleParameters & | param | ) |
Advanced arc or circular motion
| param | Circular motion parameters |
| arcs::common_interface::AuboException |
| 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 with external axes synchronized motion
| group_name | Name of the external axis group |
| via_pose | The pose of the via point during the arc motion |
| end_pose | The pose of the end point of the arc motion |
| a | Acceleration |
| v | Velocity |
| blend_radius | Blend radius |
| duration | Execution time |
| 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 | ||
| ) |
Intersection interface
| poses | Consists of three taught poses (first, move to the starting point. The starting point requirement: the intersection of the plane passing through the main cylinder axis and parallel to the sub-cylinder axis with the sub-cylinder at the bottom) p1: Intersection of the plane passing through the sub-cylinder axis and parallel to the main cylinder axis with the sub-cylinder at the left top p2: Intersection of the plane passing through the sub-cylinder axis and parallel to the main cylinder axis with the main cylinder at the left bottom p3: Intersection of the plane passing through the sub-cylinder axis and parallel to the main cylinder axis with the main cylinder at the right bottom |
| v | Velocity |
| a | Acceleration |
| main_pipe_radius | Main cylinder radius |
| sub_pipe_radius | Sub cylinder radius |
| normal_distance | Distance between the two cylinder axes |
| normal_alpha | Angle between the two cylinder axes |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::moveJoint | ( | const std::vector< double > & | q, |
| double | a, | ||
| double | v, | ||
| double | blend_radius, | ||
| double | duration | ||
| ) |
Add joint motion
| q | Joint angles, unit: rad |
| a | Acceleration, unit: rad/s^2, The maximum value can be obtained via RobotConfig::getJointMaxAccelerations() |
| v | Velocity, unit: rad/s, The maximum value can be obtained via RobotConfig::getJointMaxSpeeds() |
| blend_radius | Blend radius, unit: m |
| duration | Execution time, unit: s Normally, when speed and acceleration are given, the trajectory duration can be determined. If you want to extend the trajectory duration, set the duration parameter. Duration can extend the trajectory time, but cannot shorten it. When duration = 0, it means the execution time is not specified, and the time will be calculated based on speed and acceleration. If duration is not 0, a and v values will be ignored. |
| 0 | Success |
| AUBO_BAD_STATE(1) | The current safety mode is not Normal, ReducedMode, or Recovery |
| AUBO_QUEUE_FULL(2) | Planning queue is full |
| AUBO_BUSY(3) | The previous instruction is being executed |
| -AUBO_BAD_STATE(-1) | Possible reasons include but are not limited to: thread has been detached, thread terminated, task_id not found, or the current robot mode is not Running |
| -AUBO_TIMEOUT(-4) | Interface call timeout |
| -AUBO_INVL_ARGUMENT(-5) | The length of q is less than the degrees of freedom of the current robot arm |
| AUBO_REQUEST_IGNORE(13) | The length of q is too short and there is no need to stop at that point |
| arcs::common_interface::AuboException |
| 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 | ||
| ) |
Synchronous motion of robot and external axes
| group_name | |
| q | |
| a | |
| v | |
| blend_radius | |
| duration |
| int arcs::common_interface::MotionControl::moveLine | ( | const std::vector< double > & | pose, |
| double | a, | ||
| double | v, | ||
| double | blend_radius, | ||
| double | duration | ||
| ) |
Add linear motion
| pose | Target pose |
| a | Acceleration (if the position change is less than 1mm and the posture change is greater than 1e-4 rad, this acceleration is treated as angular acceleration in rad/s^2; otherwise, as linear acceleration in m/s^2). The maximum value can be obtained via RobotConfig::getTcpMaxAccelerations(). |
| v | Velocity (if the position change is less than 1mm and the posture change is greater than 1e-4 rad, this velocity is treated as angular velocity in rad/s; otherwise, as linear velocity in m/s). The maximum value can be obtained via RobotConfig::getTcpMaxSpeeds(). |
| blend_radius | Blend radius, unit: m, value between 0.001 and 1 |
| duration | Execution time, unit: s Normally, when speed and acceleration are given, the trajectory duration can be determined. If you want to extend the trajectory duration, set the duration parameter. Duration can extend the trajectory time, but cannot shorten it. When duration = 0, it means the execution time is not specified, and the time will be calculated based on speed and acceleration. If duration is not 0, a and v values will be ignored. |
| 0 | Success |
| AUBO_BAD_STATE(1) | The current safety mode is not Normal, ReducedMode, or Recovery |
| AUBO_QUEUE_FULL(2) | Trajectory queue is full |
| AUBO_BUSY(3) | The previous instruction is being executed |
| -AUBO_BAD_STATE(-1) | Possible reasons include but are not limited to: thread has been detached, thread terminated, task_id not found, or the current robot mode is not Running |
| -AUBO_TIMEOUT(-4) | Interface call timeout |
| -AUBO_INVL_ARGUMENT(-5) | The length of the pose array is less than the degrees of freedom of the current robot arm |
| AUBO_REQUEST_IGNORE(13) | The length of the pose array is too short and there is no need to stop at that point |
| arcs::common_interface::AuboException |
| 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 | ||
| ) |
Linear motion synchronized with external axes
| group_name | Name of the external axis group |
| pose | Target pose |
| a | Acceleration |
| v | Velocity |
| blend_radius | Blend radius |
| duration | Execution time |
| int arcs::common_interface::MotionControl::movePathBuffer | ( | const std::string & | name | ) |
Execute the cached path
| name | Name of the cached path |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::moveProcess | ( | const std::vector< double > & | pose, |
| double | a, | ||
| double | v, | ||
| double | blend_radius | ||
| ) |
Add process motion
| pose | |
| a | |
| v | |
| blend_radius |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::moveSpiral | ( | const SpiralParameters & | param, |
| double | blend_radius, | ||
| double | v, | ||
| double | a, | ||
| double | t | ||
| ) |
Spiral motion
| param | Encapsulated parameters |
| blend_radius | |
| v | |
| a | |
| t |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::moveSpline | ( | const std::vector< double > & | q, |
| double | a, | ||
| double | v, | ||
| double | duration | ||
| ) |
Perform spline interpolation in joint space
| q | Joint angles. If the input vector is of size 0, it indicates the end of the spline motion. |
| a | Acceleration, unit: rad/s^2. The maximum value can be obtained via RobotConfig::getJointMaxAccelerations(). |
| v | Velocity, unit: rad/s. The maximum value can be obtained via RobotConfig::getJointMaxSpeeds(). |
| duration |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathBufferAlloc | ( | const std::string & | name, |
| int | type, | ||
| int | size | ||
| ) |
Create a new path point buffer
| name | Name of the path |
| type | Type of the path 1: toppra time-optimal path planning 2: cubic_spline (recorded trajectory) 3: Joint B-spline interpolation, at least three points |
| size | Buffer size |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathBufferAppend | ( | const std::string & | name, |
| const std::vector< std::vector< double > > & | waypoints | ||
| ) |
Add waypoints to the path buffer
| name | Name of the path buffer |
| waypoints | Waypoints |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathBufferEval | ( | const std::string & | name, |
| const std::vector< double > & | a, | ||
| const std::vector< double > & | v, | ||
| double | t | ||
| ) |
Perform computation and optimization (time-consuming operations).
If the input parameters are the same, the calculation will not be repeated.
| name | Name of the path point buffer created by pathBufferAlloc |
| a | Joint acceleration limits, must match the robot DOF, unit: rad/s^2 |
| v | Joint velocity limits, must match the robot DOF, unit: rad/s |
| t | Time When allocating memory with pathBufferAlloc, the type must be specified. According to the type in pathBufferAlloc: Type 1: t means motion duration Type 2: t means sampling interval Type 3: t means motion duration If t=0, the internal default time is used (recommended) If t!=0, t should be set to number_of_points * interval_between_points (interval >= 0.01) |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathBufferFilter | ( | const std::string & | name, |
| int | order, | ||
| double | fd, | ||
| double | fs | ||
| ) |
Joint space path filter
pathBufferFilter
| name | Name of the path buffer |
| order | Filter order (usually 2) |
| fd | Cutoff frequency, the smaller the smoother but with more delay (usually 3-20) |
| fs | Sampling frequency of discrete data (usually 20-500) |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathBufferFree | ( | const std::string & | name | ) |
Release path buffer
| name | Name of the path buffer |
| arcs::common_interface::AuboException |
| std::vector< std::string > arcs::common_interface::MotionControl::pathBufferList | ( | ) |
List all cached path names
| arcs::common_interface::AuboException |
| bool arcs::common_interface::MotionControl::pathBufferValid | ( | const std::string & | name | ) |
Whether the buffer with the specified name is valid
The buffer must meet three conditions to be valid:
| name | Name of the buffer |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathOffsetCoordinate | ( | int | ref_coord | ) |
Set the reference coordinate system for offset.
Only valid when type=1 in pathOffsetSet.
| ref_coord | Reference coordinate system: 0-base coordinate, 1-TCP |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathOffsetDisable | ( | ) |
Disable path offset
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathOffsetEnable | ( | ) |
Enable path offset
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathOffsetLimits | ( | double | v, |
| double | a | ||
| ) |
Set the maximum speed and maximum acceleration for offset.
Only valid when type=1 in pathOffsetSet.
| v | Maximum speed |
| a | Maximum acceleration |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathOffsetSet | ( | const std::vector< double > & | offset, |
| int | type = 0 |
||
| ) |
Set path offset
| offset | Pose offset in each direction |
| type | Motion type 0-position planning 1-velocity planning |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::pathOffsetSupv | ( | const std::vector< double > & | min, |
| const std::vector< double > & | max, | ||
| int | strategy | ||
| ) |
Monitor trajectory offset range
| min | Maximum offset in the negative direction of the coordinate axis |
| max | Maximum offset in the positive direction of the coordinate axis |
| strategy | Monitoring strategy after reaching the maximum offset 0 - Disable monitoring 1 - Saturation limit, i.e., maintain maximum pose 2 - Protective stop |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::restoPath | ( | ) |
restoPath
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::resumeMoveJoint | ( | const std::vector< double > & | q, |
| double | a, | ||
| double | v, | ||
| double | duration | ||
| ) |
Move to the pause point using joint motion.
| q | Joint angles, unit: rad |
| a | Acceleration, unit: rad/s^2 |
| v | Velocity, unit: rad/s |
| duration | Execution time, unit: s Normally, when speed and acceleration are given, the trajectory duration can be determined. If you want to extend the trajectory duration, set the duration parameter. Duration can extend the trajectory time, but cannot shorten it. When duration = 0, it means the execution time is not specified, and the time will be calculated based on speed and acceleration. If duration is not 0, a and v values will be ignored. |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::resumeMoveLine | ( | const std::vector< double > & | pose, |
| double | a, | ||
| double | v, | ||
| double | duration | ||
| ) |
Move to the pause point using linear motion.
| pose | Target pose |
| a | Acceleration, unit: m/s^2 |
| v | Velocity, unit: m/s |
| duration | Execution time, unit: s Normally, when speed and acceleration are given, the trajectory duration can be determined. If you want to extend the trajectory duration, set the duration parameter. Duration can extend the trajectory time, but cannot shorten it. When duration = 0, it means the execution time is not specified, and the time will be calculated based on speed and acceleration. If duration is not 0, a and v values will be ignored. |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::resumeSpeedJoint | ( | const std::vector< double > & | qd, |
| double | a, | ||
| double | t | ||
| ) |
Joint space velocity following (used to move to a safe position after a collision during process execution)
When the robot arm has not yet reached the target velocity, giving a new target velocity will cause the robot arm to immediately reach the new target velocity.
| qd | Target joint velocity, unit: rad/s |
| a | Main axis acceleration, unit: rad/s^2 |
| t | Time required for the function to return, unit: s If t = 0, the function returns when the target velocity is reached; otherwise, the function returns after t seconds, regardless of whether the target velocity is reached. If the target velocity is not reached, it will decelerate to zero. If the target velocity is reached, it will move at a constant speed. |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::resumeSpeedLine | ( | const std::vector< double > & | xd, |
| double | a, | ||
| double | t | ||
| ) |
Cartesian space velocity following (used to move to a safe position after a collision during process execution)
When the robot arm has not yet reached the target velocity, giving a new target velocity will cause the robot arm to immediately reach the new target velocity.
| xd | Tool velocity, unit: m/s |
| a | Tool position acceleration, unit: m/s^2 |
| t | Time required for the function to return, unit: s If t = 0, the function returns when the target velocity is reached; otherwise, the function returns after t seconds, regardless of whether the target velocity is reached. If the target velocity is not reached, it will decelerate to zero. If the target velocity is reached, it will move at a constant speed. |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::resumeStopJoint | ( | double | acc | ) |
Stop motion in joint space (used after moving to a safe position via resumeSpeedJoint following a collision during process execution)
| acc | Joint acceleration, unit: rad/s^2 |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::resumeStopLine | ( | double | acc, |
| double | acc_rot | ||
| ) |
Stop motion in Cartesian space (used after moving to a safe position via resumeSpeedLine following a collision during process execution)
| acc | Position acceleration, unit: m/s^2 |
| acc_rot | Orientation acceleration, unit: rad/s^2 |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::servoCartesian | ( | const std::vector< double > & | pose, |
| double | a, | ||
| double | v, | ||
| double | t, | ||
| double | lookahead_time, | ||
| double | gain | ||
| ) |
Cartesian space servo
Currently, only pose and t parameters are available;
| pose | Pose, unit: m |
| a | Acceleration, unit: m/s^2 |
| v | Velocity, unit: m/s |
| t | Execution time, unit: s The larger the t value, the slower the robot moves, and vice versa; The optimal value for this parameter is the interval time for continuous calls to the servoCartesian interface. |
| lookahead_time | Lookahead time, unit: s Specifies the duration to move before the robot starts to decelerate, used to smooth the trajectory [0.03, 0.2]. When lookahead_time is less than one control cycle, the smaller it is, the greater the overshoot. The optimal value for this parameter is one control cycle. |
| gain | Proportional gain Proportional gain for tracking the target position [100, 200], used to control the smoothness and accuracy of the motion, The larger the proportional gain, the longer it takes to reach the target position, and the smaller the overshoot. |
| 0 | Success |
| AUBO_BAD_STATE(1) | The current safety mode is not Normal, ReducedMode, or Recovery |
| AUBO_QUEUE_FULL(2) | Planning queue is full |
| AUBO_BUSY(3) | The previous instruction is being executed |
| -AUBO_BAD_STATE(-1) | Possible reasons include but are not limited to: thread has been detached, thread terminated, task_id not found, or the current robot mode is not Running |
| -AUBO_TIMEOUT(-4) | Interface call timeout |
| -AUBO_INVL_ARGUMENT(-5) | Trajectory position or velocity out of range |
| -AUBO_REQUEST_IGNORE(-13) | Not in servo mode |
| -AUBO_IK_NO_CONVERGE(-23) | Inverse kinematics calculation does not converge, calculation error; |
| -AUBO_IK_OUT_OF_RANGE(-24) | Inverse kinematics calculation exceeds robot maximum limits; |
| AUBO_IK_CONFIG_DISMATCH(-25) | Inverse kinematics input configuration error; |
| -AUBO_IK_JACOBIAN_FAILED(-26) | Inverse kinematics Jacobian calculation failed; |
| -AUBO_IK_NO_SOLU(-27) | Analytical solution exists for the target point, but none meet the selection criteria; |
| -AUBO_IK_UNKOWN_ERROR(-28) | Inverse kinematics returned an unknown error type; |
| arcs::common_interface::AuboException |
| 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 | ||
| ) |
Servo motion (with external axes), used for executing offline trajectories, pass-through user planned trajectories, etc.
The difference from servoJointWithAxes is that it receives Cartesian poses instead of joint angles (inverse kinematics is performed internally by the software).
| pose | |
| extq | |
| t | |
| smooth_scale | |
| delay_sacle |
| 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 | ||
| ) |
| int arcs::common_interface::MotionControl::servoJoint | ( | const std::vector< double > & | q, |
| double | a, | ||
| double | v, | ||
| double | t, | ||
| double | lookahead_time, | ||
| double | gain | ||
| ) |
Joint space servo
Currently only q and t parameters are available;
| q | Joint angles, unit: rad |
| a | Acceleration, unit: rad/s^2 |
| v | Velocity, unit: rad/s |
| t | Execution time, unit: s The larger the t value, the slower the robot moves, and vice versa; The optimal value for this parameter is the interval time for continuous calls to the servoJoint interface. |
| lookahead_time | Lookahead time, unit: s Specifies the duration to move before the robot starts to decelerate, used to smooth the trajectory [0.03, 0.2]. When lookahead_time is less than one control cycle, the smaller it is, the greater the overshoot. The optimal value for this parameter is one control cycle. |
| gain | Proportional gain Proportional gain for tracking the target position [100, 200], used to control the smoothness and accuracy of the motion. The larger the proportional gain, the longer it takes to reach the target position, and the smaller the overshoot. |
| 0 | Success |
| AUBO_BAD_STATE(1) | The current safety mode is not Normal, ReducedMode, or Recovery |
| AUBO_QUEUE_FULL(2) | Planning queue is full |
| AUBO_BUSY(3) | The previous instruction is being executed |
| -AUBO_BAD_STATE(-1) | Possible reasons include but are not limited to: thread has been detached, thread terminated, task_id not found, or the current robot mode is not Running |
| -AUBO_TIMEOUT(-4) | Interface call timeout |
| -AUBO_INVL_ARGUMENT(-5) | Trajectory position or velocity out of range |
| -AUBO_REQUEST_IGNORE(-13) | Not in servo mode |
| arcs::common_interface::AuboException |
| 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 | ||
| ) |
Servo motion (with external axes), used for executing offline trajectories, pass-through user planned trajectories, etc.
| q | |
| extq | |
| t | |
| smooth_scale | |
| delay_sacle |
| 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 | ||
| ) |
| int arcs::common_interface::MotionControl::setCirclePathMode | ( | int | mode | ) |
Set circle path mode
| mode | Mode 0: Tool orientation remains unchanged relative to the arc path point coordinate system 1: Orientation changes linearly, rotating around a fixed axis in space, from the start orientation to the target orientation 2: Orientation changes from the start orientation, through the via point orientation, to the target orientation |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setConveyorTrackCompensate | ( | int | encoder_id, |
| double | comp | ||
| ) |
Set the compensation value for conveyor tracking
| encoder_id | Reserved |
| comp | Conveyor compensation value |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setConveyorTrackEncoder | ( | int | encoder_id, |
| int | tick_per_meter | ||
| ) |
Set conveyor encoder parameters
| encoder_id | Reserved |
| tick_per_meter | Linear conveyor: pulses per meter Circular conveyor: pulses per revolution |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setConveyorTrackLimit | ( | int | encoder_id, |
| double | limit | ||
| ) |
Set the maximum distance limit for conveyor tracking
| encoder_id | Reserved |
| limit | Maximum distance limit for conveyor tracking, unit: meter |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setConveyorTrackSensorOffset | ( | int | encoder_id, |
| double | offset | ||
| ) |
Set the distance from the conveyor teaching position to the sync switch
| encoder_id | Reserved |
| offset | Distance from the conveyor teaching position to the sync switch, unit: meter |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setConveyorTrackStartWindow | ( | int | encoder_id, |
| double | window_min, | ||
| double | window_max | ||
| ) |
Set the start window for conveyor tracking
| encoder_id | Reserved |
| min_window | Start position of the window, unit: meter |
| max_window | End position of the window, unit: meter |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setConveyorTrackSyncSeparation | ( | int | encoder_id, |
| double | distance, | ||
| double | time | ||
| ) |
Set conveyor sync separation, used to filter out unwanted signals from the sync switch.
| encoder_id | Reserved |
| distance | The minimum distance to travel after a sync signal appears before accepting a new sync signal as a valid object, unit: meter |
| time | The minimum time to elapse after a sync signal appears before accepting a new sync signal as a valid object, unit: second |
If distance and time are both set greater than 0, the setting takes effect. If both distance and time are set, distance takes precedence.
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setEqradius | ( | double | eqradius | ) |
Set the equivalent radius, in meters.
When using moveLine/moveCircle, the rotation angle of the end effector's pose is converted to an equivalent end position movement. The larger the value, the faster the posture rotation speed.
| eqradius | 0 means only plan the movement, and the posture rotation follows the movement. |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setFuturePointSamplePeriod | ( | double | sample_time | ) |
Set the sampling interval for points on the future path
| sample_time | Sampling interval, unit: m/s^2 |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setLookAheadSize | ( | int | size | ) |
Set look-ahead segment size
| arcs::common_interface::AuboException |
| 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 | ||
| ) |
Set resume motion parameters
| q | Resume start position |
| move_type | 0: Joint space, 1: Cartesian space |
| blend_radius | Blend radius |
| qdmax | Maximum joint speed (6 elements) |
| qddmax | Maximum joint acceleration (6 elements) |
| vmax | Maximum linear and angular speed for linear motion (2 elements) |
| amax | Maximum linear and angular acceleration for linear motion (2 elements) |
| arcs::common_interface::AuboException |
| ARCS_DEPRECATED int arcs::common_interface::MotionControl::setServoMode | ( | bool | enable | ) |
Set servo mode Use setServoModeSelect instead
| enable | Whether to enable |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setServoModeSelect | ( | int | mode | ) |
Set servo motion mode
| mode | 0 - Exit servo mode 1 - Planning servo mode 2 - Transparent mode (direct send) 3 - Transparent mode (buffered) |
| int arcs::common_interface::MotionControl::setSpeedFraction | ( | double | fraction | ) |
Dynamically adjust the robot's speed and acceleration ratio (0., 1.
]
| fraction | The ratio of robot speed and acceleration |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setTimeOptimalEnable | ( | bool | enable | ) |
| enable |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::setWorkObjectHold | ( | const std::string & | module_name, |
| const std::vector< double > & | mounting_pose | ||
| ) |
Specify the name and mounting position when the workpiece is installed on the end of another robot or external axis.
| module_name | Name of the control module |
| mounting_pose | Relative position of the grasp, if it is a robot, it is relative to the robot's end center point (not the TCP point) |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::speedFractionCritical | ( | bool | enable | ) |
Speed fraction critical section.
When enabled, the speed fraction is forced to 1. When disabled, the previous speed fraction is restored.
| enable |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::speedJoint | ( | const std::vector< double > & | qd, |
| double | a, | ||
| double | t | ||
| ) |
Joint space velocity following
When the robot arm has not yet reached the target velocity, giving a new target velocity will cause the robot arm to immediately reach the new target velocity.
| qd | Target joint velocity, unit: rad/s |
| a | Main axis acceleration, unit: rad/s^2 |
| t | Time required for the function to return, unit: s If t = 0, the function returns when the target velocity is reached; otherwise, the function returns after t seconds, regardless of whether the target velocity is reached. If the target velocity is not reached, it will decelerate to zero. If the target velocity is reached, it will move at a constant speed. |
| 0 | Success |
| AUBO_BAD_STATE(1) | The current safety mode is not Normal, ReducedMode, or Recovery |
| AUBO_BUSY(3) | The previous instruction is being executed |
| -AUBO_BAD_STATE(-1) | Possible reasons include but are not limited to: thread has been detached, thread terminated, task_id not found, or the current robot mode is not Running |
| -AUBO_TIMEOUT(-4) | Interface call timeout |
| -AUBO_INVL_ARGUMENT(-5) | The length of the qd array is less than the degrees of freedom of the current robot arm |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::speedLine | ( | const std::vector< double > & | xd, |
| double | a, | ||
| double | t | ||
| ) |
Cartesian space velocity following
When the robot arm has not yet reached the target velocity, giving a new target velocity will cause the robot arm to immediately reach the new target velocity.
| xd | Tool velocity, unit: m/s |
| a | Tool position acceleration, unit: m/s^2 |
| t | Time required for the function to return, unit: s If t = 0, the function returns when the target velocity is reached; otherwise, the function returns after t seconds, regardless of whether the target velocity is reached. If the target velocity is not reached, it will decelerate to zero. If the target velocity is reached, it will move at a constant speed. |
| 0 | Success |
| AUBO_BAD_STATE(1) | The current safety mode is not Normal, ReducedMode, or Recovery |
| AUBO_BUSY(3) | The previous instruction is being executed |
| -AUBO_BAD_STATE(-1) | Possible reasons include but are not limited to: thread has been detached, thread terminated, task_id not found, or the current robot mode is not Running |
| -AUBO_TIMEOUT(-4) | Interface call timeout |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::startMove | ( | ) |
StartMove is used to resume robot, external axes movement and belonging process after the movement has been stopped
• by the instruction StopMove. • after execution of StorePath ... RestoPath sequence. • after asynchronously raised movements errors, such as ERR_PATH_STOP or specific process error after handling in the ERROR handler.
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::stopJoint | ( | double | acc | ) |
Stop motion in joint space
| acc | Joint acceleration, unit: rad/s^2 |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::stopLine | ( | double | acc, |
| double | acc_rot | ||
| ) |
Stop motions in Cartesian space such as moveLine/moveCircle.
| acc | Tool acceleration, unit: m/s^2 |
| acc_rot |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::stopMove | ( | bool | quick, |
| bool | all_tasks | ||
| ) |
StopMove is used to stop robot and external axes movements and any belonging process temporarily.
If the instruction StartMove is given then the movement and process resumes.
This instruction can, for example, be used in a trap routine to stop the robot temporarily when an interrupt occurs.
| quick | true: Stops the robot on the path as fast as possible. Without the optional parameter \Quick, the robot stops on the path, but the braking distance is longer (same as for normal Program Stop). |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::storePath | ( | bool | keep_sync | ) |
storePath
| keep_sync |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::trackCartesian | ( | const std::vector< double > & | pose, |
| double | t, | ||
| double | smooth_scale, | ||
| double | delay_sacle | ||
| ) |
Tracking motion, used for executing offline trajectories or passing through user-planned trajectories, etc.
The difference from trackJoint is that it receives Cartesian poses instead of joint angles (inverse kinematics is performed internally by the software).
| pose | |
| t | |
| smooth_scale | |
| delay_sacle |
| int arcs::common_interface::MotionControl::trackJoint | ( | const std::vector< double > & | q, |
| double | t, | ||
| double | smooth_scale, | ||
| double | delay_sacle | ||
| ) |
Tracking motion, used for executing offline trajectories or passing through user-planned trajectories, etc.
| q | |
| smooth_scale | |
| delay_sacle |
| int arcs::common_interface::MotionControl::weaveEnd | ( | ) |
End weaving
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::weaveStart | ( | const std::string & | params | ) |
Start weaving: between weaveStart and weaveEnd, moveLine/moveCircle/moveProcess follows params.
| params | Json string. |
| arcs::common_interface::AuboException |
| int arcs::common_interface::MotionControl::weaveUpdateParameters | ( | const std::string & | params | ) |
Update frequency and amplitude during weaving process
| params | Json string used to define weaving parameters { "frequency": <num>, "amplitude": {<num>,<num>} } |
| arcs::common_interface::AuboException |
|
protected |
Definition at line 6208 of file motion_control.h.