5#ifndef AUBO_SDK_MOTION_CONTROL_INTERFACE_H
6#define AUBO_SDK_MOTION_CONTROL_INTERFACE_H
12#include <aubo/global_config.h>
16namespace common_interface {
761 const std::vector<double> &max,
int strategy);
1560 const std::vector<double> &mounting_pose);
1748 double blend_radius,
1749 const std::vector<double> &qdmax,
1750 const std::vector<double> &qddmax,
1751 const std::vector<double> &vmax,
1752 const std::vector<double> &amax);
2117 int servoJoint(
const std::vector<double> &q,
double a,
double v,
double t,
2118 double lookahead_time,
double gain);
2246 double t,
double lookahead_time,
double gain);
2272 const std::vector<double> &extq,
double a,
double v,
2273 double t,
double lookahead_time,
double gain);
2276 double v,
double t,
double lookahead_time,
2277 double gain,
const std::string &group_name,
2278 const std::vector<double> &extq);
2309 const std::vector<double> &extq,
double a,
2310 double v,
double t,
double lookahead_time,
2314 double v,
double t,
double lookahead_time,
2315 double gain,
const std::string &group_name,
2316 const std::vector<double> &extq);
2365 int trackJoint(
const std::vector<double> &q,
double t,
double smooth_scale,
2366 double delay_sacle);
2420 double smooth_scale,
double delay_sacle);
2587 int speedJoint(
const std::vector<double> &qd,
double a,
double t);
2753 int speedLine(
const std::vector<double> &xd,
double a,
double t);
3007 int moveJoint(
const std::vector<double> &q,
double a,
double v,
3008 double blend_radius,
double duration);
3035 double blend_radius,
double duration,
3036 const std::string &group_name,
3037 const std::vector<double> &extq);
3227 int moveLine(
const std::vector<double> &pose,
double a,
double v,
3228 double blend_radius,
double duration);
3255 double v,
double blend_radius,
double duration,
3256 const std::string &group_name,
3257 const std::vector<double> &extq);
3318 double blend_radius);
3493 const std::vector<double> &end_pose,
double a,
double v,
3494 double blend_radius,
double duration);
3523 const std::vector<double> &end_pose,
double a,
3524 double v,
double blend_radius,
double duration,
3525 const std::string &group_name,
3526 const std::vector<double> &extq);
3781 const std::vector<std::vector<double>> &waypoints);
3862 const std::vector<double> &v,
double t);
4214 double a,
double v,
double main_pipe_radius,
4215 double sub_pipe_radius,
double normal_distance,
4216 double normal_alpha);
5174 const std::vector<double> &offset);
5741 double a,
double t);
6038 const std::vector<double> &zeta,
int level);
int resumeMoveJoint(const std::vector< double > &q, double a, double v, double duration)
Move to the pause point using joint motion.
int pathOffsetLimits(double v, double a)
Set the maximum speed and maximum acceleration for offset.
int followJoint(const std::vector< double > &q)
Joint space following
int setLookAheadSize(int size)
Set look-ahead segment size
int jointOffsetDisable()
Disable joint offset
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 followLine(const std::vector< double > &pose)
Cartesian space following
int getResumeMode()
Get resume motion mode
int stopJoint(double acc)
Stop motion in joint space
int conveyorTrackStop(int encoder_id, double a)
Stop conveyor tracking
int speedJoint(const std::vector< double > &qd, double a, double t)
Joint space velocity following
int moveCircle2(const CircleParameters ¶m)
Advanced arc or circular motion
int getServoModeSelect()
Get the servo motion mode
int pathOffsetSupv(const std::vector< double > &min, const std::vector< double > &max, int strategy)
int getTrajectoryQueueSize()
Get the number of enqueued motion planning interpolation points
int setConveyorTrackLimit(int encoder_id, double limit)
Set the maximum distance limit for conveyor tracking
int clearPath()
ClearPath clears the whole motion path on the current motion path level (base level or StorePath leve...
bool conveyorTrackSwitch(int encoder_id)
Switch conveyor tracking item.
std::vector< std::vector< double > > getFuturePathPointsJoint()
Get trajectory points on the future path
int jointOffsetSet(const std::vector< double > &offset, int type=1)
Set joint offset
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 ...
double getMotionLeftTime(int id)
Get the remaining execution time of the motion segment with the specified ID.
int pathBufferAlloc(const std::string &name, int type, int size)
Create a new path point buffer
std::vector< int > getConveyorTrackQueue(int encoder_id)
Get encoder values of the conveyor queue
int servoCartesian(const std::vector< double > &pose, double a, double v, double t, double lookahead_time, double gain)
Cartesian space servo
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
double getSpeedFraction()
Get the speed and acceleration ratio, default is 1.
std::vector< double > getPauseJointPositions()
int startMove()
StartMove is used to resume robot, external axes movement and belonging process after the movement ha...
int storePath(bool keep_sync)
storePath
int moveJoint(const std::vector< double > &q, double a, double v, double blend_radius, double duration)
Add joint motion
bool isBlending()
Whether it is in the blending area
bool isConveyorTrackExceed(int encoder_id)
Whether the workpiece on the conveyor has moved beyond the maximum limit
int moveSpline(const std::vector< double > &q, double a, double v, double duration)
Perform spline interpolation in joint space
int resumeMoveLine(const std::vector< double > &pose, double a, double v, double duration)
Move to the pause point using linear motion.
int stopLine(double acc, double acc_rot)
Stop motions in Cartesian space such as moveLine/moveCircle.
int setConveyorTrackStartWindow(int encoder_id, double window_min, double window_max)
Set the start window for conveyor tracking
int getConveyorTrackNextItem(int encoder_id)
Get the ID of the next item on the conveyor to be tracked
int resumeStopLine(double acc, double acc_rot)
Stop motion in Cartesian space (used after moving to a safe position via resumeSpeedLine following a ...
std::tuple< std::string, std::vector< double > > getWorkObjectHold()
getWorkObjectHold
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 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 speedFractionCritical(bool enable)
Speed fraction critical section.
std::vector< std::string > pathBufferList()
List all cached path names
int stopMove(bool quick, bool all_tasks)
StopMove is used to stop robot and external axes movements and any belonging process temporarily.
int conveyorTrackCreatItem(int encoder_id, int item_id, const std::vector< double > &offset)
Add an item to the conveyor queue
int jointOffsetEnable()
Enable joint offset
ARCS_DEPRECATED bool isServoModeEnabled()
Determine whether the servo mode is enabled.
int pathOffsetDisable()
Disable path offset
int setConveyorTrackSyncSeparation(int encoder_id, double distance, double time)
Set conveyor sync separation, used to filter out unwanted signals from the sync switch.
int getQueueSize()
Get the number of enqueued instruction segments (INST), including motion instructions such as moveJoi...
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 weaveEnd()
End weaving
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 pathBufferAppend(const std::string &name, const std::vector< std::vector< double > > &waypoints)
Add waypoints to the path buffer
int enableJointSoftServo(const std::vector< double > &stiffness)
Set joint current loop stiffness coefficient
int getLookAheadSize()
Get look-ahead segment size
int moveLine(const std::vector< double > &pose, double a, double v, double blend_radius, double duration)
Add linear motion
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 exec...
int disableJointSoftServo()
Disable joint current loop stiffness coefficient
int moveProcess(const std::vector< double > &pose, double a, double v, double blend_radius)
Add process motion
int pathBufferFilter(const std::string &name, int order, double fd, double fs)
Joint space path filter
bool pathBufferValid(const std::string &name)
Whether the buffer with the specified name is valid
ARCS_DEPRECATED int setServoMode(bool enable)
Set servo mode Use setServoModeSelect instead
int setCirclePathMode(int mode)
Set circle path mode
int setTimeOptimalEnable(bool enable)
int setServoModeSelect(int mode)
Set servo motion mode
int setConveyorTrackEncoder(int encoder_id, int tick_per_meter)
Set conveyor encoder parameters
int setConveyorTrackSensorOffset(int encoder_id, double offset)
Set the distance from the conveyor teaching position to the sync switch
int speedLine(const std::vector< double > &xd, double a, double t)
Cartesian space velocity following
bool isSupportedTimeOptimal()
Check whether the time optimal algorithm is supported true - supported false - not supported
bool hasItemOnConveyorToTrack(int encoder_id)
Whether there is an item on the conveyor that can be tracked
int conveyorTrackCircle(int encoder_id, const std::vector< double > ¢er, bool rotate_tool)
Circular conveyor tracking
double getDuration(int id)
Get the expected execution duration of the motion segment with the specified ID.
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...
int pathOffsetSet(const std::vector< double > &offset, int type=0)
Set path offset
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...
double getProgress()
Get the execution progress of the current motion instruction segment.
int pathOffsetCoordinate(int ref_coord)
Set the reference coordinate system for offset.
int conveyorTrackClearItems(int encoder_id)
Clear all items in the conveyor queue
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 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 pathOffsetEnable()
Enable path offset
int moveSpiral(const SpiralParameters ¶m, double blend_radius, double v, double a, double t)
Spiral motion
int weaveStart(const std::string ¶ms)
Start weaving: between weaveStart and weaveEnd, moveLine/moveCircle/moveProcess follows params.
int enableVibrationSuppress(const std::vector< double > &omega, const std::vector< double > &zeta, int level)
int pathBufferFree(const std::string &name)
Release path buffer
int setFuturePointSamplePeriod(double sample_time)
Set the sampling interval for points on the future path
int conveyorTrackLine(int encoder_id, const std::vector< double > &direction)
Linear conveyor tracking
double getEqradius()
Get the equivalent radius, in meters.
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...
bool isConveyorTrackSync(int encoder_id)
Determine whether the conveyor and the robot arm have reached relative rest
int setConveyorTrackCompensate(int encoder_id, double comp)
Set the compensation value for conveyor tracking
int setEqradius(double eqradius)
Set the equivalent radius, in meters.
int getExecId()
Get the ID of the currently interpolating motion instruction segment.
int setSpeedFraction(double fraction)
Dynamically adjust the robot's speed and acceleration ratio (0., 1.
int weaveUpdateParameters(const std::string ¶ms)
Update frequency and amplitude during weaving process
int resumeStopJoint(double acc)
Stop motion in joint space (used after moving to a safe position via resumeSpeedJoint following a col...
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...
bool isSpeedFractionCritical()
Whether it is in the speed fraction critical section
int servoJoint(const std::vector< double > &q, double a, double v, double t, double lookahead_time, double gain)
Joint space servo
bool isTimeOptimalEnabled()
Get the time optimal algorithm state: true - enable false - disable
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 isJointSoftServoEnabled()
Determine whether the joint current loop stiffness coefficient is enabled.
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...
int disbaleVibrationSuppress()
std::shared_ptr< MotionControl > MotionControlPtr
PathBufferType
pathBuffer Type
@ PathBuffer_JointSpline
3: Joint B-spline interpolation, at least three pointsDeprecated, use 5 instead, currently it is join...
@ PathBuffer_CubicSpline
2: cubic_spline (recorded trajectory)
@ PathBuffer_TOPPRA
1: toppra time optimal path planning
@ PathBuffer_JointSplineC
4: Joint B-spline interpolation, at least three points, but the input is Cartesian space pose 废弃,建议用6...
@ PathBuffer_JointBSpline
@ PathBuffer_JointBSplineC
6: Joint B-spline interpolation, at least three points, but the input is Cartesian space pose
Circular motion parameters definition.