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

Method class for collision free path planning. More...

#include <ER_CAPI.H>

Inheritance diagram for ER_CAPI_MOP_AUTOPATH:
ER_CAPI_MOP ER_CAPI_DEVICES ER_CAPI

Static Public Member Functions

static ER_DllExport char * AutoPathVer (void)
 AutoPath Version. More...
 
static ER_DllExport void * inq_AutoPathDlg_Hwnd (void)
 Handle form AutoPath Dialog
. More...
 
static ER_DllExport int AutoPath_SetCallback_CheckConstraints (BOOL(*ptr_CheckConstraints)(int))
 Defines a callback function to check constraints during AutoPath calculation
Parameter action in Callback_API_CheckConstraints(int action) is a bitwise inclusive OR operator (|) of
AUTOPATH_CHK_CONSTRAINT_UNDEF, AUTOPATH_CHK_CONSTRAINT_START_DEST, AUTOPATH_CHK_CONSTRAINT_UPDT_DEVICES, AUTOPATH_CHK_CONSTRAINT_COLLISION, AUTOPATH_CHK_CONSTRAINT_SWE, AUTOPATH_CHK_CONSTRAINT_CART_SPACE, AUTOPATH_CHK_CONSTRAINT_ISCFREE_1, AUTOPATH_CHK_CONSTRAINT_ISCFREE_2
Define AutoPath_SetCallback_CheckConstraints() to verify constraints during AutoPath calculation
Remarks
Unsetting this callback function will use the internal constraint checking. More...
 
static ER_DllExport int SetDlgParameter (int ap_dlg_option, int ap_dlg_value)
 Set Autopath dialog parameter
Parameter ap_dlg_option is one of AUTOPATH_DLG_PARAMETER_API_CONTROL,. More...
 
static ER_DllExport int GetDlgParameter (int ap_dlg_option)
 Get Autopath dialog parameter
Parameter ap_dlg_option is one of AUTOPATH_DLG_PARAMETER_API_CONTROL,. More...
 
static ER_DllExport int AutoPathEnd (void)
 AutoPath Termination
Destroys Instance ... to be defined, not implemented yet, instance is always active. More...
 
static ER_DllExport int SetPoseStart (int nConfig, float *pose_start)
 Set specified robot joint location as start pose
Remarks
This pose must be collision free, based on current collision settings. More...
 
static ER_DllExport int SetPoseEnd (int nConfig, float *pose_end)
 Set specified robot joint location as end pose
Remarks
This pose must be collision free, based on current collision settings. More...
 
static ER_DllExport float * SetStartPose (void)
 Set current robot joint location as start pose
Remarks
This pose must be collision free, based on current collision settings. More...
 
static ER_DllExport float * SetEndPose (void)
 Set current robot joint location as end pose
Remarks
This pose must be collision free, based on current collision settings. More...
 
static ER_DllExport int FindPath (void)
 Start calculating a collision free path between start- and end pose
Remarks
A valid start and end pose must be set in advance,
see SetStartPose() and SetEndPose() More...
 
static ER_DllExport float * GetConfigurationPose (void)
 Get current configuration pose
Remarks
Access the current configuration pose before checking the constraints. More...
 
static ER_DllExport float * GetStartPose (void)
 Get current robot joint location start pose
Remarks
This pose must be set before, use SetStartPose() More...
 
static ER_DllExport float * GetEndPose (void)
 Get current robot joint location end pose
Remarks
This pose must be set before, use SetEndPose() More...
 
static ER_DllExport float * GetAxisConstraintsMin (void)
 Get axis constraints min. values
Remarks
Axis constraints can be set before, using SetAxisConstraints() More...
 
static ER_DllExport float * GetAxisConstraintsMax (void)
 Get axis constraints max. values
Remarks
Axis constraints can be set before, using SetAxisConstraints() More...
 
static ER_DllExport int AbortPlanning (void)
 Abort path planning. More...
 
static ER_DllExport int GetPlanningStatus (void)
 Get path planning status. More...
 
static ER_DllExport int GetNumberOfWayPoints (void)
 Get number of calculated way points
See GetWayPointDof(), GetWayPointDof() More...
 
static ER_DllExport int GetWayPointDof (void)
 Get dof or number of values for each way point
Remarks
dof coincides normally with the number of robot joints
See GetNumberOfWayPoints(), GetWayPointDof() More...
 
static ER_DllExport int GetWayPointConfiguration (int idx)
 Get calculatated configuration idx in way point
See GetNumberOfWayPoints(), GetWayPointDof(), GetWayPoint() More...
 
static ER_DllExport float * GetWayPoint (int idx)
 Get calculatated way point
See GetNumberOfWayPoints(), GetWayPointDof(), GetWayPointConfiguration() More...
 
static ER_DllExport int ClearAllWayPoints (void)
 Clears all calculated way points
See GetNumberOfWayPoints(), GetWayPointDof(), GetWayPoint(), GetWayPointConfiguration() More...
 
static ER_DllExport UINT * Accuracy (void)
 AutoPath accuracy
Valid *accuracy values are in [1..100] Remarks
Disable AUTOPATH_PARAMETER_DYNADJUST so that accuracy has an effect. More...
 
static ER_DllExport int SetAxisConstraints (int axisBit=0x3FF, int setting=0, float qConstraintMin=0, float qConstraintMax=0)
 Set axis constraints
Parameter setting is a bitwise inclusive OR operator (|) of
AUTOPATH_CONSTRAINT_RESET, AUTOPATH_CONSTRAINT_MIN, AUTOPATH_CONSTRAINT_MAX Remarks
An Error occured if qConstraintMin or qConstraintMax exceed the nominal travel ranges
Set axisBit=0 and setting=AUTOPATH_CONSTRAINT_RESET to reset constraints to min. and max. travel ranges
axisBit=0x1 will set the constraints for the 1st joint
axisBit=0x2 will set the constraints for the 2nd joint
axisBit=0x4 will set the constraints for the 3rd joint
axisBit=0x8 will set the constraints for the 4th joint
axisBit=0x10 will set the constraints for the 5th joint
axisBit=0x20 will set the constraints for the 6th joint and so on ... More...
 
static ER_DllExport int SetAxisPriority (int axisBit, int priority)
 Set axis priority
Parameter priority is in [1..99]. More...
 
static ER_DllExport int SetAxisEnable (int axisBit, int enable)
 Set axis enable
Parameter enable is 1 for enable or 0 for disable. More...
 
static ER_DllExport int SetParameter (int ap_option, int ap_value)
 Set Autopath calculation parameter
Parameter 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_OUTPUT_SETTINGS. More...
 
static ER_DllExport int GetParameter (int ap_option)
 Get Autopath calculation parameter
Parameter 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_OUTPUT_SETTINGS. More...
 
static ER_DllExport int GetResults (int ap_result)
 Get Autopath Result
Parameter 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. 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 class for collision free path planning.

Member Function Documentation

◆ AbortPlanning()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::AbortPlanning ( void  )
static

Abort path planning.

Return values
0- OK
1- Error, no calculation running

◆ Accuracy()

static ER_DllExport UINT* ER_CAPI_MOP_AUTOPATH::Accuracy ( void  )
static

AutoPath accuracy
Valid *accuracy values are in [1..100] Remarks
Disable AUTOPATH_PARAMETER_DYNADJUST so that accuracy has an effect.

// Example:
...
UINT *accuracy = er_mop_autopath.Accuracy();
_info_line_msg(0," Accuracy() %s",accuracy?"Ok":"Error");
if (accuracy)
{
*accuracy = 49;
_info_line_msg(0,"accuracy= %u",*accuracy);
}
...
Return values
pointerto accuracy value
NULL- Error

◆ AutoPath_SetCallback_CheckConstraints()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::AutoPath_SetCallback_CheckConstraints ( BOOL(*)(int)  ptr_CheckConstraints)
static

Defines a callback function to check constraints during AutoPath calculation
Parameter action in Callback_API_CheckConstraints(int action) is a bitwise inclusive OR operator (|) of
AUTOPATH_CHK_CONSTRAINT_UNDEF, AUTOPATH_CHK_CONSTRAINT_START_DEST, AUTOPATH_CHK_CONSTRAINT_UPDT_DEVICES, AUTOPATH_CHK_CONSTRAINT_COLLISION, AUTOPATH_CHK_CONSTRAINT_SWE, AUTOPATH_CHK_CONSTRAINT_CART_SPACE, AUTOPATH_CHK_CONSTRAINT_ISCFREE_1, AUTOPATH_CHK_CONSTRAINT_ISCFREE_2
Define AutoPath_SetCallback_CheckConstraints() to verify constraints during AutoPath calculation
Remarks
Unsetting this callback function will use the internal constraint checking.

// Example:
...
// Declaration of a callback functions for progress messages
static BOOL Callback_API_CheckConstraints(int action)
// Return
// TRUE - constraints violated
// FALSE - constraints fulfilled
{
BOOL do_chk=FALSE;
{
er_user_io_dialog._info_line_msg(0,"UserDLL -> Callback_API_CheckConstraints() %s","UNDEF");
do_chk=FALSE;
}
{
do_chk=TRUE;
}
{
do_chk=TRUE;
}
{
char s[MAXSTR];
sprintf(s,"action = %d = 0x%X",action,action);
er_user_io_dialog._info_line_msg(0,"UserDLL -> Callback_API_CheckConstraints() = %s %s",s,"START_DEST" );
do_chk=TRUE;
}
if (do_chk)
{
BOOL chk=FALSE;
if (!chk && (action & AUTOPATH_CHK_CONSTRAINT_CART_SPACE))
{
chk=FALSE;
}
if (!chk && (action & AUTOPATH_CHK_CONSTRAINT_SWE))
if (!chk && (action & AUTOPATH_CHK_CONSTRAINT_COLLISION))
return chk ? TRUE : FALSE;
}
return TRUE;
}
...
// Set callback function pointer
er_mop_autopath.AutoPath_SetCallback_CheckConstraints(Callback_API_CheckConstraints);
...
// Reset callback function pointer
er_mop_autopath.AutoPath_SetCallback_CheckConstraints(NULL);
...
Parameters
[in]ptr_CheckConstraints(int) callback function pointer
Return values
0- Ok
1- Error

◆ AutoPathEnd()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::AutoPathEnd ( void  )
static

AutoPath Termination
Destroys Instance ... to be defined, not implemented yet, instance is always active.

Return values
0- OK
1- Error

◆ AutoPathVer()

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

AutoPath Version.

Return values
versionAutoPath version number

◆ ClearAllWayPoints()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::ClearAllWayPoints ( void  )
static

Clears all calculated way points
See GetNumberOfWayPoints(), GetWayPointDof(), GetWayPoint(), GetWayPointConfiguration()

Return values
1- Error, no way points to clear
0- Ok

◆ FindPath()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::FindPath ( void  )
static

Start calculating a collision free path between start- and end pose
Remarks
A valid start and end pose must be set in advance,
see SetStartPose() and SetEndPose()

Return values
0- OK
1- Error

◆ GetAxisConstraintsMax()

static ER_DllExport float* ER_CAPI_MOP_AUTOPATH::GetAxisConstraintsMax ( void  )
static

Get axis constraints max. values
Remarks
Axis constraints can be set before, using SetAxisConstraints()

// Example:
...
float *q;
if (q) _info_line_msg_q(0,"GetAxisConstraintsMax()",q); else _info_line_msg(0,"GetAxisConstraintsMax() not set or invalid");
...
Return values
pointerto end pose
NULL- Error, invalid axis constraint or not set

◆ GetAxisConstraintsMin()

static ER_DllExport float* ER_CAPI_MOP_AUTOPATH::GetAxisConstraintsMin ( void  )
static

Get axis constraints min. values
Remarks
Axis constraints can be set before, using SetAxisConstraints()

// Example:
...
float *q;
if (q) _info_line_msg_q(0,"GetAxisConstraintsMin()",q); else _info_line_msg(0,"GetAxisConstraintsMin() not set or invalid");
...
Return values
pointerto end pose
NULL- Error, invalid axis constraint or not set

◆ GetConfigurationPose()

static ER_DllExport float* ER_CAPI_MOP_AUTOPATH::GetConfigurationPose ( void  )
static

Get current configuration pose
Remarks
Access the current configuration pose before checking the constraints.

Return values
pointerto current configuration pose
NULL- Error, pose is not valid or not set

◆ GetDlgParameter()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::GetDlgParameter ( int  ap_dlg_option)
static

Get Autopath dialog parameter
Parameter ap_dlg_option is one of AUTOPATH_DLG_PARAMETER_API_CONTROL,.

AUTOPATH_DLG_PARAMETER_SHOW_WINDOW,

AUTOPATH_DLG_PARAMETER_DISABLE_MSG

Parameters
[in]ap_dlg_optionautopath dialog parameter
Return values
-1- Error
ap_dlg_value- depending on paramter ap_dlg_option

◆ GetEndPose()

static ER_DllExport float* ER_CAPI_MOP_AUTOPATH::GetEndPose ( void  )
static

Get current robot joint location end pose
Remarks
This pose must be set before, use SetEndPose()

// Example:
...
float *q;
if (q) _info_line_msg_q(0,"GetEndPose()",q); else _info_line_msg(0,"GetEndPose() not set or invalid");
...
Return values
pointerto end pose
NULL- Error, pose is not valid or not set

◆ GetNumberOfWayPoints()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::GetNumberOfWayPoints ( void  )
static

Get number of calculated way points
See GetWayPointDof(), GetWayPointDof()

Return values
-1- Error
n- Number of Way Points

◆ GetParameter()

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

Get Autopath calculation parameter
Parameter 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_OUTPUT_SETTINGS.

Parameters
[in]ap_optionautopath parameter of required value
Return values
-1- Error
ap_value- depending on parameter ap_option

◆ GetPlanningStatus()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::GetPlanningStatus ( void  )
static

Get path planning status.

Return values
-1- Error
0- OK, no calculation running
1- Calculating
2- Calculating done with success
3- Calculating aborted

◆ GetResults()

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

Get Autopath Result
Parameter 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.

Parameters
[in]ap_result- requested result value
Return values
-1- Error
requestedvalue - depending on parameter ap_result

◆ GetStartPose()

static ER_DllExport float* ER_CAPI_MOP_AUTOPATH::GetStartPose ( void  )
static

Get current robot joint location start pose
Remarks
This pose must be set before, use SetStartPose()

// Example:
...
float *q;
if (q) _info_line_msg_q(0,"GetStartPose()",q); else _info_line_msg(0,"GetStartPose() not set or invalid");
...
Return values
pointerto start pose
NULL- Error, pose is not valid or not set

◆ GetWayPoint()

static ER_DllExport float* ER_CAPI_MOP_AUTOPATH::GetWayPoint ( int  idx)
static

Get calculatated way point
See GetNumberOfWayPoints(), GetWayPointDof(), GetWayPointConfiguration()

Parameters
[in]idxway point index, zero based
Return values
NULL- Error
pointerof float vector with dof data

◆ GetWayPointConfiguration()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::GetWayPointConfiguration ( int  idx)
static

Get calculatated configuration idx in way point
See GetNumberOfWayPoints(), GetWayPointDof(), GetWayPoint()

Parameters
[in]idxway point index, zero based
Return values
0- Error
>0- valid configuration idx

◆ GetWayPointDof()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::GetWayPointDof ( void  )
static

Get dof or number of values for each way point
Remarks
dof coincides normally with the number of robot joints
See GetNumberOfWayPoints(), GetWayPointDof()

Return values
-1- Error
numberof values, dof

◆ inq_AutoPathDlg_Hwnd()

static ER_DllExport void* ER_CAPI_MOP_AUTOPATH::inq_AutoPathDlg_Hwnd ( void  )
static

Handle form AutoPath Dialog
.

Return values
handle- OK
NULL- Error

◆ SetAxisConstraints()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::SetAxisConstraints ( int  axisBit = 0x3FF,
int  setting = 0,
float  qConstraintMin = 0,
float  qConstraintMax = 0 
)
static

Set axis constraints
Parameter setting is a bitwise inclusive OR operator (|) of
AUTOPATH_CONSTRAINT_RESET, AUTOPATH_CONSTRAINT_MIN, AUTOPATH_CONSTRAINT_MAX Remarks
An Error occured if qConstraintMin or qConstraintMax exceed the nominal travel ranges
Set axisBit=0 and setting=AUTOPATH_CONSTRAINT_RESET to reset constraints to min. and max. travel ranges
axisBit=0x1 will set the constraints for the 1st joint
axisBit=0x2 will set the constraints for the 2nd joint
axisBit=0x4 will set the constraints for the 3rd joint
axisBit=0x8 will set the constraints for the 4th joint
axisBit=0x10 will set the constraints for the 5th joint
axisBit=0x20 will set the constraints for the 6th joint and so on ...

// Example:
...
float qCMin[] = { 0.05f, 0.05f, 0.05f,-180.0f*fRAD, 0.0f*fRAD,-180.0f*fRAD};
float qCMax[] = { 0.80f, 0.80f, 0.20f, 180.0f*fRAD, 90.0f*fRAD, 180.0f*fRAD};
axisBit = 1;
for (int i=0;i<(int)er_rob_kin.inq_num_active_jnts();i++)
{
res=er_mop_autopath.SetAxisConstraints(axisBit,setting, qCMin[i],qCMax[i]); // Axis 1..6
_info_line_msg(0,"SetAxisConstraints(0x%X) %s",axisBit,res?"Error":"Ok");
axisBit = axisBit << 1;
}
...
Parameters
[in]axisBitaxis bit field
[in]setting0x0-Reset to nom. values, 0x1-Set Min value, 0x2-Set Max value
[in]qConstraintMinmin. constraint axis value, depending on axisBit and setting
[in]qConstraintMaxmax. constraint axis value, depending on axisBit and setting
Return values
1- Error, axis constraints are set to min. and max. travel range values
0- Ok

◆ SetAxisEnable()

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

Set axis enable
Parameter enable is 1 for enable or 0 for disable.

// Example:
...
int axisBit = 0x3F; // axis bit field 0011 1111
int enable = 1;
ret = er_mop_autopath.SetAxisEnable(axisBit,enable);
_info_line_msg(0," SetAxisEnable() %s",ret==0?"Ok":"Error");
...
Parameters
[in]axisBitaxis bit field
[in]enable1-enable, 0-disable
Return values
1- Error
0- Ok

◆ SetAxisPriority()

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

Set axis priority
Parameter priority is in [1..99].

// Example:
...
int axisBit = 0x3F; // axis bit field 0011 1111
int priority = 49; // [1..99]
ret = er_mop_autopath.SetAxisPriority(axisBit,priority);
_info_line_msg(0," SetAxisPriority() %s",ret==0?"Ok":"Error");
...
Parameters
[in]axisBitaxis bit field
[in]prioritypercentage value
Return values
1- Error
0- Ok

◆ SetDlgParameter()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::SetDlgParameter ( int  ap_dlg_option,
int  ap_dlg_value 
)
static

Set Autopath dialog parameter
Parameter ap_dlg_option is one of AUTOPATH_DLG_PARAMETER_API_CONTROL,.

AUTOPATH_DLG_PARAMETER_SHOW_WINDOW,

AUTOPATH_DLG_PARAMETER_DISABLE_MSG Remarks
To control AutoPath via API, enable API_CONTROL and enable DISABLE_MSG

// Example:
...
er_mop_autopath.SetDlgParameter(AUTOPATH_DLG_PARAMETER_API_CONTROL,TRUE);
// Hide or show AutoPath Dialog
...
Parameters
[in]ap_dlg_optionautopath dialog parameter
[in]ap_dlg_valuedepending on paramter ap_dlg_option
Return values
1- Error
0- Ok

◆ SetEndPose()

static ER_DllExport float* ER_CAPI_MOP_AUTOPATH::SetEndPose ( void  )
static

Set current robot joint location as end pose
Remarks
This pose must be collision free, based on current collision settings.

Return values
pointerto end pose
NULL- Error, pose is not valid, due to collision or travel ranges are exceeded

◆ SetParameter()

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

Set Autopath calculation parameter
Parameter 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_OUTPUT_SETTINGS.

Parameters
[in]ap_optionautopath parameter index
[in]ap_valuedepending on paramter ap_option
Return values
1- Error
0- Ok

◆ SetPoseEnd()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::SetPoseEnd ( int  nConfig,
float *  pose_end 
)
static

Set specified robot joint location as end pose
Remarks
This pose must be collision free, based on current collision settings.

Parameters
[in]nConfign-dimensional configuration space
[in]pose_endpointer to end pose
Return values
0- OK
1- Error, pose is not valid, due to collision or travel ranges are exceeded

◆ SetPoseStart()

static ER_DllExport int ER_CAPI_MOP_AUTOPATH::SetPoseStart ( int  nConfig,
float *  pose_start 
)
static

Set specified robot joint location as start pose
Remarks
This pose must be collision free, based on current collision settings.

Parameters
[in]nConfign-dimensional configuration space
[in]pose_startpointer to start pose
Return values
0- OK
1- Error, pose is not valid, due to collision or travel ranges are exceeded

◆ SetStartPose()

static ER_DllExport float* ER_CAPI_MOP_AUTOPATH::SetStartPose ( void  )
static

Set current robot joint location as start pose
Remarks
This pose must be collision free, based on current collision settings.

Return values
pointerto start pose
NULL- Error, pose is not valid, due to collision or travel ranges are exceeded

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