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

Method class API for forward- and Inverse kinematics. More...

#include <erk_capi.h>

Inheritance diagram for ERK_CAPI_ROB_KIN_API:
ERK_CAPI_ROB ERK_CAPI_DEVICES ERK_CAPI

Static Public Member Functions

static DLLAPI int ER_STDCALL erGetInvKinID (ER_HND er_hnd, long *invkin_id)
 Inverse kinematics ID for cRobot. More...
 
static DLLAPI int ER_STDCALL erGetInvKinSubID (ER_HND er_hnd, long *invkinsub_id)
 Inverse kinematics Sub-ID for cRobot. More...
 
static DLLAPI int ER_STDCALL erSetJointSolutions (ER_HND er_hnd, double *q_solutions, long *q_warnings)
 Set all robot joint solutions. The kinematics joint data q_solutions are in units [m] for prismatic joint type
and [rad] for rotational joint type
Get the number of active joints with erGet_num_dofs()
Get the number of configurations with erGetNumConfigs()
Remarks
Call this function after calling the inverse kinematics transformation, erInvKinRobotBaseTip(), erInvKinWorldTip(), erInvKinRobotBaseTcp(), erInvKinWorldTcp() More...
 
static DLLAPI int ER_STDCALL erSetJointDyn (ER_HND er_hnd, double q_dyn, long jnt_no)
 Set a single actual robot joint data. The kinematics joint data q_dyn are in units [m] for prismatic joint type
and [rad] for rotational joint type
Get the number of active joints with erGet_num_dofs() More...
 
static DLLAPI int ER_STDCALL erGetRobotBasetoFirstJoint (ER_HND er_hnd, DFRAME *bT0)
 Robot Base to first joint of kinematics chain.
. More...
 
static DLLAPI int ER_STDCALL erGetJointFrameActiveNext (ER_HND er_hnd, long active_jnt_no, DFRAME *T_nxt)
 Get kinematics transformation to the next joint for each active joint "Geometric Data to next".
Get the number of active joints with erGet_num_dofs()
Remarks
see erGetRobotBasetoFirstJoint(), erGetJointFrameActiveLast(), erGetJointFramePassiveNext(), erGetJointFramePassiveLast() More...
 
static DLLAPI int ER_STDCALL erSetJointFrameActiveNext (ER_HND er_hnd, long active_jnt_no, DFRAME *T_nxt)
 Set kinematics transformation to the next joint for each active joint "Geometric Data to next".
Get the number of active joints with erGet_num_dofs()
Remarks
see example erGetJointFrameActiveNext() More...
 
static DLLAPI int ER_STDCALL erGetJointFrameActiveLast (ER_HND er_hnd, long active_jnt_no, DFRAME *T_last)
 Get kinematics transformation from last joint for each active joint "Geometric Data from last".
Get the number of active joints with erGet_num_dofs()
Remarks
see example erGetJointFrameActiveNext() More...
 
static DLLAPI int ER_STDCALL erSetJointFrameActiveLast (ER_HND er_hnd, long active_jnt_no, DFRAME *T_last)
 Set kinematics transformation from last joint for each active joint "Geometric Data from last".
Get the number of active joints with erGet_num_dofs()
Remarks
see example erGetJointFrameActiveNext() More...
 
static DLLAPI int ER_STDCALL erGetJointFramePassiveNext (ER_HND er_hnd, long passive_jnt_no, DFRAME *T_nxt)
 Get kinematics transformation to the next joint for each passive joint "Geometric Data to next".
Get the number of passive joints with erGet_num_dofs_passive() More...
 
static DLLAPI int ER_STDCALL erSetJointFramePassiveNext (ER_HND er_hnd, long passive_jnt_no, DFRAME *T_nxt)
 Set kinematics transformation to the next joint for each passive joint "Geometric Data to next".
Get the number of passive joints with erGet_num_dofs_passive()
Remarks
see example erGetJointFrameActiveNext() More...
 
static DLLAPI int ER_STDCALL erGetJointFramePassiveLast (ER_HND er_hnd, long passive_jnt_no, DFRAME *T_last)
 Get kinematics transformation from last joint for each passive joint "Geometric Data from last".
Get the number of passive joints with erGet_num_dofs_passive()
Remarks
see example erGetJointFrameActiveNext() More...
 
static DLLAPI int ER_STDCALL erSetJointFramePassiveLast (ER_HND er_hnd, long passive_jnt_no, DFRAME *T_last)
 Set kinematics transformation from last joint for each passive joint "Geometric Data from last".
Set the number of passive joints with erGet_num_dofs_passive()
Remarks
see example erGetJointFrameActiveNext() More...
 
static DLLAPI void **ER_STDCALL erGet_erk_kin_usr_ptr (ER_HND er_hnd)
 Access user pointer for user defined inverse and forward kinematics in EasySimKernel_apikinx64.dll
This allows the user to allocate individual memory.
The EASY-ROB Kernel administrates this pointer, related to the current device
Remarks
see erSetJointSolutions() to return the calculated results, joint solution and warning for each solution, depending on the number of robot configuration. 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_ROB
static ERK_CAPI_ROB_KIN erk_capi_rob_kin
 Method class forward-, Inverse kinematics, desired robot joints, tools, position w.r.t. world and reference system. More...
 
static ERK_CAPI_ROB_KIN_API erk_capi_rob_kin_api
 Method class API for forward- and Inverse kinematics. More...
 
static ERK_CAPI_ROB_ATRIBUTES erk_capi_rob_attributes
 Method class for robot/device attributes, travel ranges, home position, device name, ... 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

Method class API for forward- and Inverse kinematics.

Member Function Documentation

◆ erGet_erk_kin_usr_ptr()

static DLLAPI void** ER_STDCALL ERK_CAPI_ROB_KIN_API::erGet_erk_kin_usr_ptr ( ER_HND  er_hnd)
static

Access user pointer for user defined inverse and forward kinematics in EasySimKernel_apikinx64.dll
This allows the user to allocate individual memory.
The EASY-ROB Kernel administrates this pointer, related to the current device
Remarks
see erSetJointSolutions() to return the calculated results, joint solution and warning for each solution, depending on the number of robot configuration.

// Example:
EXPORT_C int inv_erk_kin_user_ext(ER_HND er_hnd, int status, int *pinvkin_id, int *pinvkin_sub_id, DFRAME *bTt)
// see example project "EasySimKernel_apikin.sln" for simple 2 axis scara robot
Parameter *pinvkin_id and *pinvkin_sub_id are the inverse kinematics ID and Sub-ID fo the robot
Parameter bTt is the cartesian transformation from the robot base to the robot tip
...
switch (*pinvkin_id) {
default:
*pinvkin_id = 0;
case 18:
switch (status) {
case ER_APIDLL_CNTRL_INITIALIZE: // 1. allocate some user memory
// alloc user defined class
void **kin_usr_ptr = erk_rob_kin_api.erGet_erk_kin_usr_ptr(er_hnd); // access kinematics user pointer
MY_USR_KIN_CLASS *p = (MY_USR_KIN_CLASS *)*kin_usr_ptr; // cast void pointer to own data type, to access the content
p = new MY_USR_KIN_CLASS;
*kin_usr_ptr = (void *)p; // copy new address
// do some preparation
...
break;
case ER_APIDLL_CNTRL_SIM_STEP: // 2. Inverse calculation
void **kin_usr_ptr = erk_rob_kin_api.erGet_erk_kin_usr_ptr(er_hnd); // access kinematics user pointer
MY_USR_KIN_CLASS *p = (MY_USR_KIN_CLASS *)*kin_usr_ptr; // cast void pointer to own data type, to access the content
if (!p)
int warn = p->Scara_Inverse(bTt); // inverse kinematics calculation
return warn;
...
break;
default:
case ER_APIDLL_CNTRL_TERMINATE: // 3. free user defined class
void **kin_usr_ptr = erk_rob_kin_api.erGet_erk_kin_usr_ptr(er_hnd); // access kinematics user pointer
MY_USR_KIN_CLASS *p = (MY_USR_KIN_CLASS *)*kin_usr_ptr; // cast void pointer to own data type, to access the content
if (!p)
delete p;
p = NULL;
*kin_usr_ptr = (void *)p; // copy new address
return INV_WARN_OK;
...
break;
}
return INV_WARN_OK; // xy plane Scara
break;
}
...
Return values
pointerto user defined memory

◆ erGetInvKinID()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erGetInvKinID ( ER_HND  er_hnd,
long *  invkin_id 
)
static

Inverse kinematics ID for cRobot.

Parameters
[in]er_hndunique kinematics handle ER_HND
[out]invkin_idinverse kinematics ID
Return values
0- OK
1- Error, invalid handle

◆ erGetInvKinSubID()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erGetInvKinSubID ( ER_HND  er_hnd,
long *  invkinsub_id 
)
static

Inverse kinematics Sub-ID for cRobot.

Parameters
[in]er_hndunique kinematics handle ER_HND
[out]invkinsub_idinverse kinematics Sub-ID
Return values
0- OK
1- Error, invalid handle

◆ erGetJointFrameActiveLast()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erGetJointFrameActiveLast ( ER_HND  er_hnd,
long  active_jnt_no,
DFRAME T_last 
)
static

Get kinematics transformation from last joint for each active joint "Geometric Data from last".
Get the number of active joints with erGet_num_dofs()
Remarks
see example erGetJointFrameActiveNext()

Parameters
[in]er_hndunique kinematics handle ER_HND
[in]active_jnt_noactive joint number[1..number of active joints], max active_jnt_no is::ER_KIN_DOFS
[out]T_lasttransformation to the next joint
Return values
0- OK
1- Error, invalid handle

◆ erGetJointFrameActiveNext()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erGetJointFrameActiveNext ( ER_HND  er_hnd,
long  active_jnt_no,
DFRAME T_nxt 
)
static

Get kinematics transformation to the next joint for each active joint "Geometric Data to next".
Get the number of active joints with erGet_num_dofs()
Remarks
see erGetRobotBasetoFirstJoint(), erGetJointFrameActiveLast(), erGetJointFramePassiveNext(), erGetJointFramePassiveLast()

// Example:
DFRAME bT0
erk_rob_kin_api.erGetRobotBasetoFirstJoint(er_hnd, &bT0); // Robot Base to first joint of kinematics chain
// active joints
long n_dof_active = erk_rob_kin.erGet_num_dofs(er_hnd); // Get number of active robot joints
for (int ii = 0; ii <= n_dof_active; ++ii)
{
if (ii == 0)
{
DFRAME iTb, T_last, T_nxt;
erk_rob_kin.erGetRobotBase(er_hnd, &iTb); // Get robot base location w.r.t. world
}
else
{
DFRAME bTax, T_last, T_nxt;
erk_rob_kin.erGetJointFrameRobotBase(er_hnd, ii, &bTax); // Get location of active joint coorsys w.r.t robot base
}
}
// passive joints
long n_dof_passive = erk_rob_kin.erGet_num_dofs_passive(er_hnd); // Get number of passive robot joints
for (int ii = 1; ii <= n_dof_passive; ii++)
{
erk_rob_kin.erGetJointFrameRobotBase_passive(er_hnd, ii, &bTax); // Get location of passive joint coorsys w.r.t robot base
}
...
Parameters
[in]er_hndunique kinematics handle ER_HND
[in]active_jnt_noactive joint number[1..number of active joints], max active_jnt_no is::ER_KIN_DOFS
[out]T_nxttransformation to the next joint
Return values
0- OK
1- Error, invalid handle

◆ erGetJointFramePassiveLast()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erGetJointFramePassiveLast ( ER_HND  er_hnd,
long  passive_jnt_no,
DFRAME T_last 
)
static

Get kinematics transformation from last joint for each passive joint "Geometric Data from last".
Get the number of passive joints with erGet_num_dofs_passive()
Remarks
see example erGetJointFrameActiveNext()

Parameters
[in]er_hndunique kinematics handle ER_HND
[in]passive_jnt_nopassive joint number[1..number of passive joints], max passive_jnt_no is::ER_KIN_PASSIVE_JNTS
[out]T_lasttransformation from last joint
Return values
0- OK
1- Error, invalid handle

◆ erGetJointFramePassiveNext()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erGetJointFramePassiveNext ( ER_HND  er_hnd,
long  passive_jnt_no,
DFRAME T_nxt 
)
static

Get kinematics transformation to the next joint for each passive joint "Geometric Data to next".
Get the number of passive joints with erGet_num_dofs_passive()

Parameters
[in]er_hndunique kinematics handle ER_HND
[in]passive_jnt_nopassive joint number[1..number of passive joints], max passive_jnt_no is::ER_KIN_PASSIVE_JNTS
[out]T_nxttransformation to the next joint
Return values
0- OK
1- Error, invalid handle

◆ erGetRobotBasetoFirstJoint()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erGetRobotBasetoFirstJoint ( ER_HND  er_hnd,
DFRAME bT0 
)
static

Robot Base to first joint of kinematics chain.
.

Parameters
[in]er_hndunique kinematics handle ER_HND
[out]bT0base to first joint
Return values
0- OK
1- Error, invalid handle

◆ erSetJointDyn()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erSetJointDyn ( ER_HND  er_hnd,
double  q_dyn,
long  jnt_no 
)
static

Set a single actual robot joint data. The kinematics joint data q_dyn are in units [m] for prismatic joint type
and [rad] for rotational joint type
Get the number of active joints with erGet_num_dofs()

Parameters
[in]er_hndunique kinematics handle ER_HND
[in]q_dynrobot joint data, max size ER_KIN_DOFS
[in]jnt_nojoint number [1..number of active joints], max jnt_no is ER_KIN_DOFS
Return values
0- OK
1- Error, invalid handle

◆ erSetJointFrameActiveLast()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erSetJointFrameActiveLast ( ER_HND  er_hnd,
long  active_jnt_no,
DFRAME T_last 
)
static

Set kinematics transformation from last joint for each active joint "Geometric Data from last".
Get the number of active joints with erGet_num_dofs()
Remarks
see example erGetJointFrameActiveNext()

Parameters
[in]er_hndunique kinematics handle ER_HND
[in]active_jnt_noactive joint number[1..number of active joints], max active_jnt_no is::ER_KIN_DOFS
[in]T_lasttransformation to the next joint
Return values
0- OK
1- Error, invalid handle

◆ erSetJointFrameActiveNext()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erSetJointFrameActiveNext ( ER_HND  er_hnd,
long  active_jnt_no,
DFRAME T_nxt 
)
static

Set kinematics transformation to the next joint for each active joint "Geometric Data to next".
Get the number of active joints with erGet_num_dofs()
Remarks
see example erGetJointFrameActiveNext()

Parameters
[in]er_hndunique kinematics handle ER_HND
[in]active_jnt_noactive joint number[1..number of active joints], max active_jnt_no is::ER_KIN_DOFS
[in]T_nxttransformation to the next joint
Return values
0- OK
1- Error, invalid handle

◆ erSetJointFramePassiveLast()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erSetJointFramePassiveLast ( ER_HND  er_hnd,
long  passive_jnt_no,
DFRAME T_last 
)
static

Set kinematics transformation from last joint for each passive joint "Geometric Data from last".
Set the number of passive joints with erGet_num_dofs_passive()
Remarks
see example erGetJointFrameActiveNext()

Parameters
[in]er_hndunique kinematics handle ER_HND
[in]passive_jnt_nopassive joint number[1..number of passive joints], max passive_jnt_no is::ER_KIN_PASSIVE_JNTS
[in]T_lasttransformation from last joint
Return values
0- OK
1- Error, invalid handle

◆ erSetJointFramePassiveNext()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erSetJointFramePassiveNext ( ER_HND  er_hnd,
long  passive_jnt_no,
DFRAME T_nxt 
)
static

Set kinematics transformation to the next joint for each passive joint "Geometric Data to next".
Get the number of passive joints with erGet_num_dofs_passive()
Remarks
see example erGetJointFrameActiveNext()

Parameters
[in]er_hndunique kinematics handle ER_HND
[in]passive_jnt_nopassive joint number[1..number of passive joints], max passive_jnt_no is::ER_KIN_PASSIVE_JNTS
[in]T_nxttransformation to the next joint
Return values
0- OK
1- Error, invalid handle

◆ erSetJointSolutions()

static DLLAPI int ER_STDCALL ERK_CAPI_ROB_KIN_API::erSetJointSolutions ( ER_HND  er_hnd,
double *  q_solutions,
long *  q_warnings 
)
static

Set all robot joint solutions. The kinematics joint data q_solutions are in units [m] for prismatic joint type
and [rad] for rotational joint type
Get the number of active joints with erGet_num_dofs()
Get the number of configurations with erGetNumConfigs()
Remarks
Call this function after calling the inverse kinematics transformation, erInvKinRobotBaseTip(), erInvKinWorldTip(), erInvKinRobotBaseTcp(), erInvKinWorldTcp()

// Example:
double q[ER_KIN_DOFS]; // contains current solution
double q_solutions[ER_KIN_CONFIGS*ER_KIN_DOFS]; // contains all solutions
long q_warnings[ER_KIN_CONFIGS]; // warning for each solution
long ret;
ER_HND c_er_hnd; // valid robot handle
long num_configs;
ret = erGetNumConfigs(c_er_hnd,&num_configs); // Get number of possible robot configurations
long inv_warn = INV_WARN_OK;
inv_warn=erInvKinRobotBaseTcp(c_er_hnd,&bTw); // Calculating the inverse kinematics transformation
erGetJoints(c_er_hnd,q); // Get robot joint data
erGetJointSolutions(c_er_hnd,q_solutions,q_warnings); // Get all robot joint solutions
char *warn_s[] = {"OK" , "SINGULAR" , "UNREACH" , "CNFG" , "INVKIN" , "SWE_EXCEED" , "?"};
for (int i=0;i<num_configs;i++)
{
char s[ER_MAXSTR];
long q_warn = q_warnings[i];
sprintf(s,"q_sol[%d] (%s): ",i,warn_s[q_warn]);
if (q_warn!= INV_WARN_OK && q_warn!= INV_WARN_SINGULAR && q_warn!= INV_WARN_SWE_EXCEED)
{
fprintf(fp,"%s\n",s);
continue;
}
double *dq = &q_solutions[i*ER_KIN_DOFS];
out_vec_joints(fp,s,dq,jointtype,num_dofs);
}
...
Parameters
[in]er_hndunique kinematics handle ER_HND
[in]q_solutionsrobot joint data, max size ER_KIN_CONFIGS * ER_KIN_DOFS
[in]q_warningswarning for each solution, max size ER_KIN_CONFIGS
Return values
0- OK
1- Error, invalid handle

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