EASY-ROB™ Kernel  v8.606
Static Public Member Functions | List of all members
ERK_CAPI_TOOLPATH_MOTION_EXEC Class Reference

brief Method class to access motion execution data at target More...

#include <erk_capi.h>

Inheritance diagram for ERK_CAPI_TOOLPATH_MOTION_EXEC:
ERK_CAPI_TOOLPATH ERK_CAPI_DEVICES ERK_CAPI

Static Public Member Functions

static DLLAPI ER_TARGET_MOTION_EXEC_HND ER_STDCALL GetMotionExecHnd (ER_TARGET_LOCATION_HND er_tarloc_hnd)
 Handle for target execution data
Target execution data are calculated while interpolation through the complete tool path, if the robot has reached the target
see also. More...
 
static DLLAPI long ER_STDCALL erGetMotionExec_motion_success (ER_TARGET_MOTION_EXEC_HND hnd)
 Motion success is true when the robot has reached the target location successfully
Remarks
ERK_CAPI_TOOLPATH::erGET_NEXT_TOOLPATH_STEP_INIT() at the beginning of interpolation will reset motion_success for each targat location. More...
 
static DLLAPI double ER_STDCALL erGetMotionExec_time_stamp (ER_TARGET_MOTION_EXEC_HND hnd)
 Time stamp - total execution time [s] at the target location, while interpolation through the complete tool path
Remarks
ERK_CAPI_TOOLPATH::erGET_NEXT_TOOLPATH_STEP_INIT() sets the time_stamp = 0. More...
 
static DLLAPI double ER_STDCALL erGetMotionExec_trajectory_time (ER_TARGET_MOTION_EXEC_HND hnd)
 Trajectory time [s], time to reach the target location, while interpolation through the complete tool path. More...
 
static DLLAPI long ER_STDCALL erGetMotionExec_configuration (ER_TARGET_MOTION_EXEC_HND hnd)
 Robot configuration, when reaching the target, while interpolation through the complete tool path
Remarks
Normally a robot configuration will
NOT change during a CP (ER_LIN, ER_CIRC) move
Valid robot configurations are between 1 and number of possible configurations depending on robot, maximum ER_KIN_CONFIGS
A valid robot configuration can be specified with. More...
 
static DLLAPI double *ER_STDCALL erGetMotionExec_JointPos (ER_TARGET_MOTION_EXEC_HND hnd)
 Joint position at target location, while interpolation through the complete tool path. More...
 
static DLLAPI double *ER_STDCALL erGetMotionExec_ExtAxValues (ER_TARGET_MOTION_EXEC_HND hnd)
 External axis values at target location, while interpolation through the complete tool path. More...
 
- Static Public Member Functions inherited from ERK_CAPI_TOOLPATH
static DLLAPI int ER_STDCALL erInitToolPath (ER_HND er_hnd, ER_TOOLPATH_HND *er_tpth_hnd)
 Create a unique tool path handle for a kinematics. More...
 
static DLLAPI int ER_STDCALL erUnloadToolPath (ER_TOOLPATH_HND *er_tpth_hnd)
 Unload an instance of a kinematics tool path. More...
 
static DLLAPI int ER_STDCALL erInsertToolPath (ER_HND er_hnd, ER_TOOLPATH_HND *er_tpth_hnd, ER_TOOLPATH_HND er_tpth_hnd_ref)
 Create and insert a unique tool path handle.
The created tool path handle er_tpth_hnd is inserted before the tool path handle er_tpth_hnd_ref
Remarks
If parameter er_tpth_hnd_ref is NULL, the new tool path is appended. More...
 
static DLLAPI int ER_STDCALL erSwapToolPath (ER_TOOLPATH_HND er_tpth_hnd1, ER_TOOLPATH_HND er_tpth_hnd2)
 Swap two tool pathes.
Swaps the position of two tool path handles. More...
 
static DLLAPI int ER_STDCALL erToolPathGetTargetLocationNumber (ER_TOOLPATH_HND er_tpth_hnd)
 Get the number of target locations in tool path. More...
 
static DLLAPI char *ER_STDCALL erToolPathName (ER_TOOLPATH_HND er_tpth_hnd)
 Name of tool path. More...
 
static DLLAPI long ER_STDCALL erToolPathEnable (ER_TOOLPATH_HND er_tpth_hnd, long enable)
 Enable or disable tool path
Parameter enable is one of ER_ONOFF_DISABLE, ER_ONOFF_ENABLE, ER_ONOFF_STATUS. More...
 
static DLLAPI ER_HND ER_STDCALL erToolPathGetRobotHandle (ER_TOOLPATH_HND er_tpth_hnd)
 Get device robot handle belonging to tool path handle. More...
 
static DLLAPI ER_HND ER_STDCALL erToolPathGetTrackMotionHandle (ER_TOOLPATH_HND er_tpth_hnd)
 Get device track motion handle belonging to tool path handle. More...
 
static DLLAPI ER_HND ER_STDCALL erToolPathGetPositionerHandle (ER_TOOLPATH_HND er_tpth_hnd)
 Get device positioner handle belonging to tool path handle. More...
 
static DLLAPI ER_HND ER_STDCALL erToolPathGetConveyorHandle (ER_TOOLPATH_HND er_tpth_hnd)
 Get device conveyor handle belonging to tool path handle. More...
 
static DLLAPI long ER_STDCALL erToolPathSetTrackMotionHandle (ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_TrackMotion=NULL)
 Set track motion handle belonging to tool path handle.
The tool path handles the track motion device as external axis, see erConnectTrackMotion()
hnd_TrackMotion=NULL will remove track motion handle from the tool path. More...
 
static DLLAPI long ER_STDCALL erToolPathSetPositionerHandle (ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_Positioner=NULL)
 Set positioner handle belonging to tool path handle.
The tool path handles the positioner device as external axis, see erConnectPositioner()
hnd_Positioner=NULL will remove positioner handle from the tool path. More...
 
static DLLAPI long ER_STDCALL erToolPathSetConveyorHandle (ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_Conveyor=NULL)
 Set conveyor handle belonging to tool path handle.
The tool path handles the conveyor device as external axis, see erConnectConveyor()
hnd_Conveyor=NULL will remove conveyor handle from the tool path. More...
 
static DLLAPI char *ER_STDCALL erToolPathLogFileName (ER_TOOLPATH_HND er_tpth_hnd)
 Name log file. More...
 
static DLLAPI char *ER_STDCALL erToolPathPrgFileName (ER_TOOLPATH_HND er_tpth_hnd)
 Name program file. More...
 
static DLLAPI ER_TARGET_LOCATION_HND ER_STDCALL erToolPathGetTargetLocationFirst (ER_TOOLPATH_HND er_tpth_hnd)
 Get the first 'target location handle' in the tool path. More...
 
static DLLAPI ER_TARGET_LOCATION_HND ER_STDCALL erToolPathGetTargetLocationLast (ER_TOOLPATH_HND er_tpth_hnd)
 Get the last 'target location handle' in the tool path. More...
 
static DLLAPI long ER_STDCALL CpyEventsTemplate (ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_EVENTS_HND hnd)
 Copy events to template data.
The events defined with events handle hnd are copied to the events template belonging to the tool path handle er_tpth_hnd. More...
 
static DLLAPI ER_TARGET_EVENTS_HND ER_STDCALL GetEventsTemplateHnd (ER_TOOLPATH_HND er_tpth_hnd)
 Get events template data from tool path.
Get the events template data belonging to the tool path er_tpth_hnd. More...
 
static DLLAPI long ER_STDCALL CpyMotionAttributesTemplate (ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_ATTRIBUTES_HND hnd)
 Copy attributes to template data.
The attributes defined with attribute handle hnd are copied to the attribute template belonging to the tool path handle er_tpth_hnd. More...
 
static DLLAPI ER_TARGET_ATTRIBUTES_HND ER_STDCALL GetMotionAttributesTemplateHnd (ER_TOOLPATH_HND er_tpth_hnd)
 Get attributes template data from tool path.
Get the attributes template data belonging to the tool path er_tpth_hnd. More...
 
static DLLAPI long ER_STDCALL CpyMoveJointTemplate (ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_MOVE_JOINT_HND hnd)
 Copy move joint data to template data.
The move joint data defined with move joint handle hnd are copied to the move joint template belonging to the tool path handle er_tpth_hnd. More...
 
static DLLAPI ER_TARGET_MOVE_JOINT_HND ER_STDCALL GetMoveJointTemplate (ER_TOOLPATH_HND er_tpth_hnd)
 Get move joint template data from tool path.
Get the move joint template data belonging to the tool path er_tpth_hnd. More...
 
static DLLAPI long ER_STDCALL CpyMoveCPTemplate (ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_MOVE_CP_HND hnd)
 Copy move cp data to template data.
The move cp data defined with move cp handle hnd are copied to the move cp template belonging to the tool path handle er_tpth_hnd. More...
 
static DLLAPI ER_TARGET_MOVE_CP_HND ER_STDCALL GetMoveCPTemplate (ER_TOOLPATH_HND er_tpth_hnd)
 Get move cp template data from tool path.
Get the move cp template data belonging to the tool path er_tpth_hnd. More...
 
static DLLAPI long ER_STDCALL CpyExtAxTrackMotionTemplate (ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND hnd)
 Copy external axis track motion data to template data.
The external axis track motion data defined with external axis track motion handle hnd are copied to the external axis track motion template belonging to the tool path handle er_tpth_hnd. More...
 
static DLLAPI ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND ER_STDCALL GetExtAxTrackMotionTemplate (ER_TOOLPATH_HND er_tpth_hnd)
 Get external axis track motion template data from tool path.
Get the external axis track motion template data belonging to the tool path er_tpth_hnd. More...
 
static DLLAPI long ER_STDCALL CpyExtAxPositionerTemplate (ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_EXTAX_DEVICE_POSITIONER_HND hnd)
 Copy external axis positioner data to template data.
The external axis positioner data defined with external axis positioner handle hnd are copied to the external axis positioner template belonging to the tool path handle er_tpth_hnd. More...
 
static DLLAPI ER_TARGET_EXTAX_DEVICE_POSITIONER_HND ER_STDCALL GetExtAxPositionerTemplate (ER_TOOLPATH_HND er_tpth_hnd)
 Get external axis positioner template data from tool path.
Get the external axis positioner template data belonging to the tool path er_tpth_hnd. More...
 
static DLLAPI long ER_STDCALL CpyExtAxConveyorTemplate (ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND hnd)
 Copy external axis conveyor data to template data.
The external axis conveyor data defined with external axis conveyor handle hnd are copied to the external axis conveyor template belonging to the tool path handle er_tpth_hnd. More...
 
static DLLAPI ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND ER_STDCALL GetExtAxConveyorTemplate (ER_TOOLPATH_HND er_tpth_hnd)
 Get external axis conveyor template data from tool path.
Get the external axis conveyor template data belonging to the tool path er_tpth_hnd. More...
 
static DLLAPI long ER_STDCALL erToolPathReset (ER_TOOLPATH_HND er_tpth_hnd)
 Reset all tool path target locations.
All target locations defined in tool path er_tpth_hnd are resetted to default values and set to invalid. More...
 
static DLLAPI int ER_STDCALL erToolPathResetInitRobot (ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL)
 Set initial joint start location for the robot.
Remarks
Read current joint data from loaded robot. This method must be called before the interpolation starts. More...
 
static DLLAPI int ER_STDCALL erToolPathResetInitTrackMotion (ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL)
 Set initial joint start location for the TrackMotion.
Remarks
Read current joint data from loaded TrackMotion. This method must be called before the interpolation starts. More...
 
static DLLAPI int ER_STDCALL erToolPathResetInitPositioner (ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL)
 Set initial joint start location for the Positioner.
Remarks
Read current joint data from loaded Positioner. This method must be called before the interpolation starts. More...
 
static DLLAPI int ER_STDCALL erToolPathResetInitConveyor (ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL)
 Set initial joint start location for the Conveyor.
Remarks
Read current joint data from loaded Conveyor. This method must be called before the interpolation starts. More...
 
static DLLAPI int ER_STDCALL erToolPathSetInitPos (ER_TOOLPATH_HND er_tpth_hnd, double InterpolationTime=0)
 Initializes the Trajectory Planner based on current settings.
Remarks
This method must be called before the interpolation starts, see erGET_NEXT_TOOLPATH_STEP() More...
 
static DLLAPI int ER_STDCALL erGET_NEXT_TOOLPATH_STEP_INIT (ER_TOOLPATH_HND er_tpth_hnd, long cntrl)
 Initializes the interpolation through a complete tool path
Parameter cntrl must be set to ER_MOP_GNTPS_CNTRL_INIT
and can be extended by an individual bitwise-inclusive-OR operator (|) of. More...
 
static DLLAPI int ER_STDCALL erGET_NEXT_TOOLPATH_STEP (ER_TOOLPATH_HND er_tpth_hnd, long cntrl, NEXT_STEP_DATA *p_next_step_data=NULL, double time=0)
 Interpolation through a complete tool path
Parameter cntrl is an individual bitwise-inclusive-OR operator (|) of ER_MOP_GNTPS_CNTRL_NEXT_STEP, ER_MOP_GNTPS_CNTRL_UPDATE_GEO, ER_MOP_GNTPS_CNTRL_STEPDATA_OUT
Remarks
Before using this method, call erGET_NEXT_TOOLPATH_STEP_INIT(), see also erGET_NEXT_STEP() More...
 
static DLLAPI ER_TARGET_LOCATION_HND ER_STDCALL erGET_NEXT_TOOLPATH_STEP_cTargetLocation (ER_TOOLPATH_HND er_tpth_hnd)
 Get the current 'target location handle' while interpolation through a complete tool path. More...
 
static DLLAPI int ER_STDCALL erGET_NEXT_TOOLPATH_STEP_TERMINATE (ER_TOOLPATH_HND er_tpth_hnd)
 Terminates interpolation
Remarks
This method must be called after the interpolation of a tool path, see erGET_NEXT_TOOLPATH_STEP() More...
 
- Static Public Member Functions inherited from ERK_CAPI_DEVICES
static DLLAPI int ER_STDCALL erInitKin (ER_HND *er_hnd, Host_HND host_hnd=NULL)
 Create a unique kinematics handle.
Opcode 101, Chapter 3.4.1, Page 3-26, same as erINITIALIZE()
Initializes one instance of a robot and creates an unique kinematics handle er_hnd belonging to a robot kinematics.
This handles is necessary to access individual data from the robot and to call other functions.
Use erLoadKin() to load an EASY-ROB rob file (*.rob) containing a kinematics. More...
 
static DLLAPI int ER_STDCALL erUnloadKin (ER_HND *er_hnd)
 Unload an instance of kinematics of the Kernel.
Unloads an instance of kinematics givin by the unique kinematics handle.
Unloading a kinematics will call callback function TerFreeGeometryProc for each geometry belonging to this kinematics.
The number of loaded kinematics will be decremented.
This kinematics handle er_hnd is set to NULL and is not valid after calling this function. More...
 
static DLLAPI int ER_STDCALL erConnectPositioner (ER_HND er_hnd, ER_HND er_hnd_connect)
 Connects a positioner kinematics with handle er_hnd_connect to the robot kinematics with handle er_hnd.
Remarks
Use erConnectPositionerSetSync() for synchronized motion with a positioner.
Use erConnectPositionerGetSync() to receive synchronization status between robot and the connected positioner. More...
 
static DLLAPI ER_HND ER_STDCALL erConnectPositionerGetHND (ER_HND er_hnd)
 Get robots connection handle between robot and positioner.
See also erConnectPositioner() More...
 
static DLLAPI int ER_STDCALL erConnectPositionerSetSync (ER_HND er_hnd, long connect_sync)
 Set robots synchronization flag for synchronization between robot and positioner.
The synchronization flag connect_sync can be one of the following values.
1: ER_SYNC_OFF, 2: ER_SYNC_ON
See also erConnectPositionerGetSync() More...
 
static DLLAPI int ER_STDCALL erConnectPositionerGetSync (ER_HND er_hnd)
 Get robots synchronization flag for synchronization between robot and positioner.
See also erConnectPositionerSetSync() More...
 
static DLLAPI int ER_STDCALL erConnectConveyor (ER_HND er_hnd, ER_HND er_hnd_connect)
 Connects a conveyor kinematics with handle er_hnd_connect to the robot kinematics with handle er_hnd.
Remarks
Use erConnectConveyorSetSync() for synchronized motion with a conveyor.
Use erConnectConveyorGetSync() to receive synchronization status between robot and the connected conveyor. More...
 
static DLLAPI ER_HND ER_STDCALL erConnectConveyorGetHND (ER_HND er_hnd)
 Get robots connection handle between robot and conveyor.
See also erConnectConveyor() More...
 
static DLLAPI int ER_STDCALL erConnectConveyorSetSync (ER_HND er_hnd, long connect_sync)
 Set robots synchronization flag for synchronization between robot and conveyor.
The synchronization flag connect_sync can be one of the following values.
1: ER_SYNC_OFF, 2: ER_SYNC_ON
See also erConnectConveyorGetSync() More...
 
static DLLAPI int ER_STDCALL erConnectConveyorGetSync (ER_HND er_hnd)
 Get robots synchronization flag for synchronization between robot and conveyor.
See also erConnectConveyorSetSync() More...
 
static DLLAPI int ER_STDCALL erConnectTrackMotion (ER_HND er_hnd, ER_HND er_hnd_connect)
 Connects a track motion kinematics with handle er_hnd_connect to the robot kinematics with handle er_hnd.
Remarks
Use erConnectTrackMotionSetSync() for synchronized motion with a track motion.
Use erConnectTrackMotionGetSync() to receive synchronization status between robot and the connected track motion. More...
 
static DLLAPI ER_HND ER_STDCALL erConnectTrackMotionGetHND (ER_HND er_hnd)
 Get robots connection handle between robot and track motion.
See also erConnectTrackMotion() More...
 
static DLLAPI int ER_STDCALL erConnectTrackMotionSetSync (ER_HND er_hnd, long connect_sync)
 Set robots synchronization flag for synchronization between robot and track motion.
The synchronization flag connect_sync can be one of the following values.
1: ER_SYNC_OFF, 2: ER_SYNC_ON, 4: ER_SYNC_CONVEYOR
See also erConnectTrackMotionGetSync() More...
 
static DLLAPI int ER_STDCALL erConnectTrackMotionGetSync (ER_HND er_hnd)
 Get robots synchronization flag for synchronization between robot and track motion.
See also erConnectTrackMotionSetSync() More...
 
static DLLAPI int ER_STDCALL erConnectRobot (ER_HND er_hnd, ER_HND er_hnd_connect)
 Connects a slave robot kinematics with handle er_hnd_connect to the robot kinematics with handle er_hnd.
Remarks
Use erConnectRobotSetSync() for synchronized motion with a slave robot.
Use erConnectRobotGetSync() to receive synchronization status between robot and the connected slave robot. More...
 
static DLLAPI ER_HND ER_STDCALL erConnectRobotGetHND (ER_HND er_hnd)
 Get robots connection handle between robot and slave robot.
See also erConnectRobot() More...
 
static DLLAPI int ER_STDCALL erConnectRobotSetSync (ER_HND er_hnd, long connect_sync)
 Set robots synchronization flag for synchronization between robot and slave robot.
The synchronization flag connect_sync can be one of the following values.
1: ER_SYNC_OFF, 2: ER_SYNC_ON
See also erConnectRobotGetSync() More...
 
static DLLAPI int ER_STDCALL erConnectRobotGetSync (ER_HND er_hnd)
 Get robots synchronization flag for synchronization between robot and slave robot.
See also erConnectRobotSetSync() More...
 
static DLLAPI int ER_STDCALL erUnloadTool (ER_HND er_hnd)
 Unload a kinematics tool.
Unloads a kinematics tool givin by the unique kinematics handle.
Unloading a kinematics tool will call callback function TerFreeGeometryProc for each geometry belonging to this kinematics tool.
Remarks
This kinematics handle er_hnd is still valid after calling this function. More...
 
static DLLAPI int ER_STDCALL erLoadKin (ER_HND er_hnd, char *fln_rob)
 Load an EASY-ROB rob file (*.rob) containing a kinematics.
Loading a robfile will call the callback function TerLoadGeometryProc() each time when a geometry-file-name is detected in the robfile.
In this case the host application has to read or import the geometry and store it inside their own structure.
Remarks
Get a valid unique kinematics handle with erInitKin()
In case the robfile cannot be loaded, the kinematics handle is not valid anymore. Get a new kinematics handle with erInitKin() More...
 
static DLLAPI int ER_STDCALL erLoadTool (ER_HND er_hnd, char *fln_tool)
 Load an EASY-ROB tool file (*.tol) containing tool (tcp) data.
Loading a toolfile will call the callback function TerLoadGeometryProc() each time when a geometry-file-name is detected in the toolfile.
. More...
 
static DLLAPI int ER_STDCALL erGet_n_Kin (ER_HND er_hnd)
 Get the number of loaded kinematics. More...
 
static DLLAPI int ER_STDCALL erGet_n_Kin_IR (ER_HND er_hnd)
 Get the number of loaded kinematics with more than 3 joints and inverse kinematics. More...
 
static DLLAPI int ER_STDCALL erGetName (ER_HND er_hnd, char *name)
 Get the name of the robot. More...
 

Additional Inherited Members

- Static Public Attributes inherited from ERK_CAPI_TOOLPATH
static ERK_CAPI_TOOLPATH_TARGETS erk_toolpath_targets
 Method class to create, unload and specify target locations. More...
 
static ERK_CAPI_TOOLPATH_HEAD erk_toolpath_head
 Method class to set and get tool path motion header data for target locations. More...
 
static ERK_CAPI_TOOLPATH_INSTRUCTIONS erk_toolpath_instructions
 Method class to set and get Instructions for target locations. More...
 
static ERK_CAPI_TOOLPATH_EVENTS erk_toolpath_events
 Method class to set and get tool path events for target locations. More...
 
static ERK_CAPI_TOOLPATH_ATTRIBUTES_AUX erk_toolpath_attributes_aux
 Method class to set and get tool path auxiliary motion attributes for target locations. More...
 
static ERK_CAPI_TOOLPATH_ATTRIBUTES erk_toolpath_attributes
 Method class to set and get tool path motion attributes for target locations. More...
 
static ERK_CAPI_TOOLPATH_MOVE_JOINT erk_toolpath_move_joint
 Method class to specify a joint motion for target location. More...
 
static ERK_CAPI_TOOLPATH_MOVE_CP erk_toolpath_move_cp
 Method class to specify a cp motion for target location. More...
 
static ERK_CAPI_TOOLPATH_MOTION_EXEC erk_toolpath_motion_exec
 Method class to access motion execution data at target. More...
 
static ERK_CAPI_TOOLPATH_EXTAX_TRACKMOTION erk_toolpath_extax_trackmotion
 Method class to specify external axis data for a track/slider-motion for target location. More...
 
static ERK_CAPI_TOOLPATH_EXTAX_POSITIONER erk_toolpath_extax_positioner
 Method class to specify external axis data for a positioner for target location. More...
 
static ERK_CAPI_TOOLPATH_EXTAX_CONVEYOR erk_toolpath_extax_conveyor
 Method class to specify external axis data for a conveyor for target location. More...
 
static ERK_CAPI_TOOLPATH_TOOLBOX erk_toolpath_toolbox
 Method class for miscellaneous tool path calculations. More...
 
static ERK_CAPI_TOOLPATH_APIPP erk_toolpath_apipp
 Method for post processing, creating a robot program for a tool path. More...
 
static ERK_CAPI_TOOLPATH_CREATE erk_toolpath_create
 Method class to create tool pathes. More...
 
- Static Public Attributes inherited from ERK_CAPI_DEVICES
static ERK_CAPI_ROB erk_capi_rob
 Method class kinematics and transformations. More...
 
static ERK_CAPI_MOP erk_capi_mop
 Method class for motion planning and -execution. More...
 
static ERK_CAPI_TOOLPATH erk_capi_toolpath
 Method class for tool path definition. More...
 
- Static Public Attributes inherited from ERK_CAPI
static ERK_CAPI_ADMIN erk_capi_admin
 Method class to administrate this Robotics Simulation Kernel. More...
 
static ERK_CAPI_DEVICES erk_capi_devices
 Method class to create, attach, update devices, for kinematics calculations and for motion planning and -execution. More...
 
static ERK_CAPI_SIM erk_capi_sim
 Method class for simulation settings. More...
 
static ERK_CAPI_AUTOPATH erk_capi_autopath
 Method class for collision free path planning. More...
 
static ERK_CAPI_TARGETS erk_capi_targets
 Method class for paths and tags. More...
 
static ERK_CAPI_GEO erk_capi_geo
 Method class to handle 3D Geometry Data. More...
 
static ERK_CAPI_SYS erk_capi_sys
 Method class for mathematical calculations, simulation status, units. More...
 

Detailed Description

brief Method class to access motion execution data at target

Member Function Documentation

◆ erGetMotionExec_configuration()

static DLLAPI long ER_STDCALL ERK_CAPI_TOOLPATH_MOTION_EXEC::erGetMotionExec_configuration ( ER_TARGET_MOTION_EXEC_HND  hnd)
static

Robot configuration, when reaching the target, while interpolation through the complete tool path
Remarks
Normally a robot configuration will
NOT change during a CP (ER_LIN, ER_CIRC) move
Valid robot configurations are between 1 and number of possible configurations depending on robot, maximum ER_KIN_CONFIGS
A valid robot configuration can be specified with.

Parameters
[in]hndunique target execution handle ER_TARGET_MOTION_EXEC_HND
Return values
configuration- robot configuration [1..ER_KIN_CONFIGS], 0-robot configuration can not be calculated

◆ erGetMotionExec_ExtAxValues()

static DLLAPI double* ER_STDCALL ERK_CAPI_TOOLPATH_MOTION_EXEC::erGetMotionExec_ExtAxValues ( ER_TARGET_MOTION_EXEC_HND  hnd)
static

External axis values at target location, while interpolation through the complete tool path.

Parameters
[in]hndunique target execution handle ER_TARGET_MOTION_EXEC_HND
Return values
pointerto double - ExtAxValues vector, maximum size ER_KIN_DOFS
NULL- Error

◆ erGetMotionExec_JointPos()

static DLLAPI double* ER_STDCALL ERK_CAPI_TOOLPATH_MOTION_EXEC::erGetMotionExec_JointPos ( ER_TARGET_MOTION_EXEC_HND  hnd)
static

Joint position at target location, while interpolation through the complete tool path.

Parameters
[in]hndunique target execution handle ER_TARGET_MOTION_EXEC_HND
Return values
pointerto double - JointPos vector, maximum size ER_KIN_DOFS
NULL- Error

◆ erGetMotionExec_motion_success()

static DLLAPI long ER_STDCALL ERK_CAPI_TOOLPATH_MOTION_EXEC::erGetMotionExec_motion_success ( ER_TARGET_MOTION_EXEC_HND  hnd)
static

Motion success is true when the robot has reached the target location successfully
Remarks
ERK_CAPI_TOOLPATH::erGET_NEXT_TOOLPATH_STEP_INIT() at the beginning of interpolation will reset motion_success for each targat location.

Parameters
[in]hndunique target execution handle ER_TARGET_MOTION_EXEC_HND
Return values
motion_success- 1-success, 0-Error reaching the target

◆ erGetMotionExec_time_stamp()

static DLLAPI double ER_STDCALL ERK_CAPI_TOOLPATH_MOTION_EXEC::erGetMotionExec_time_stamp ( ER_TARGET_MOTION_EXEC_HND  hnd)
static

Time stamp - total execution time [s] at the target location, while interpolation through the complete tool path
Remarks
ERK_CAPI_TOOLPATH::erGET_NEXT_TOOLPATH_STEP_INIT() sets the time_stamp = 0.

Parameters
[in]hndunique target execution handle ER_TARGET_MOTION_EXEC_HND
Return values
time_stamp- total execution time [s]

◆ erGetMotionExec_trajectory_time()

static DLLAPI double ER_STDCALL ERK_CAPI_TOOLPATH_MOTION_EXEC::erGetMotionExec_trajectory_time ( ER_TARGET_MOTION_EXEC_HND  hnd)
static

Trajectory time [s], time to reach the target location, while interpolation through the complete tool path.

Parameters
[in]hndunique target execution handle ER_TARGET_MOTION_EXEC_HND
Return values
trajectory_time- elapsed time in [s]

◆ GetMotionExecHnd()

static DLLAPI ER_TARGET_MOTION_EXEC_HND ER_STDCALL ERK_CAPI_TOOLPATH_MOTION_EXEC::GetMotionExecHnd ( ER_TARGET_LOCATION_HND  er_tarloc_hnd)
static

Handle for target execution data
Target execution data are calculated while interpolation through the complete tool path, if the robot has reached the target
see also.

Typical data belonging to a target execution data are:
motion_success, time_stamp, trajectory_time, robot configuration, JointPos, external axis values
Remarks
The returned handle ER_TARGET_MOTION_EXEC_HND is used to access target execution data

Parameters
[in]er_tarloc_hndunique target location handle ER_TARGET_LOCATION_HND
Return values
hnd- target execution handle ER_TARGET_MOTION_EXEC_HND
NULL- Error, invalid target locations

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