AUBO SDK  0.26.0
arcs::common_interface::MotionControl Class Reference

#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
int setTcpMaxLinearVelocity (double v)
 Set TCP maximum linear velocity
double getTcpMaxLinearVelocity ()
 Get TCP maximum linear velocity
int resetTcpMaxLinearVelocity ()
 Reset TCP maximum linear velocity
int setEndPath ()
 Set end path (terminate blending at current trajectory segment)

Protected Attributes

void * d_

Detailed Description

Definition at line 69 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

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

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

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

Member Data Documentation

◆ d_

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

Definition at line 6562 of file motion_control.h.


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