EASY-ROB™ Application Programming Interface  v9.301
Static Public Member Functions | List of all members
ER_CAPI_MOP_AUTOPATH_SDK Class Reference

Method for collision free path planning. More...

#include <ER_CAPI.H>

Inheritance diagram for ER_CAPI_MOP_AUTOPATH_SDK:
ER_CAPI_MOP ER_CAPI_DEVICES ER_CAPI

Static Public Member Functions

static ER_DllExport char * AutoPathVer (void)
 AutoPath Version. More...
 
static ER_DllExport int AutoPathSetMem (AutoPath_SDK_ConfigurationSpace *apcs)
 allocate memory for AutoPath_SDK_ConfigurationSpace data depending on nConfig
see example AutoPathInit() More...
 
static ER_DllExport int AutoPathInit (AutoPath_SDK_ConfigurationSpace *apcs)
 Initialize AutoPath
Call this functions to setup the autopath configuration space
Parameter apcs defines the complete configuration for all used devices, such as
number of configurations up to AUTOPATH_KIN_DOFS, device handle for each configuration, device axis index, etc.
call AutoPathSetMem() first. More...
 
static ER_DllExport int AutoPathFreeMem (AutoPath_SDK_ConfigurationSpace *apcs)
 free memory of AutoPath_SDK_ConfigurationSpace data
see example AutoPathInit() More...
 
static ER_DllExport int AutoPathTerminate (AutoPath_SDK_ConfigurationSpace *apcs)
 Terminate AutoPath
call AutoPathFreeMem() first, see example AutoPathInit() More...
 
static ER_DllExport int AutoPath_SetCallback_CheckConstraints (BOOL(*ptr_CheckConstraints)(int, void *))
 Defines a callback function to check constraints during AutoPath calculation
The callback function is called with two parameters
Parameter action in Callback_API_CheckConstraints() is a bitwise inclusive OR operator (|) of
AUTOPATH_CHK_CONSTRAINT_UNDEF, AUTOPATH_CHK_CONSTRAINT_START, AUTOPATH_CHK_CONSTRAINT_DEST, AUTOPATH_CHK_CONSTRAINT_COLLISION, AUTOPATH_CHK_CONSTRAINT_SWE, AUTOPATH_CHK_CONSTRAINT_CART_SPACE, AUTOPATH_CHK_CONSTRAINT_ISCFREE
Parameter vapcs in Callback_API_CheckConstraints() defines the autopath configuration space AutoPath_SDK_ConfigurationSpace
see example AutoPathInit() More...
 
static ER_DllExport int SetPoseStart (double *pose_start)
 Set start configuration
Remarks
This pose must be valid - collision free, based on callback function "ptr_CheckConstraints" to check constraints. More...
 
static ER_DllExport int SetPoseEnd (double *pose_end)
 Set end configuration
Remarks
This pose must be valid - collision free, based on callback function "ptr_CheckConstraints" to check constraints. More...
 
static ER_DllExport int FindPath (void)
 Start motion planner, find a collision free path between start and end pose
In each step, the callback function "ptr_CheckConstraints" is called, to check constraints If the target is reached, the callback function is called with action parameter AUTOPATH_STATUS_MP_SUCCESS. More...
 
static ER_DllExport double * GetConfigurationPose (void)
 current configuration pose during FindPath Process return pointer, size nConfig More...
 
static ER_DllExport double * GetStartPose (void)
 Get Start Pose return pointer, size nConfig. More...
 
static ER_DllExport double * GetEndPose (void)
 Get End Pose return pointer, size nConfig. More...
 
static ER_DllExport double * GetAxisConstraintsMin (void)
 Get minimum axis constraints return pointer, size nConfig. More...
 
static ER_DllExport double * GetAxisConstraintsMax (void)
 Get maximum axis constraints return pointer, size nConfig. More...
 
static ER_DllExport int AbortPlanning (void)
 Abort path planning
use GetPlanningStatus() More...
 
static ER_DllExport int GetPlanningStatus (void)
 Get path planning status
The planning status is one of
AUTOPATH_STATUS_MP_IDLE
AUTOPATH_STATUS_MP_RUNNING. More...
 
static ER_DllExport int GetNumberOfWayPoints (void)
 Get number of calculated way points, including start and end pose
call this method after FindPath() succeeded. More...
 
static ER_DllExport int GetWayPointDof (void)
 Get dof of calculated way points. More...
 
static ER_DllExport double * GetWayPoint (int idx)
 Get way point. More...
 
static ER_DllExport int ClearAllWayPoints (void)
 Clear all way points. More...
 
static ER_DllExport int SetAccuracy (UINT accuracy)
 Set accuracy. More...
 
static ER_DllExport int SetAxisConstraints (int axisBit=AUTOPATH_AXIS_BIT_DOF6, int setting=0, double qConstraintMin=0, double qConstraintMax=0)
 Set axis constraints
Parameter setting is a bitwise inclusive OR operator (|) of AUTOPATH_CONSTRAINT_RESET, AUTOPATH_CONSTRAINT_MIN, AUTOPATH_CONSTRAINT_MAX. More...
 
static ER_DllExport int SetAxisPriority (int axisBit, int priority)
 Set axis priority. More...
 
static ER_DllExport int SetAxisEnable (int axisBit, int enable)
 Set axis enable. More...
 
static ER_DllExport int SetParameter (int ap_option, int ap_value)
 Set parameter Paramter ap_option is one of
AUTOPATH_PARAMETER_DYNADJUST
AUTOPATH_PARAMETER_ALGORITHM
AUTOPATH_PARAMETER_NTREES
AUTOPATH_PARAMETER_MIN_NUM_WAYPOINTS
AUTOPATH_PARAMETER_FORCE_DETERM_BEHAVIOR
AUTOPATH_PARAMETER_LIMIT_REVOLUTE_JNT_CSPACE
AUTOPATH_PARAMETER_THREAD_PRIORITY
AUTOPATH_PARAMETER_THREAD_EXECUTION
AUTOPATH_PARAMETER_SEED_VALUE. More...
 
static ER_DllExport int GetParameter (int ap_option)
 Get parameter Paramter ap_option is one of
AUTOPATH_PARAMETER_DYNADJUST
AUTOPATH_PARAMETER_ALGORITHM
AUTOPATH_PARAMETER_NTREES
AUTOPATH_PARAMETER_MIN_NUM_WAYPOINTS
AUTOPATH_PARAMETER_FORCE_DETERM_BEHAVIOR
AUTOPATH_PARAMETER_LIMIT_REVOLUTE_JNT_CSPACE
AUTOPATH_PARAMETER_THREAD_PRIORITY
AUTOPATH_PARAMETER_THREAD_EXECUTION
AUTOPATH_PARAMETER_SEED_VALUE. More...
 
static ER_DllExport int GetResults (int ap_result)
 Get results Paramter ap_result is one of
AUTOPATH_RESULT_CHECKS
AUTOPATH_RESULT_SECONDS
AUTOPATH_RESULT_CPS
AUTOPATH_RESULT_CFREE
AUTOPATH_RESULT_COBSTACLE
AUTOPATH_RESULT_CDENSITY
AUTOPATH_RESULT_DSECONDS
AUTOPATH_RESULT_SEED_VALUE
AUTOPATH_RESULT_QUALITY_INDEX
AUTOPATH_RESULT_QUALITY_INDEX_STD_DEV. More...
 
- Static Public Member Functions inherited from ER_CAPI_MOP
static ER_DllExport void ** inq_ipo_jnt_usr_ptr (void)
 Access user pointer for joint interpolation in er_ipo.dll
This allows the user to allocate individual memory.
EASY-ROB administrates this pointer, related to the current device
See example given for ER_CAPI_ROB_KIN::inq_kin_usr_ptr() More...
 
static ER_DllExport void ** inq_ipo_cp_usr_ptr (void)
 Access user pointer for linear interpolation in er_ipo.dll
This allows the user to allocate individual memory.
EASY-ROB administrates this pointer, related to the current device
See example given for ER_CAPI_ROB_KIN::inq_kin_usr_ptr() More...
 
static ER_DllExport void ** inq_ipo_circ_usr_ptr (void)
 Access user pointer for circular interpolation in er_ipo.dll
This allows the user to allocate individual memory.
EASY-ROB administrates this pointer, related to the current device
See example given for ER_CAPI_ROB_KIN::inq_kin_usr_ptr() More...
 
- Static Public Member Functions inherited from ER_CAPI_DEVICES
static ER_DllExport int data_update_all_devices (void)
 Forces mathematical update for all devices, use before calling chk_limits(::AUX_UPDATE_IDX_COLLISION)
Calculates for alle devices the forward kinematics, all joints coorsys and the devices location w.r.t world. More...
 
static ER_DllExport int inq_Get_n_devices (void)
 Get number of current loaded robots in a workcell. More...
 
static ER_DllExport int inq_Get_c_device_idx (void)
 Get current device idx [1..n_devices]. More...
 
static ER_DllExport ER_UID inq_Get_c_device_uid (void)
 Get current device unique id. More...
 
static ER_DllExport int inq_Set_device_idx (int device_idx)
 Sets current device idx [1..n_devices]. More...
 
static ER_DllExport int inq_Set_device_uid (ER_UID device_uid)
 Sets current device unique id. More...
 
static ER_DllExport int inq_Set_device_name (char *device_name)
 Sets current device by name of the robot
Remarks
A device name must be unique. More...
 
static ER_DllExport int inq_Get_device_idx_by_uid (ER_UID uid)
 Gets device idx by device unique id
if the uid is not valid, -1 is returned. More...
 
static ER_DllExport ER_UID inq_Get_device_uid_by_idx (int idx)
 Get device unique uid by device idx
if idx is not valid, -1 is returned. More...
 
static ER_DllExport char * inq_Get_device_name_by_uid (ER_UID uid)
 Get device name by device unique id
if uid is not valid, NULL is returned. More...
 
static ER_DllExport char * inq_Get_device_name_by_idx (int idx)
 Get device name by device idx [1..n_devices]
if idx is not valid, NULL is returned. More...
 
static ER_DllExport int inq_Get_device_idx_by_name (char *device_name)
 Get device idx by device name
if 'device name' is not valid, -1 is returned. More...
 
static ER_DllExport ER_UID inq_Get_device_uid_by_name (char *device_name)
 Get device unique uid by device name
if 'device name' is not valid, -1 is returned. More...
 
static ER_DllExport int * inq_device_ref_sys_type (void)
 Reference type of the current device
The reference type (attach location) can be one of the following values.
REF_NO_REF, REF_BASE, REF_TOOL, REF_WORLD, REF_WOBJ, REF_TAG, REF_CAD, REF_TIP, REF_JNT, REF_GRAB. More...
 
static ER_DllExport char * inq_device_ref_sys_type_name (void)
 Reference type name of the current device
The reference type name (name of attach location) depends of one of the following values.
REF_NO_REF, REF_BASE, REF_TOOL, REF_WORLD, REF_WOBJ, REF_TAG, REF_CAD, REF_TIP, REF_JNT, REF_GRAB
See also inq_device_ref_sys_type() More...
 
static ER_DllExport int * inq_device_ref_sys_grp (void)
 Reference group of current device
The reference group depends on the attach location.
e.g.: If the cDevice is attacehd to another robot, the returned reference group will ROBOT_GRP
If the cDevice is not attached, the returned reference group will be UNDEF_GRP
The reference group is one of UNDEF_GRP=-1, ROBOT_GRP=0, TOOL_GRP=1, BODY_GRP=2. More...
 
static ER_DllExport ER_UID * inq_device_ref_sys_grp_uid (void)
 Unique ID of reference device/robot
The Unique ID depends on the attach location. More...
 
static ER_DllExport char * inq_device_ref_sys_name (void)
 Reference name of the current device
The reference type name (name of attach location) depends of one of the following values.
REF_NO_REF, REF_BASE, REF_TOOL, REF_WORLD, REF_WOBJ, REF_TAG, REF_CAD, REF_TIP, REF_JNT, REF_GRAB
See also inq_device_ref_sys_type(), inq_device_ref_sys_type_name() Remarks
In case of the reference type is REF_CAD, the name of the reference body is returned. More...
 
static ER_DllExport int * inq_device_ref_sys_jnt_idx (void)
 Reference joint idx of the cDevice, if the reference type is REF_JNT
The index of reference joint is returned
For active joints a positive value > 0 is returned
For passive joints a negative value < 0 is returned
0 is returned if the cDevice is attached to the robot base or if the reference type is not REF_JNT. More...
 
static ER_DllExport int Device_Create (char *robot_name)
 Creates a new device with one rotational axis in z direction. More...
 
static ER_DllExport int Device_ReAttach_by_name (int new_reference_type, char *new_reference_device_name, int new_reference_jnt_idx, bool keep_world_position)
 Attaches the current device to another device
Attaches the current device to another device, given by new_reference_device_name
The attach location can be one of the following values.
REF_NO_REF - no reference system defined
REF_BASE - reference system is robot Base coorsys
REF_TOOL - reference system is robot Tool, Tcp coorsys
REF_WORLD - reference system is World, Inertia coorsys
REF_WOBJ - reference system is path work object
REF_TAG - reference system is tag
REF_CAD - reference system is geometry
REF_TIP - reference system is robot Flange, Tip coorsys
REF_JNT - reference system is a robot Joint
REF_GRAB - reference system is robot Flange, Tip coorsys
Parameter keep_world_position determine if the current device will keep its current world position or will "jump" to the defined attach location
See also Device_ReAttach_by_idx(), Device_ReAttach_by_uid()
Remarks
Make sure that the device to be attached to is current inq_Set_device_idx() More...
 
static ER_DllExport int Device_ReAttach_by_idx (int new_reference_type, int new_reference_device_idx, int new_reference_jnt_idx, bool keep_world_position)
 Attaches the current device to another device
Attaches the current device to another device, given by new_reference_device_idx
The attach location can be one of the following values.
REF_NO_REF - no reference system defined
REF_BASE - reference system is robot Base coorsys
REF_TOOL - reference system is robot Tool, Tcp coorsys
REF_WORLD - reference system is World, Inertia coorsys
REF_WOBJ - reference system is path work object
REF_TAG - reference system is tag
REF_CAD - reference system is geometry
REF_TIP - reference system is robot Flange, Tip coorsys
REF_JNT - reference system is a robot Joint
REF_GRAB - reference system is robot Flange, Tip coorsys
Parameter keep_world_position determine if the current device will keep its current world position or will "jump" to the defined attach location
See also Device_ReAttach_by_name(), Device_ReAttach_by_uid()
Remarks
Make sure that the device to be attached to is current inq_Set_device_idx()
The device idx is within [1..n_devices]. More...
 
static ER_DllExport int Device_ReAttach_by_uid (int new_reference_type, ER_UID new_reference_device_uid, int new_reference_jnt_idx, bool keep_world_position)
 Attaches the current device to another device
Attaches the current device to another device, given by new_reference_device_uid
The attach location can be one of the following values.
REF_NO_REF - no reference system defined
REF_BASE - reference system is robot Base coorsys
REF_TOOL - reference system is robot Tool, Tcp coorsys
REF_WORLD - reference system is World, Inertia coorsys
REF_WOBJ - reference system is path work object
REF_TAG - reference system is tag
REF_CAD - reference system is geometry
REF_TIP - reference system is robot Flange, Tip coorsys
REF_JNT - reference system is a robot Joint
REF_GRAB - reference system is robot Flange, Tip coorsys
Parameter keep_world_position determine if the current device will keep its current world position or will "jump" to the defined attach location
See also Device_ReAttach_by_name(), Device_ReAttach_by_idx()
Remarks
Make sure that the device to be attached to is current inq_Set_device_idx() More...
 
static ER_DllExport int Tool_Device_by_name (char *tool_device_name)
 Sets tool data to the device specified by name
The current device takes over the current tool data of the device tool_device_name
See also Tool_Device_by_idx(), Tool_Device_by_uid()
Remarks
This is not a copy of the tool data.
The new tool data for the current device is calculated by the transformtion from the current device tip to the tcp location of the tool device. More...
 
static ER_DllExport int Tool_Device_by_idx (int tool_device_idx)
 Sets tool data to the device specified by idx
The current device takes over the current tool data of the device tool_device_idx
See also Tool_Device_by_name(), Tool_Device_by_uid()
Remarks
This is not a copy of the tool data.
The new tool data for the current device is calculated by the transformtion from the current device tip to the tcp location of the tool device. More...
 
static ER_DllExport int Tool_Device_by_uid (ER_UID tool_device_uid)
 Sets tool data to the device specified by unique id
The current device takes over the current tool data of the device tool_device_uid
See also Tool_Device_by_name(), Tool_Device_by_idx()
Remarks
This is not a copy of the tool data.
The new tool data for the current device is calculated by the transformtion from the current device tip to the tcp location of the tool device. More...
 
static ER_DllExport int * inq_device_link_ref_sys_type (void)
 Linkage reference type of the current device
The linkage reference type can be one of the following values.
REF_NO_REF if cDevice is not synchrnized
REF_JNT if cDevice is linked by joint to another device
See inq_device_link_ref_sys_grp_uid(), inq_device_link_ref_sys_jnt_link_idx(), Device_Link_by_name() More...
 
static ER_DllExport int * inq_device_sync_ref_sys_type (void)
 Obsolete, use inq_device_link_ref_sys_type() More...
 
static ER_DllExport char * inq_device_link_ref_sys_type_name (void)
 Linkage reference type name of the current device
The linkage reference type name depends on the inq_device_link_ref_sys_type() and can be one of the following values.
REF_NO_REF if cDevice is not synchrnized
REF_JNT if cDevice is linked by joint to another device
See inq_device_link_ref_sys_type() More...
 
static ER_DllExport char * inq_device_sync_ref_sys_type_name (void)
 Obsolete, use inq_device_link_ref_sys_type_name() More...
 
static ER_DllExport ER_UID * inq_device_link_ref_sys_grp_uid (void)
 Linkage Unique ID of the reference device current device
The Unique ID depends on the linkage reference type, which is REF_JNT if linked. More...
 
static ER_DllExport ER_UID * inq_device_sync_ref_sys_grp_uid (void)
 Obsolete, use inq_device_link_ref_sys_grp_uid() More...
 
static ER_DllExport int * inq_device_link_ref_sys_jnt_link_idx (void)
 Linkage joint index vector, if the linkage reference type is REF_JNT and valid unique ID exist
The joint index vector contains for each active Jnt a linkage index
This linkage index is

0 if linked with an active joint of a sync. ref. device

< 0 if linked with a passive joint of a sync. ref. device
= 0 if no linkage
See inq_device_link_ref_sys_type(), inq_device_link_ref_sys_grp_uid. More...

 
static ER_DllExport int * inq_device_sync_ref_sys_jnt_sync_idx (void)
 Obsolete, use inq_device_link_ref_sys_jnt_link_idx() More...
 
static ER_DllExport int Device_Link_by_name (int new_reference_type, char *new_reference_device_name=NULL, int *new_reference_jnt_link_idx=NULL)
 Link current device to another device by name
new_reference_type one of REF_NO_REF=0 or REF_JNT=9
new_reference_device_name name of device to synchonize with
new_reference_jnt_sync_idx reference joint idxs for each Jnt, if new_reference_type is REF_JNT
See Device_Link_by_idx(), Device_Link_by_uid() More...
 
static ER_DllExport int Device_Sync_by_name (int new_reference_type, char *new_reference_device_name=NULL, int *new_reference_jnt_link_idx=NULL)
 Obsolete, use Device_Link_by_name() More...
 
static ER_DllExport int Device_Link_by_idx (int new_reference_type, int new_reference_device_idx=0, int *new_reference_jnt_link_idx=NULL)
 Link current device to another device by idx
new_reference_type one of REF_NO_REF=0 or REF_JNT=9
new_reference_device_idx idx of device to synchonize with, [1..n_devices]
new_reference_jnt_sync_idx reference joint idxs for each Jnt, if new_reference_type is REF_JNT See Device_Link_by_name(), Device_Link_by_uid() More...
 
static ER_DllExport int Device_Sync_by_idx (int new_reference_type, int new_reference_device_idx=0, int *new_reference_jnt_link_idx=NULL)
 Obsolete, use Device_Link_by_idx() More...
 
static ER_DllExport int Device_Link_by_uid (int new_reference_type, ER_UID new_reference_device_uid=0, int *new_reference_jnt_link_idx=NULL)
 Link current device to another device by uid
new_reference_type one of REF_NO_REF=0 or REF_JNT=9
new_reference_device_uid uid of device to synchonize with
new_reference_jnt_sync_idx reference joint idxs for each Jnt, if new_reference_type is REF_JNT See Device_Link_by_name(), Device_Link_by_idx() More...
 
static ER_DllExport int Device_Sync_by_uid (int new_reference_type, ER_UID new_reference_device_uid=0, int *new_reference_jnt_link_idx=NULL)
 Obsolete, use Device_Link_by_uid() More...
 

Additional Inherited Members

- Static Public Attributes inherited from ER_CAPI_MOP
static ER_CAPI_MOP_DATA er_capi_mop_data
 Method class for start-, target data, motion time, etc. More...
 
static ER_CAPI_MOP_PATH er_capi_mop_path
 Method class for path specifications, motion type (PTP, LIN, CIRC), speeds, acceleration, waiting time, etc. More...
 
static ER_CAPI_MOP_PREP er_capi_mop_prep
 Method class for trajectory planning (preparation) More...
 
static ER_CAPI_MOP_EXEC er_capi_mop_exec
 Method class for trajectory execution. More...
 
static ER_CAPI_MOP_AUTOPATH er_capi_mop_autopath
 Method class for collision free motion planning. More...
 
static ER_CAPI_MOP_AUTOPATH_SDK er_capi_mop_autopath_sdk
 Method class for collision free motion planning. More...
 
- Static Public Attributes inherited from ER_CAPI_DEVICES
static ER_CAPI_ROB er_capi_rob
 Method class kinematics and transformations. More...
 
static ER_CAPI_MOP er_capi_mop
 Method class for trajectory planning and -execution. More...
 
- Static Public Attributes inherited from ER_CAPI
static ER_CAPI_USER_IO er_capi_user_io
 Method class for interaction with EASY-ROB. More...
 
static ER_CAPI_DEVICES er_capi_devices
 Method class to create, attach, update devices, for kinematics calculations and for trajectory planning and -execution. More...
 
static ER_CAPI_SIM er_capi_sim
 Method class for simulation settings. More...
 
static ER_CAPI_TARGETS er_capi_targets
 Method class for paths and tags. More...
 
static ER_CAPI_CAD er_capi_cad
 Method class for for 3D CAD Data import and -export, changing attributes and positions. More...
 
static ER_CAPI_SYS er_capi_sys
 Method class for mathematical calculations, simulation status, units. More...
 

Detailed Description

Method for collision free path planning.

Member Function Documentation

◆ AbortPlanning()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::AbortPlanning ( void  )
static

Abort path planning
use GetPlanningStatus()

Return values
0- AUTOPATH_OK
1- AUTOPATH_ERROR

◆ AutoPath_SetCallback_CheckConstraints()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::AutoPath_SetCallback_CheckConstraints ( BOOL(*)(int, void *)  ptr_CheckConstraints)
static

Defines a callback function to check constraints during AutoPath calculation
The callback function is called with two parameters
Parameter action in Callback_API_CheckConstraints() is a bitwise inclusive OR operator (|) of
AUTOPATH_CHK_CONSTRAINT_UNDEF, AUTOPATH_CHK_CONSTRAINT_START, AUTOPATH_CHK_CONSTRAINT_DEST, AUTOPATH_CHK_CONSTRAINT_COLLISION, AUTOPATH_CHK_CONSTRAINT_SWE, AUTOPATH_CHK_CONSTRAINT_CART_SPACE, AUTOPATH_CHK_CONSTRAINT_ISCFREE
Parameter vapcs in Callback_API_CheckConstraints() defines the autopath configuration space AutoPath_SDK_ConfigurationSpace
see example AutoPathInit()

// Example:
// Callback function
static BOOL Callback_API_CheckConstraints_apcs(int action, void*vapcs)
// Return
// TRUE - constraints violated
// FALSE - constraints fulfilled
{
BOOL do_chk=FALSE;
switch (action) {
case AUTOPATH_CHK_CONSTRAINT_START: // SetPoseStart()
case AUTOPATH_CHK_CONSTRAINT_DEST: // SetPoseEnd()
do_chk=TRUE;
break;
// target reached
break;
}
...
if (do_chk)
{
double* currentConfiguration = er_mop_autopath_sdk.GetConfigurationPose();
result = Check Constraints_in_HostApp(...)
}
...
return result; // true - violated, false - ok
}
...
AutoPath_SDK_ConfigurationSpace *papcs = new AutoPath_SDK_ConfigurationSpace;
...
er_mop_autopath_sdk.AutoPathInit(papcs);
...
// Set callback function pointer
er_mop_autopath_sdk.AutoPath_SetCallback_CheckConstraints(Callback_API_CheckConstraints_apcs);
...
// do autopath calculation ....
erk_autoPath.FindPath();
// get way points
...
// Reset callback function pointer
er_mop_autopath_sdk.AutoPath_SetCallback_CheckConstraints(NULL);
...
Parameters
[in]ptr_CheckConstraints(int) callback function pointer
Return values
0- Ok
1- Error

◆ AutoPathFreeMem()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::AutoPathFreeMem ( AutoPath_SDK_ConfigurationSpace apcs)
static

free memory of AutoPath_SDK_ConfigurationSpace data
see example AutoPathInit()

Parameters
[in]apcsautopath configuration space AutoPath_SDK_ConfigurationSpace
Return values
0- AUTOPATH_OK - OK
1- AUTOPATH_ERROR - Error, AutoPath initialization failed

◆ AutoPathInit()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::AutoPathInit ( AutoPath_SDK_ConfigurationSpace apcs)
static

Initialize AutoPath
Call this functions to setup the autopath configuration space
Parameter apcs defines the complete configuration for all used devices, such as
number of configurations up to AUTOPATH_KIN_DOFS, device handle for each configuration, device axis index, etc.
call AutoPathSetMem() first.

// Example:
int nConfig = 6;
papcs->initialized = 0;
papcs->nConfig = nConfig;
papcs->deviceHandle = NULL;
papcs->deviceAxisIdx = NULL;
papcs->AxisEnable = NULL;
papcs->AxisPriority = NULL;
papcs->AxisRotTrans = NULL;
papcs->AxisType = NULL;
papcs->ConstraintMin = NULL;
papcs->ConstraintMax = NULL;
papcs->SpeedWeight = NULL;
papcs->DistanceWeight = NULL;
papcs->UsrData = NULL;
...
er_mop_autopath_sdk.AutoPathSetMem(papcs); // allocate memory depending on nConfig
...
// set AutoPath_SDK_ConfigurationSpace data for each configuration
for (int i=0;i<papcs->nConfig;++i)
{
papcs->deviceHandle[i] = er_hnd[i];
papcs->deviceAxisIdx[i] = i;
papcs->AxisEnable[i] = 1;
papcs->AxisPriority[i] = 50;
papcs->AxisType[i] = AUTOPATH_AXIS_TYPE_ROBOT; // Robot
papcs->ConstraintMin[i] = ...;
papcs->ConstraintMax[i] = ...;
papcs->SpeedWeight[i] = 1;
papcs->DistanceWeight[i]= 1;
}
er_mop_autopath_sdk.AutoPathInit(papcs); // Initialize AutoPath
...
// Set callback function pointer
er_mop_autopath_sdk.AutoPath_SetCallback_CheckConstraints(Callback_API_CheckConstraints_apcs);
...
// define additional settings
...
// define start and destination
// -> SetPoseStart(), SetPoseEnd()
// do autopath calculation
// -> FindPath();
// get results
// -> GetNumberOfWayPoints(), GetWayPoint(), GetResults()
...
// Verify results, move along all waypoints
...
// Clear all WayPoints
// -> ClearAllWayPoints()
...
// Reset callback function pointer
er_mop_autopath_sdk.AutoPath_SetCallback_CheckConstraints(NULL);
...
// Terminate AutoPath
er_mop_autopath_sdk.AutoPathFreeMem(papcs); // free memory of AutoPath_SDK_ConfigurationSpace data
delete papcs;
papcs= NULL;
er_mop_autopath_sdk.AutoPathTerminate(papcs); // Terminate AutoPath
...
Parameters
[in]apcsautopath configuration space AutoPath_SDK_ConfigurationSpace
Return values
0- AUTOPATH_OK - OK
1- AUTOPATH_ERROR - Error, AutoPath initialization failed
2- AUTOPATH_INVALID_LICENSE - Error, AutoPath not licensed

◆ AutoPathSetMem()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::AutoPathSetMem ( AutoPath_SDK_ConfigurationSpace apcs)
static

allocate memory for AutoPath_SDK_ConfigurationSpace data depending on nConfig
see example AutoPathInit()

Parameters
[in]apcsautopath configuration space AutoPath_SDK_ConfigurationSpace
Return values
0- AUTOPATH_OK - OK
1- AUTOPATH_ERROR - Error, AutoPath initialization failed

◆ AutoPathTerminate()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::AutoPathTerminate ( AutoPath_SDK_ConfigurationSpace apcs)
static

Terminate AutoPath
call AutoPathFreeMem() first, see example AutoPathInit()

Parameters
[in]apcsautopath configuration space AutoPath_SDK_ConfigurationSpace
Return values
0- AUTOPATH_OK - OK
1- AUTOPATH_ERROR - Error, AutoPath initialization failed

◆ AutoPathVer()

static ER_DllExport char* ER_CAPI_MOP_AUTOPATH_SDK::AutoPathVer ( void  )
static

AutoPath Version.

Return values
versionAutoPath version number

◆ ClearAllWayPoints()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::ClearAllWayPoints ( void  )
static

Clear all way points.

Return values
0- AUTOPATH_OK
1- AUTOPATH_ERROR

◆ FindPath()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::FindPath ( void  )
static

Start motion planner, find a collision free path between start and end pose
In each step, the callback function "ptr_CheckConstraints" is called, to check constraints If the target is reached, the callback function is called with action parameter AUTOPATH_STATUS_MP_SUCCESS.

Return values
0- AUTOPATH_OK
1- AUTOPATH_ERROR

◆ GetAxisConstraintsMax()

static ER_DllExport double* ER_CAPI_MOP_AUTOPATH_SDK::GetAxisConstraintsMax ( void  )
static

Get maximum axis constraints return pointer, size nConfig.

◆ GetAxisConstraintsMin()

static ER_DllExport double* ER_CAPI_MOP_AUTOPATH_SDK::GetAxisConstraintsMin ( void  )
static

Get minimum axis constraints return pointer, size nConfig.

◆ GetConfigurationPose()

static ER_DllExport double* ER_CAPI_MOP_AUTOPATH_SDK::GetConfigurationPose ( void  )
static

current configuration pose during FindPath Process return pointer, size nConfig

◆ GetEndPose()

static ER_DllExport double* ER_CAPI_MOP_AUTOPATH_SDK::GetEndPose ( void  )
static

Get End Pose return pointer, size nConfig.

◆ GetNumberOfWayPoints()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::GetNumberOfWayPoints ( void  )
static

Get number of calculated way points, including start and end pose
call this method after FindPath() succeeded.

Return values
numberof way points

◆ GetParameter()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::GetParameter ( int  ap_option)
static

◆ GetPlanningStatus()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::GetPlanningStatus ( void  )
static

Get path planning status
The planning status is one of
AUTOPATH_STATUS_MP_IDLE
AUTOPATH_STATUS_MP_RUNNING.

Return values
planningstatus

◆ GetResults()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::GetResults ( int  ap_result)
static

Get results Paramter ap_result is one of
AUTOPATH_RESULT_CHECKS
AUTOPATH_RESULT_SECONDS
AUTOPATH_RESULT_CPS
AUTOPATH_RESULT_CFREE
AUTOPATH_RESULT_COBSTACLE
AUTOPATH_RESULT_CDENSITY
AUTOPATH_RESULT_DSECONDS
AUTOPATH_RESULT_SEED_VALUE
AUTOPATH_RESULT_QUALITY_INDEX
AUTOPATH_RESULT_QUALITY_INDEX_STD_DEV.

// Example:
...
char *ap_result_s[] = {"?","Checks","Seconds","CpS","CFree","CObstacle","CDensity","dSeconds","?","?","?"};
{
int ap_result=i;
int ap_value = er_mop_autopath_sdk.GetResults(ap_result);
_info_line_msg(0," GetResults(%s) = %d",ap_result_s[ap_result],ap_value);
}
int seed_value = er_mop_autopath_sdk.GetResults(AUTOPATH_RESULT_SEED_VALUE); // Random starting seed value to influence behavior
int quality_index = er_mop_autopath_sdk.GetResults(AUTOPATH_RESULT_QUALITY_INDEX); // Quality Index based on calculated way points
int quality_index_std_dev = er_mop_autopath_sdk.GetResults(AUTOPATH_RESULT_QUALITY_INDEX_STD_DEV); // Quality Index Standard Deviation, based on calculated way points
_info_line_msg(0," Seed_Value = %d Thread_Exec %s",seed_value,thread_exec?"Yes":"No");
...
Parameters
[in]ap_result- autopath result
Return values
0- AUTOPATH_OK
1- AUTOPATH_ERROR

◆ GetStartPose()

static ER_DllExport double* ER_CAPI_MOP_AUTOPATH_SDK::GetStartPose ( void  )
static

Get Start Pose return pointer, size nConfig.

◆ GetWayPoint()

static ER_DllExport double* ER_CAPI_MOP_AUTOPATH_SDK::GetWayPoint ( int  idx)
static

Get way point.

Parameters
[in]idx[0.. number of way points-1]
Return values
pointer

◆ GetWayPointDof()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::GetWayPointDof ( void  )
static

Get dof of calculated way points.

Return values
dofof way points

◆ SetAccuracy()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::SetAccuracy ( UINT  accuracy)
static

Set accuracy.

Parameters
[in]accuracy[1..100]
Return values
0- AUTOPATH_OK
1- AUTOPATH_ERROR

◆ SetAxisConstraints()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::SetAxisConstraints ( int  axisBit = AUTOPATH_AXIS_BIT_DOF6,
int  setting = 0,
double  qConstraintMin = 0,
double  qConstraintMax = 0 
)
static

Set axis constraints
Parameter setting is a bitwise inclusive OR operator (|) of AUTOPATH_CONSTRAINT_RESET, AUTOPATH_CONSTRAINT_MIN, AUTOPATH_CONSTRAINT_MAX.

Parameters
[in]axisBit- a bitwise inclusive OR operator (|) of AUTOPATH_AXIS_BIT_1 ... AUTOPATH_AXIS_BIT_24
[in]setting
[in]qConstraintMin- size of nConfig
[in]qConstraintMax- size of nConfig
Return values
0- AUTOPATH_OK
1- AUTOPATH_ERROR

◆ SetAxisEnable()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::SetAxisEnable ( int  axisBit,
int  enable 
)
static

Set axis enable.

Return values
0- AUTOPATH_OK
1- AUTOPATH_ERROR

◆ SetAxisPriority()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::SetAxisPriority ( int  axisBit,
int  priority 
)
static

Set axis priority.

Parameters
[in]axisBit
[in]priority[1..50..100]
Return values
0- AUTOPATH_OK
1- AUTOPATH_ERROR

◆ SetParameter()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::SetParameter ( int  ap_option,
int  ap_value 
)
static

◆ SetPoseEnd()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::SetPoseEnd ( double *  pose_end)
static

Set end configuration
Remarks
This pose must be valid - collision free, based on callback function "ptr_CheckConstraints" to check constraints.

Parameters
[in]pose_endpointer to start pose, maximum size AUTOPATH_KIN_DOFS
Return values
0- AUTOPATH_OK
1- AUTOPATH_ERROR

◆ SetPoseStart()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH_SDK::SetPoseStart ( double *  pose_start)
static

Set start configuration
Remarks
This pose must be valid - collision free, based on callback function "ptr_CheckConstraints" to check constraints.

Parameters
[in]pose_startpointer to start pose, maximum size AUTOPATH_KIN_DOFS
Return values
0- AUTOPATH_OK
1- AUTOPATH_ERROR

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