AUBO SDK  0.26.0
Loading...
Searching...
No Matches
arcs::common_interface::MotionControl Class Reference

MotionControl. More...

#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 &param)
 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 &params)
 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 > &center, 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 &param, 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 &params)
 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_
 

Detailed Description

MotionControl.

Definition at line 67 of file motion_control.h.

Constructor & Destructor Documentation

◆ MotionControl()

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

◆ ~MotionControl()

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

Member Function Documentation

◆ clearPath()

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

ClearPath clears the whole motion path on the current motion path level (base level or StorePath level).

Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Lua function prototype
clearPath() -> number
Lua example
num = clearPath()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.clearPath","params":[],"id":1}
JSON-RPC response example
{"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 
)

Circular conveyor tracking

Note
Not implemented yet
Parameters
encoder_id0 - integrated sensor
rotate_tool
Returns
Exceptions
arcs::common_interface::AuboException

◆ conveyorTrackClearItems()

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

Clear all items in the conveyor queue

Parameters
encoder_idReserved
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
conveyorTrackClearItems(self: pyaubo_sdk.MotionControl, arg0: int) -> int
Lua function prototype
conveyorTrackClearItems(encoder_id: number) -> int
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackClearItems","params":[0],"id":1}
JSON-RPC response example
{"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 
)

Add an item to the conveyor queue

Parameters
encoder_idReserved
item_idItem ID
offsetOffset of the current item position relative to the template item position
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
conveyorTrackCreatItem(self: pyaubo_sdk.MotionControl, arg0: int, arg1:int, arg2: List[float]) -> int
Lua function prototype
conveyorTrackCreatItem(encoder_id: number, item_id: number, offset: table) -> number
JSON-RPC request example
{"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 response example
{"id":1,"jsonrpc":"2.0","result":0.0}

◆ conveyorTrackLine()

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

Linear conveyor tracking

Parameters
encoder_idReserved
directionThe movement direction of the conveyor relative to the robot base coordinate system
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
conveyorTrackLine(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
conveyorTrackLine -> int
JSON-RPC request example
{"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 response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ conveyorTrackStop()

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

Stop conveyor tracking

Parameters
encoder_idReserved
aReserved
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
conveyorTrackStop(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
conveyorTrackStop -> int
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackStop","params":[0,1.0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ conveyorTrackSwitch()

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.

Returns
Exceptions
arcs::common_interface::AuboException
Parameters
encoder_idReserved
Python function prototype
conveyorTrackSwitch(self: pyaubo_sdk.MotionControl) -> bool
Lua function prototype
conveyorTrackSwitch() -> boolean
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackSwitch","params":[0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":true}

◆ disableJointSoftServo()

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

Disable joint current loop stiffness coefficient

Returns
Returns 0 on success, otherwise error code
Exceptions
arcs::common_interface::AuboException
Python function prototype
disableJointSoftServo(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
disableJointSoftServo() -> number
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.disableJointSoftServo","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":1}

◆ disbaleVibrationSuppress()

int arcs::common_interface::MotionControl::disbaleVibrationSuppress ( )

◆ enableJointSoftServo()

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

Set joint current loop stiffness coefficient

Parameters
stiffnessStiffness coefficient for each joint, as a percentage [0 -> 1]. The larger the value, the stiffer the joint.
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
enableJointSoftServo(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
Lua function prototype
enableJointSoftServo(stiffness: table) -> int
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotConfig.enableJointSoftServo","params":[[0.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ enableVibrationSuppress()

int arcs::common_interface::MotionControl::enableVibrationSuppress ( const std::vector< double > &  omega,
const std::vector< double > &  zeta,
int  level 
)

◆ followJoint()

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

Joint space following

Note
Not implemented yet
Exceptions
arcs::common_interface::AuboException
Python function prototype
followJoint(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
Lua function prototype
followJoint(q: table) -> nil
Lua example
followJoint({0,0,0,0,0,0})

◆ followLine()

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

Cartesian space following

Note
Not implemented yet
Exceptions
arcs::common_interface::AuboException
Python function prototype
followLine(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
Lua function prototype
followLine(pose: table) -> nil
Lua example
followLine({0.58712,-0.15775,0.48703,2.76,0.344,1.432})

◆ getConveyorTrackNextItem()

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

Get the ID of the next item on the conveyor to be tracked

Parameters
encoder_idReserved
Returns
Returns the item ID; returns -1 if there is no next item
Exceptions
arcs::common_interface::AuboException
Python function prototype
getConveyorTrackNextItem(self: pyaubo_sdk.MotionControl, arg0: int) -> int
Lua function prototype
getConveyorTrackNextItem(encoder_id: number) -> int
JSON-RPC Request Example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackNextItem","params":[0],"id":1}
JSON-RPC Response Example
{"id":1,"jsonrpc":"2.0","result":{10}}

◆ getConveyorTrackQueue()

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

Get encoder values of the conveyor queue

Parameters
encoder_idReserved
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
getConveyorTrackQueue(self: pyaubo_sdk.MotionControl, arg0: int) -> List[int]
Lua function prototype
getConveyorTrackQueue(encoder_id: number) -> table
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackQueue","params":[0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":{[-500,-200,150,-50]}}

◆ getDuration()

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

Get the expected execution duration of the motion segment with the specified ID.

Parameters
idMotion segment ID
Returns
Returns the expected execution duration
Exceptions
arcs::common_interface::AuboException
Python function prototype
getDuration(self: pyaubo_sdk.MotionControl, arg0: int) -> float
Lua function prototype
getDuration(id: number) -> number
Lua example
num = getDuration(16)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getDuration","params":[16],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0.0}

◆ getEqradius()

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.

Returns
Returns the equivalent radius.
Exceptions
arcs::common_interface::AuboException
Python function prototype
getEqradius(self: pyaubo_sdk.MotionControl) -> float
Lua function prototype
getEqradius() -> number
Lua example
num = getEqradius()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getEqradius","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":1.0}

◆ getExecId()

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

Get the ID of the currently interpolating motion instruction segment.

Returns
The ID of the currently interpolating motion instruction segment.
Return values
-1Indicates 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.
Exceptions
arcs::common_interface::AuboException
Python function prototype
getExecId(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
getExecId() -> number
Lua example
num = getExecId()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getExecId","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":-1}

◆ getFuturePathPointsJoint()

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

Get trajectory points on the future path

Returns
Waypoints (100ms * 10)
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getFuturePathPointsJoint","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[]}

◆ getLookAheadSize()

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

Get look-ahead segment size

Returns
Returns the look-ahead segment size
Exceptions
arcs::common_interface::AuboException
Python function prototype
getLookAheadSize(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
getLookAheadSize() -> number
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getLookAheadSize","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":1}

◆ getMotionLeftTime()

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

Get the remaining execution time of the motion segment with the specified ID.

Parameters
idMotion segment ID
Returns
Returns the remaining execution time
Exceptions
arcs::common_interface::AuboException
Python function prototype
getMotionLeftTime(self: pyaubo_sdk.MotionControl, arg0: int) -> float
Lua function prototype
getMotionLeftTime(id: number) -> number
Lua example
num = getMotionLeftTime(16)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getMotionLeftTime","params":[16],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0.0}

◆ getPauseJointPositions()

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

Note
Get the joint positions at the pause point.

Commonly used during process recovery after a collision occurs (first move to the pause position using resumeMoveJoint or resumeMoveLine, then resume the process).

Returns
Pause joint positions
Exceptions
arcs::common_interface::AuboException
Python function prototype
getPauseJointPositions(self: pyaubo_sdk.MotionControl) -> List[float]
Lua function prototype
getPauseJointPositions() -> table
Lua example
JointPositions = getPauseJointPositions()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getPauseJointPositions","params":[],"id":1}
JSON-RPC response example
{"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 ( )

Get the execution progress of the current motion instruction segment.

Returns
Returns the execution progress.
Exceptions
arcs::common_interface::AuboException
Python function prototype
getProgress(self: pyaubo_sdk.MotionControl) -> float
Lua function prototype
getProgress() -> number
Lua example
num = getProgress()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getProgress","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0.0}

◆ getQueueSize()

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)

Returns
The number of enqueued instruction segments.
Exceptions
arcs::common_interface::AuboException
Python function prototype
getQueueSize(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
getQueueSize() -> number
Lua example
num = getQueueSize()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getQueueSize","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ getResumeMode()

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

Get resume motion mode

Returns
0: Resume start point is the pause point; 1: Resume start point is the specified point
Exceptions
arcs::common_interface::AuboException
Python function prototype
getResumeMode(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
getResumeMode() -> int
Lua example
num = getResumeMode()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getResumeMode","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":false}

◆ getServoModeSelect()

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

Get the servo motion mode

Returns
Lua function prototype
getServoModeSelect() -> number
Lua example
num = getServoModeSelect()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getServoModeSelect","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ getSpeedFraction()

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

Get the speed and acceleration ratio, default is 1.

Can be set via setSpeedFraction interface.

Returns
Returns the speed and acceleration ratio.
Exceptions
arcs::common_interface::AuboException
Python function prototype
getSpeedFraction(self: pyaubo_sdk.MotionControl) -> float
Lua function prototype
getSpeedFraction() -> number
Lua example
num = getSpeedFraction()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getSpeedFraction","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":1.0}

◆ getTrajectoryQueueSize()

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

Get the number of enqueued motion planning interpolation points

Returns
The number of enqueued motion planning interpolation points
Exceptions
arcs::common_interface::AuboException
Python function prototype
getTrajectoryQueueSize(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
getTrajectoryQueueSize() -> number
Lua example
num = getTrajectoryQueueSize()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getTrajectoryQueueSize","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ getWorkObjectHold()

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

getWorkObjectHold

Note
Not implemented yet
Returns
Returns a tuple containing the control module name and mounting pose
Exceptions
arcs::common_interface::AuboException
Python function prototype
getWorkObjectHold(self: pyaubo_sdk.MotionControl) -> Tuple[str, List[float]]
Lua function prototype
getWorkObjectHold() -> table
Lua example
Object_table = getWorkObjectHold()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.getWorkObjectHold","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":["",[]]}

◆ hasItemOnConveyorToTrack()

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

Whether there is an item on the conveyor that can be tracked

Parameters
encoder_idReserved
Returns
If the first item in the queue is in tracking state, returns true. If the first item is not in tracking state, checks the rest of the queue for items within the start window. Items outside the start window are dequeued until an item is found within the window, which is then set to tracking state and returns true. If no item in the queue is within the start window, returns false.
Exceptions
arcs::common_interface::AuboException
Python function prototype
hasItemOnConveyorToTrack(self: pyaubo_sdk.MotionControl) -> bool
Lua function prototype
hasItemOnConveyorToTrack() -> boolean
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.hasItemOnConveyorToTrack","params":[0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":{true}}

◆ isBlending()

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

Whether it is in the blending area

Returns
Returns true if in the blending area; otherwise returns false
Exceptions
arcs::common_interface::AuboException
Lua function prototype
isBlending() -> bool
Lua example
status = isBlending()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.isBlending","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":false}

◆ isConveyorTrackExceed()

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

Whether the workpiece on the conveyor has moved beyond the maximum limit

Parameters
encoder_idReserved
Returns
true : The movement distance exceeds the maximum limit false : The movement distance does not exceed the maximum limit
Exceptions
arcs::common_interface::AuboException
Python function prototype
isConveyorTrackExceed(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
Lua function prototype
isConveyorTrackExceed(encoder_id: number) -> bool
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackExceed","params":[0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":false}

◆ isConveyorTrackSync()

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

Determine whether the conveyor and the robot arm have reached relative rest

Parameters
encoder_idReserved
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
isConveyorTrackSync(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
Lua function prototype
isConveyorTrackSync(encoder_id: number) -> bool
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackSync","params":[0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":false}

◆ isJointSoftServoEnabled()

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

Determine whether the joint current loop stiffness coefficient is enabled.

Returns
Returns true if enabled, otherwise returns false.
Exceptions
arcs::common_interface::AuboException
Python function prototype
isJointSoftServoEnabled(self: pyaubo_sdk.MotionControl) -> bool
Lua function prototype
isJointSoftServoEnabled() -> boolean
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.isJointSoftServoEnabled","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":1}

◆ isServoModeEnabled()

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

Determine whether the servo mode is enabled.

Use getServoModeSelect instead.

Returns
Returns true if enabled, otherwise returns false.
Exceptions
arcs::common_interface::AuboException
Python function prototype
isServoModeEnabled(self: pyaubo_sdk.MotionControl) -> bool
Lua function prototype
isServoModeEnabled() -> boolean
Lua example
Servo_status = isServoModeEnabled()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.isServoModeEnabled","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":false}

◆ isSpeedFractionCritical()

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

Whether it is in the speed fraction critical section

Returns
Returns true if in the speed fraction critical section; otherwise returns false
Exceptions
arcs::common_interface::AuboException
Lua function prototype
isSpeedFractionCritical() -> bool
Lua example
status = isSpeedFractionCritical()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.isSpeedFractionCritical","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":true}

◆ isSupportedTimeOptimal()

bool arcs::common_interface::MotionControl::isSupportedTimeOptimal ( )

Check whether the time optimal algorithm is supported true - supported false - not supported

Returns
Return whether the time-optimal algorithm is supported
Exceptions
arcs::common_interface::AuboException
Python function prototype
isSupportedTimeOptimal(self: pyaubo_sdk.MotionControl) -> bool
Lua function prototype
isSupportedTimeOptimal() -> boolean
Lua example
flag = isSupportedTimeOptimal()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.isSupportedTimeOptimal","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":true}

◆ isTimeOptimalEnabled()

bool arcs::common_interface::MotionControl::isTimeOptimalEnabled ( )

Get the time optimal algorithm state: true - enable false - disable

Returns
Returns the time optimal algorithm state
Exceptions
arcs::common_interface::AuboException
Python function prototype
isTimeOptimalEnabled(self: pyaubo_sdk.MotionControl) -> bool
Lua function prototype
isTimeOptimalEnabled() -> boolean
Lua example
flag = isTimeOptimalEnabled()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.isTimeOptimalEnabled","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":true}

◆ jointOffsetDisable()

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

Disable joint offset

Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
jointOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
jointOffsetDisable() -> nil
Lua example
jointOffsetDisable()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetDisable","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ jointOffsetEnable()

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

Enable joint offset

Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
jointOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
jointOffsetEnable() -> nil
Lua example
jointOffsetEnable()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetEnable","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ jointOffsetSet()

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

Set joint offset

Parameters
offsetPose offset for each joint
type
Returns
Returns 0 on success; otherwise returns error code AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
jointOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: int) -> int
Lua function prototype
jointOffsetSet(offset: table, type: number) -> nil
Lua example
jointOffsetSet({0.1,0,0,0,0,0},1)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetSet","params":[[0.1,0,0,0,0],1],"id":1}
JSON-RPC response example
{"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 
)

Add circular arc motion

Parameters
via_poseThe pose of the via point during the arc motion
end_poseThe pose of the end point of the arc motion
aAcceleration (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)
vVelocity (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_radiusBlend radius, unit: m
durationExecution 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.
Returns
Returns 0 on success; otherwise returns error code AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
moveCircle(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: List[float], arg2: float, arg3: float, arg4: float, arg5: float) -> int
Lua function prototype
moveCircle(via_pose: table, end_pose: table, a: number, v: number, blend_radius: number, duration: number) -> nil
Lua example
moveCircle({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)
JSON-RPC request example
{"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 response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ moveCircle2()

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

Advanced arc or circular motion

Parameters
paramCircular motion parameters
Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
moveCircle2(self: pyaubo_sdk.MotionControl, arg0: arcs::common_interface::CircleParameters) -> int
Lua function prototype
moveCircle2(param: table) -> nil
Lua example
moveCircle2({0.440164,-0.00249391,0.398658,2.45651,0,1.570},{0.440164,0.166256,0.297599,2.45651,0,1.5708},1.2,0.25,0,0,0,0,0,0)
JSON-RPC request example
{"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 response example
{"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 with external axes synchronized motion

Parameters
group_nameName of the external axis group
via_poseThe pose of the via point during the arc motion
end_poseThe pose of the end point of the arc motion
aAcceleration
vVelocity
blend_radiusBlend radius
durationExecution time
Returns

◆ 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 
)

Intersection interface

Parameters
posesConsists 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
vVelocity
aAcceleration
main_pipe_radiusMain cylinder radius
sub_pipe_radiusSub cylinder radius
normal_distanceDistance between the two cylinder axes
normal_alphaAngle between the two cylinder axes
Returns
Returns 0 on success; otherwise returns an error code AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
moveIntersection(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float, arg4: float, arg5: float, arg6: float) -> int
Lua function prototype
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 
)

Add joint motion

Parameters
qJoint angles, unit: rad
aAcceleration, unit: rad/s^2, The maximum value can be obtained via RobotConfig::getJointMaxAccelerations()
vVelocity, unit: rad/s, The maximum value can be obtained via RobotConfig::getJointMaxSpeeds()
blend_radiusBlend radius, unit: m
durationExecution 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.
Return values
0Success
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
Exceptions
arcs::common_interface::AuboException
Python function prototype
moveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float, arg4: float) -> int
Lua function prototype
moveJoint(q: table, a: number, v: number, blend_radius: number, duration: number) -> nil
Lua example
moveJoint({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033, -2.28774},0.3,0.3,0,0)
JSON-RPC request example
{"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 response example
{"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 
)

Synchronous motion of robot and external axes

Parameters
group_name
q
a
v
blend_radius
duration
Returns

◆ moveLine()

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

Add linear motion

Parameters
poseTarget pose
aAcceleration (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().
vVelocity (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_radiusBlend radius, unit: m, value between 0.001 and 1
durationExecution 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.
Return values
0Success
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
Exceptions
arcs::common_interface::AuboException
Python function prototype
moveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float, arg4: float) -> int
Lua function prototype
moveLine(pose: table, a: number, v: number, blend_radius: number, duration: number) -> nil
Lua example
moveLine({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.3,1.0,0)
JSON-RPC request example
{"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 response example
{"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 
)

Linear motion synchronized with external axes

Parameters
group_nameName of the external axis group
poseTarget pose
aAcceleration
vVelocity
blend_radiusBlend radius
durationExecution time
Returns

◆ movePathBuffer()

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

Execute the cached path

Parameters
nameName of the cached path
Returns
Returns 0 on success; otherwise returns an error code -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
movePathBuffer(self: pyaubo_sdk.MotionControl, arg0: str) -> int
Lua function prototype
movePathBuffer(name: string) -> nil
Lua example
movePathBuffer("traje_name")
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.movePathBuffer","params":["rec"],"id":1}
JSON-RPC response example
{"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 
)

Add process motion

Parameters
pose
a
v
blend_radius
Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Lua function prototype
moveProcess(pose: table, a: number, v: number, blend_radius: number, duration: number) -> nil
Lua example
moveProcess({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.2,0.25,0)
JSON-RPC request example
{"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 response example
{"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 
)

Spiral motion

Parameters
paramEncapsulated parameters
blend_radius
v
a
t
Returns
Returns 0 on success; otherwise returns an error code AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"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 response example
{"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 
)

Perform spline interpolation in joint space

Parameters
qJoint angles. If the input vector is of size 0, it indicates the end of the spline motion.
aAcceleration, unit: rad/s^2. The maximum value can be obtained via RobotConfig::getJointMaxAccelerations().
vVelocity, unit: rad/s. The maximum value can be obtained via RobotConfig::getJointMaxSpeeds().
duration
Returns
Returns 0 on success; otherwise returns an error code: AUBO_BUSY AUBO_BAD_STATE -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
moveSpline(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float) -> int
Lua function prototype
moveSpline(q: table, a: number, v: number, duration: number) -> nil
Lua example
moveSpline({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033, -2.28774},1.3,1.0,0)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpline","params":[[0,0,0,0,0,0],1,1,0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathBufferAlloc()

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

Create a new path point buffer

Parameters
nameName of the path
typeType of the path
1: toppra time-optimal path planning
2: cubic_spline (recorded trajectory)
3: Joint B-spline interpolation, at least three points
sizeBuffer size
Returns
Returns AUBO_OK(0) on success
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathBufferAlloc(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int, arg2: int) -> int
Lua function prototype
pathBufferAlloc(name: string, type: number, size: number) -> nil
Lua exmaple
pathBufferAlloc("traje_name",5,100)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAlloc","params":["rec",2,3],"id":1}
JSON-RPC response example
{"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 
)

Add waypoints to the path buffer

Parameters
nameName of the path buffer
waypointsWaypoints
Returns
Returns 0 on success; otherwise returns an error code -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathBufferAppend(self: pyaubo_sdk.MotionControl, arg0: str, arg1: List[List[float]]) -> int
Lua function prototype
pathBufferAppend(name: string, waypoints: table) -> nil
Lua example
pathBufferAppend("traje_name",{{-0.000000,0.000009,-0.000001,0.000002,0.000002,0.000000},{-0.000001,0.000010,-0.000002,0.000000,0.000003,0.000002}})
JSON-RPC request example
{"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 response example
{"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 
)

Perform computation and optimization (time-consuming operations).

If the input parameters are the same, the calculation will not be repeated.

Parameters
nameName of the path point buffer created by pathBufferAlloc
aJoint acceleration limits, must match the robot DOF, unit: rad/s^2
vJoint velocity limits, must match the robot DOF, unit: rad/s
tTime
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)
Returns
Returns 0 on success; otherwise returns an error code -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathBufferEval(self: pyaubo_sdk.MotionControl, arg0: str, arg1: List[float], arg2: List[float], arg3: float) -> int
Lua function prototype
pathBufferEval(name: string, a: table, v: table, t: number) -> nil
Lua example
pathBufferEval("traje_name",{1,1,1,1,1,1},{1,1,1,1,1,1},0.02)
JSON-RPC request example
{"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 response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathBufferFilter()

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

Joint space path filter

pathBufferFilter

Parameters
nameName of the path buffer
orderFilter order (usually 2)
fdCutoff frequency, the smaller the smoother but with more delay (usually 3-20)
fsSampling frequency of discrete data (usually 20-500)
Returns
Returns 0 on success
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathBufferFilter(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int, arg2: float, arg3: float) -> int
Lua function prototype
pathBufferFilter(name: string, order: number, fd: number, fs:number) -> nil
Lua example
pathBufferFilter("traje_name",2,5,125)

◆ pathBufferFree()

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

Release path buffer

Parameters
nameName of the path buffer
Returns
Returns 0 on success; otherwise returns an error code -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathBufferFree(self: pyaubo_sdk.MotionControl, arg0: str) -> int
Lua function prototype
pathBufferFree(name: string) -> nil
Lua example
pathBufferFree("traje_name")
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferFree","params":["rec"],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":-5}

◆ pathBufferList()

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

List all cached path names

Returns
Returns all cached path names
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathBufferList(self: pyaubo_sdk.MotionControl) -> List[str]
Lua function prototype
pathBufferList() -> table
Lua example
Buffer_table = pathBufferList()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferList","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[]}

◆ pathBufferValid()

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:

  1. The buffer exists and memory has been allocated
  2. The number of points passed into the buffer must be greater than or equal to the buffer size
  3. pathBufferEval must be executed once
Parameters
nameName of the buffer
Returns
Returns true if valid; false otherwise
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathBufferValid(self: pyaubo_sdk.MotionControl, arg0: str) -> bool
Lua function prototype
pathBufferValid(name: string) -> boolean
Lua example
buffer_status = pathBufferValid("traje_name")
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferValid","params":["rec"],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":false}

◆ pathOffsetCoordinate()

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

Set the reference coordinate system for offset.

Only valid when type=1 in pathOffsetSet.

Parameters
ref_coordReference coordinate system: 0-base coordinate, 1-TCP
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathOffsetCoordinate(self: pyaubo_sdk.MotionControl, arg0: int) -> float
Lua function prototype
pathOffsetCoordinate(ref_coord: number) -> number
Lua example
num = pathOffsetCoordinate(0)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetCoordinate","params":[0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathOffsetDisable()

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

Disable path offset

Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
pathOffsetDisable() -> nil
Lua example
pathOffsetDisable()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetDisable","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathOffsetEnable()

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

Enable path offset

Returns
Returns 0 on success; otherwise returns an error code: AUBO_BUSY AUBO_BAD_STATE -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
pathOffsetEnable() -> number
Lua example
num = pathOffsetEnable()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetEnable","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ pathOffsetLimits()

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.

Parameters
vMaximum speed
aMaximum acceleration
Returns
Returns 0 on success; otherwise returns an error code: AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathOffsetLimits(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
Lua function prototype
pathOffsetLimits(v: number, a: number) -> nil
Lua example
pathOffsetLimits(1.5,2.5)

◆ pathOffsetSet()

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

Set path offset

Parameters
offsetPose offset in each direction
typeMotion type 0-position planning 1-velocity planning
Returns
Returns 0 on success; otherwise returns error code AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: int) -> int
Lua function prototype
pathOffsetSet(offset: table, type: number) -> nil
Lua example
pathOffsetSet({ 0, 0, 0.1, 0, 0, 0 }, 0)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetSet","params":[[0,0,0.01,0,0,0],0],"id":1}
JSON-RPC response example
{"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 
)

Monitor trajectory offset range

Parameters
minMaximum offset in the negative direction of the coordinate axis
maxMaximum offset in the positive direction of the coordinate axis
strategyMonitoring strategy after reaching the maximum offset     0 - Disable monitoring     1 - Saturation limit, i.e., maintain maximum pose     2 - Protective stop
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathOffsetSupv(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: List[float], arg2: int) -> int
Lua function prototype
pathOffsetSupv(min: table, max: table, strategy: number) -> number
Lua example
num = pathOffsetSupv({0,0,-0.2,0,0,0},{0,0,0.5,0,0,0},0)

◆ restoPath()

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

restoPath

Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Lua function prototype
restoPath() -> number
Lua example
num restoPath()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.restoPath","params":[],"id":1}
JSON-RPC response example
{"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 
)

Move to the pause point using joint motion.

Parameters
qJoint angles, unit: rad
aAcceleration, unit: rad/s^2
vVelocity, unit: rad/s
durationExecution 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.
Returns
Returns 0 on success; otherwise returns error code -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
resumeMoveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float) -> int
Lua function prototype
resumeMoveJoint(q: table, a: number, v: number, duration: number) -> nil
Lua example
resumeMoveJoint({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033, -2.28774},1.3,1.0,0)
JSON-RPC request example
{"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 response example
{"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 
)

Move to the pause point using linear motion.

Parameters
poseTarget pose
aAcceleration, unit: m/s^2
vVelocity, unit: m/s
durationExecution 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.
Returns
Returns 0 on success; otherwise returns error code -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
resumeMoveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float) -> int
Lua function prototype
resumeMoveLine(pose: table, a: number, v: number, duration: number) -> nil
Lua example
resumeMoveLine({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.2,0.25,0)
JSON-RPC request example
{"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 response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ resumeSpeedJoint()

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.

Parameters
qdTarget joint velocity, unit: rad/s
aMain axis acceleration, unit: rad/s^2
tTime 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.
Returns
Returns 0 on success; otherwise returns error code AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
resumeSpeedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float) -> int
Lua function prototype
resumeSpeedJoint(q: table, a: number, t: number) -> nil
Lua example
resumeSpeedJoint({0.2,0,0,0,0,0},1.5,10)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":-1}

◆ resumeSpeedLine()

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.

Parameters
xdTool velocity, unit: m/s
aTool position acceleration, unit: m/s^2
tTime 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.
Returns
Returns 0 on success; otherwise returns error code -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
resumeSpeedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float) -> int
Lua function prototype
resumeSpeedLine(pose: table, a: number, t: number) -> nil
Lua example
resumeSpeedLine({0.25,0,0,0,0,0},1.2,100)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":-1}

◆ resumeStopJoint()

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)

Parameters
accJoint acceleration, unit: rad/s^2
Returns
Returns 0 on success; otherwise returns an error code AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
resumeStopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
Lua function prototype
resumeStopJoint(acc: number) -> nil
Lua example
resumeStopJoint(31)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopJoint","params":[31],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":-1}

◆ resumeStopLine()

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)

Parameters
accPosition acceleration, unit: m/s^2
acc_rotOrientation acceleration, unit: rad/s^2
Returns
Returns 0 on success; otherwise returns an error code AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
resumeStopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
Lua function prototype
resumeStopLine(acc: number, acc_rot: number) -> nil
Lua example
resumeStopLine(10,10)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopLine","params":[10,10],"id":1}
JSON-RPC response example
{"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 
)

Cartesian space servo

Currently, only pose and t parameters are available;

Parameters
posePose, unit: m
aAcceleration, unit: m/s^2
vVelocity, unit: m/s
tExecution 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_timeLookahead 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.
gainProportional 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.
Return values
0Success
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;
Exceptions
arcs::common_interface::AuboException
Python function prototype
servoCartesian(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
Lua function prototype
servoCartesian(pose: table, a: number, v: number, t: number, lookahead_time: number, gain: number) -> nil
Lua example
servoCartesian({0.58712,-0.15775,0.48703,2.76,0.344,1.432},0,0,10,0,0)
JSON-RPC request example
{"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 response example
{"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 
)

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).

Parameters
pose
extq
t
smooth_scale
delay_sacle
Returns

◆ 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 
)

Joint space servo

Currently only q and t parameters are available;

Parameters
qJoint angles, unit: rad
aAcceleration, unit: rad/s^2
vVelocity, unit: rad/s
tExecution 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_timeLookahead 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.
gainProportional 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.
Return values
0Success
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
Exceptions
arcs::common_interface::AuboException
Python function prototype
servoJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
Lua function prototype
servoJoint(q: table, a: number, v: number, t: number, lookahead_time: number, gain: number) -> nil
Lua example
servoJoint({0,0,0,0,0,0},0,0,10,0,0)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.servoJoint","params":[[0,0,0,0,0,0],0,0,10,0,0],"id":1}
JSON-RPC response example
{"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 
)

Servo motion (with external axes), used for executing offline trajectories, pass-through user planned trajectories, etc.

Parameters
q
extq
t
smooth_scale
delay_sacle
Returns

◆ 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)

Set circle path mode

Parameters
modeMode
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
Returns
Returns 0 on success; otherwise returns an error code AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
setCirclePathMode(self: pyaubo_sdk.MotionControl, arg0: int) -> int
Lua function prototype
setCirclePathMode(mode: number) -> nil
Lua example
setCirclePathMode(1)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setCirclePathMode","params":[0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackCompensate()

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

Set the compensation value for conveyor tracking

Parameters
encoder_idReserved
compConveyor compensation value
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
setConveyorTrackCompensate(self: pyaubo_sdk.MotionControl, arg0: int, arg1: float) -> int
Lua function prototype
setConveyorTrackCompensate(comp: number) -> number
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackCompensate","params":[0, 0.1],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackEncoder()

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

Set conveyor encoder parameters

Parameters
encoder_idReserved
tick_per_meterLinear conveyor: pulses per meter Circular conveyor: pulses per revolution
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
setConveyorTrackEncoder(self: pyaubo_sdk.MotionControl) -> int
Lua function prototype
setConveyorTrackEncoder(encoder_id: bumber,tick_per_meter: number) -> int
Lua example
num = setConveyorTrackEncoder(1,40000)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackEncoder","params":[1,40000],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackLimit()

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

Set the maximum distance limit for conveyor tracking

Parameters
encoder_idReserved
limitMaximum distance limit for conveyor tracking, unit: meter
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
setConveyorTrackLimit(self: pyaubo_sdk.MotionControl, arg0: int, arg1: double) -> int
Lua function prototype
setConveyorTrackLimit(encoder_id: number, limit: number) -> int
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackLimit","params":[0, 1.5],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackSensorOffset()

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

Set the distance from the conveyor teaching position to the sync switch

Parameters
encoder_idReserved
offsetDistance from the conveyor teaching position to the sync switch, unit: meter
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
setConveyorTrackSensorOffset(self: pyaubo_sdk.MotionControl, arg0: int, arg1: double) -> int
Lua function prototype
setConveyorTrackSensorOffset(encoder_id: number, offset: number) -> int
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSensorOffset","params":[0, 0.2],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackStartWindow()

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

Set the start window for conveyor tracking

Parameters
encoder_idReserved
min_windowStart position of the window, unit: meter
max_windowEnd position of the window, unit: meter
Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
setConveyorTrackStartWindow(self: pyaubo_sdk.MotionControl, arg0: int, arg1: double, arg2: double) -> int
Lua function prototype
setConveyorTrackStartWindow(encoder_id: number, min_window: number, max_window: number) -> int
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackStartWindow","params":[0, 0.2, 1.0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setConveyorTrackSyncSeparation()

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.

Parameters
encoder_idReserved
distanceThe minimum distance to travel after a sync signal appears before accepting a new sync signal as a valid object, unit: meter
timeThe 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.

Returns
Exceptions
arcs::common_interface::AuboException
Python function prototype
setConveyorTrackSyncSeparation(self: pyaubo_sdk.MotionControl, arg0: int, arg1: double, arg2: double) -> int
Lua function prototype
setConveyorTrackSyncSeparation(encoder_id: number, distance: number, time: number) -> int
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSyncSeparation","params":[0, 0.05, 0.2],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setEqradius()

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.

Parameters
eqradius0 means only plan the movement, and the posture rotation follows the movement.
Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setEqradius","params":[0.8],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}
Python function prototype
setEqradius(self: pyaubo_sdk.MotionControl, arg0: float) -> int
Lua function prototype
setEqradius(eqradius: number) -> number
Lua example
num = setEqradius(1)

◆ setFuturePointSamplePeriod()

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

Set the sampling interval for points on the future path

Parameters
sample_timeSampling interval, unit: m/s^2
Returns
Returns 0 on success; otherwise returns an error code AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException

◆ setLookAheadSize()

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

Set look-ahead segment size

  1. For tasks requiring high speed smoothness, such as CNC machining, gluing, welding, etc., a longer look-ahead segment size can provide better speed planning and smoother motion.
  2. For fast-response tasks such as picking, a shorter look-ahead segment size is preferred to improve response speed, but may cause large speed fluctuations due to insufficiently timely path feeding.
Returns
Returns 0 on success
Exceptions
arcs::common_interface::AuboException
Python function prototype
setLookAheadSize(self: pyaubo_sdk.MotionControl, arg0: int) -> int
Lua function prototype
setLookAheadSize(eqradius: number) -> number
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setLookAheadSize","params":[1],"id":1}
JSON-RPC response example
{"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 
)

Set resume motion parameters

Parameters
qResume start position
move_type0: Joint space, 1: Cartesian space
blend_radiusBlend radius
qdmaxMaximum joint speed (6 elements)
qddmaxMaximum joint acceleration (6 elements)
vmaxMaximum linear and angular speed for linear motion (2 elements)
amaxMaximum linear and angular acceleration for linear motion (2 elements)
Returns
Returns 0 on success; otherwise returns error code AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
setResumeStartPoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: int, arg2: float, arg3: List[float], arg4: List[float], arg5: float, arg6: float) -> int
Lua function prototype
setResumeStartPoint(q: table, move_type: number, blend_radius: number, qdmax: table, qddmax: table, vmax: number, amax: number) -> nil
Lua example
setResumeStartPoint({0,0,0,0,0,0},1,1,{0,0,0,0,0,0},{0,0,0,0,0,0},{1,1},{1,1})
JSON-RPC request example
{"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 response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setServoMode()

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

Set servo mode Use setServoModeSelect instead

Parameters
enableWhether to enable
Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
setServoMode(self: pyaubo_sdk.MotionControl, arg0: bool) -> int
Lua function prototype
setServoMode(enable: boolean) -> nil
Lua example
setServoMode(true)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setServoMode","params":[true],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setServoModeSelect()

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

Set servo motion mode

Parameters
mode0 - Exit servo mode 1 - Planning servo mode 2 - Transparent mode (direct send) 3 - Transparent mode (buffered)
Returns
Lua function prototype
setServoModeSelect(0) -> nil
Lua example
setServoModeSelect(0)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setServoModeSelect","params":[0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setSpeedFraction()

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

Dynamically adjust the robot's speed and acceleration ratio (0., 1.

]

Parameters
fractionThe ratio of robot speed and acceleration
Returns
Returns 0 on success; otherwise returns an error code: AUBO_INVL_ARGUMENT AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
setSpeedFraction(self: pyaubo_sdk.MotionControl, arg0: float) -> int
Lua function prototype
setSpeedFraction(fraction: number) -> nil
Lua example
setSpeedFraction(0.5)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setSpeedFraction","params":[0.8],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ setTimeOptimalEnable()

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

Parameters
enable
Exceptions
arcs::common_interface::AuboException
Lua function prototype
setTimeOptimalEnable() -> number
Lua example
setTimeOptimalEnable(true)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.setTimeOptimalEnable","params":[true],"id":1}
JSON-RPC response example
{"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 
)

Specify the name and mounting position when the workpiece is installed on the end of another robot or external axis.

Note
Not implemented yet
Parameters
module_nameName of the control module
mounting_poseRelative position of the grasp, if it is a robot, it is relative to the robot's end center point (not the TCP point)
Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
setWorkObjectHold(self: pyaubo_sdk.MotionControl, arg0: str, arg1: List[float]) -> int
Lua function prototype
setWorkObjectHold(module_name: string, mounting_pose: table) -> nil
Lua example
setWorkObjectHold("object",{0.2,0.1,-0.4,3.14,0,-1.57})

◆ speedFractionCritical()

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.

Parameters
enable
Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Lua function prototype
speedFractionCritical() -> nil
Lua example
speedFractionCritical(true)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.speedFractionCritical","params":[true],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ speedJoint()

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.

Parameters
qdTarget joint velocity, unit: rad/s
aMain axis acceleration, unit: rad/s^2
tTime 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.
Return values
0Success
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
Exceptions
arcs::common_interface::AuboException
Python function prototype
speedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float) -> int
Lua function prototype
speedJoint(qd: table, a: number, t: number) -> nil
Lua example
speedJoint({0.2,0,0,0,0,0}, 1.5,10)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.speedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ speedLine()

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.

Parameters
xdTool velocity, unit: m/s
aTool position acceleration, unit: m/s^2
tTime 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.
Return values
0Success
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
Exceptions
arcs::common_interface::AuboException
Python function prototype
speedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float, arg2: float) -> int
Lua function prototype
speedLine(pose: table, a: number, t: number) -> nil
Lua example
speedLine({0.25,0,0,0,0,0},1.2,100)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.speedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ startMove()

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.

Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Lua function prototype
startMove() -> number
Lua example
num = startMove()
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.startMove","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ stopJoint()

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

Stop motion in joint space

Parameters
accJoint acceleration, unit: rad/s^2
Returns
Returns 0 on success; otherwise returns an error code AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
stopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
Lua function prototype
stopJoint(acc: number) -> nil
Lua example
stopJoint(2)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.stopJoint","params":[31],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ stopLine()

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

Stop motions in Cartesian space such as moveLine/moveCircle.

Parameters
accTool acceleration, unit: m/s^2
acc_rot
Returns
Returns 0 on success; otherwise returns an error code AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Python function prototype
stopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
Lua function prototype
stopLine(acc: number, acc_rot: number) -> nil
Lua example
stopLine(10,10)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.stopLine","params":[10,10],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ stopMove()

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.

Parameters
quicktrue: 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).
Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Lua function prototype
StopMove(quick: bool,all_tasks: bool) -> number
Lua example
num = StopMove(true,true)

◆ storePath()

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

storePath

Parameters
keep_sync
Returns
Returns 0 on success; otherwise returns an error code: AUBO_BAD_STATE AUBO_BUSY -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Lua function prototype
storePath(keep_sync: bool) -> number
Lua example
num = storePath()

◆ trackCartesian()

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).

Parameters
pose
t
smooth_scale
delay_sacle
Returns
Lua function prototype
trackCartesian(pose: table,t: number,smooth_scale: number,delay_sacle: number) -> nil
Lua example
trackCartesian({0.58712,-0.15775,0.48703,2.76,0.344,1.432},0.01,0.5,1)
JSON-RPC request example
{"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 response example
{"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 
)

Tracking motion, used for executing offline trajectories or passing through user-planned trajectories, etc.

Parameters
q
smooth_scale
delay_sacle
Returns
Lua function prototype
trackJoint(q: table,t: number,smooth_scale: number,delay_sacle: number) -> nil
Lua example
trackJoint({0,0,0,0,0,0},0.01,0.5,1)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.trackJoint","params":[[0,0,0,0,0,0],0.01,0.5,1],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ weaveEnd()

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

End weaving

Returns
Returns 0 on success; otherwise returns an error code AUBO_BUSY AUBO_BAD_STATE -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.MotionControl.weaveEnd","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ weaveStart()

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

Start weaving: between weaveStart and weaveEnd, moveLine/moveCircle/moveProcess follows params.

Warning
Start RuntimeMachine before calling weaveStart.
Parameters
paramsJson string.
Since v0.29
  • "type": <string> — Waveform: "SINE" | "SPIRAL" | "TRIANGLE" | "TRAPEZOIDAL" (case-sensitive).
  • "step": <number> — Arc-length sampling step, m.
  • "amplitude": [<number>,<number>] — Left/right weave amplitude, m.
  • "hold_distance": [<number>,<number>] — Dwell distance at peak amplitude along path, m.
  • "hold_time": [<number>,<number>] — Dwell time at peak amplitude, s.
  • "angle": <number> — Angle to normal plane, rad.
  • "direction": <integer> — Initial direction: 0=above path, 1=below path.
  • "movep_uniform_vel": <bool> — Uniform-velocity planning (boolean value).
Since v0.31
  • Same as v0.29.
New/changed in v0.32
  • "frequency": <number> — Weave frequency, Hz (range [0.1, 5]).
  • "ori_weave_range": [<number>,<number>,<number>] — Attitude weave range [x,y,z], rad; often used with Archimedean spiral for force-guided hole finding.
  • "ori_weave_frequency": [<number>,<number>,<number>] — Attitude weave frequency [x,y,z], m^-1 (per unit arc; range [0, 1]).
  • "adjust_cycle_num": <integer> — Number of transition cycles.
  • "azimuth": <number> — Waveform azimuth, rad.
  • "ridge_height": <number> — Center raise height, m.
Warning
hold_time is supported for SINE only and may be asymmetric.
You may relate frequency = vel / step when an external path speed vel (m·s^-1) is available.
Note
  • Two-element arrays are [left,right]; three-element arrays are attitude [x,y,z].
  • All angles are in radians (rad).
Returns
Returns 0 on success; otherwise returns an error code:
  • AUBO_BUSY
  • AUBO_BAD_STATE
  • -AUBO_INVL_ARGUMENT
  • -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException
Example v0.29/v0.31
params = {
"type": "SINE",
"step": 0.005,
"amplitude": [0.01, 0.01],
"hold_distance": [0.001, 0.001],
"hold_time": [0, 0],
"angle": 0,
"direction": 0,
"movep_uniform_vel": false
}
Example v0.32
params = {
"type" : "SINE", // "SINE" "SPIRAL" "TRIANGLE" "TRAPEZOIDAL"
"step" : 0.0, // frequency = vel / step (vel: m·s^-1)
"frequency" : 0.0, // [0.1, 5] Hz
"amplitude" : [0.01, 0.01], // m
"hold_distance" : [0.001, 0.001], // m
"hold_time" : [0, 0], // s (SINE only)
"angle" : 0, // rad
"direction" : 0,
"ori_weave_range" : [0.001, 0.001, 0.001], // rad
"ori_weave_frequency": [0.001, 0.001, 0.001], // m^-1
"adjust_cycle_num": 0,
"azimuth" : 0, // rad
"ridge_height" : 0 // m
}
Python function prototype
weaveStart(self: pyaubo_sdk.MotionControl, arg0: str) -> int
Python example
robot_name = rpc_cli.getRobotNames()[0]
robot_interface = rpc_cli.getRobotInterface(robot_name)
robot_interface.getMotionControl().weaveStart(params)
Lua function prototype
weaveStart(params: string) -> nil
Lua example (v0.29/0.31)
weaveStart("{\"type\":\"SINE\",\"step\":0.005,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"movep_uniform_vel\":false}")
Lua example (v0.32)
weaveStart("{\"type\":\"SINE\",\"step\":0.0,\"frequency\":2.0,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"ori_weave_range\":[0.001,0.001,0.001],\"ori_weave_frequency\":[0.001,0.001,0.001],\"adjust_cycle_num\":0,\"azimuth\":0,\"ridge_height\":0}")
JSON-RPC request example (v0.29/0.31)
{"jsonrpc":"2.0","method":"rob1.MotionControl.weaveStart","params":["{\"type\":\"SINE\",\"step\":0.005,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"movep_uniform_vel\":false}"],"id":1}
JSON-RPC request example (v0.32)
{"jsonrpc":"2.0","method":"rob1.MotionControl.weaveStart","params":["{\"type\":\"SINE\",\"step\":0.0,\"frequency\":2.0,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"ori_weave_range\":[0.001,0.001,0.001],\"ori_weave_frequency\":[0.001,0.001,0.001],\"adjust_cycle_num\":0,\"azimuth\":0,\"ridge_height\":0}"],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ weaveUpdateParameters()

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

Update frequency and amplitude during weaving process

Parameters
paramsJson string used to define weaving parameters { "frequency": <num>, "amplitude": {<num>,<num>} }
Returns
Returns 0 on success
Exceptions
arcs::common_interface::AuboException

Member Data Documentation

◆ d_

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

Definition at line 6208 of file motion_control.h.


The documentation for this class was generated from the following file: