Class Kinematics¶
Defined in File KinematicsApi.h
Class Documentation¶
-
class Kinematics¶
Raw API class of the WMX3 kinematics library.
Public Functions
-
Kinematics(WMX3Api *f)¶
-
Kinematics(const Kinematics &src)¶
-
Kinematics()¶
-
~Kinematics()¶
-
Kinematics &operator=(const Kinematics &src)¶
-
bool IsDeviceValid()¶
A device is required to execute most functions in this class. If this function returns FALSE, a device can be created by calling the ‘CreateDevice’ function from the ‘WMX3Api’ object that was passed to the constructor of this class.
- Returns:
TRUE if this class object has access to a device, and FALSE otherwise.
-
inline WMX3Api *GetWMX3Api()¶
Get the WMX3Api instance used by this Kinematics object.
This function returns the WMX3Api instance that this Kinematics object uses.
- Returns:
WMX3 device that the current kinematics API uses. Note if the instance is initialized by the default constructor, it return NULL.
-
WMX3APIFUNC GetVersion(int *majorVersion, int *minorVersion, int *revisionVersion = NULL, int *fixVersion = NULL)¶
Get the Version object.
This function retrieves the version of the kinematics library currently loaded in the WMX3 engine.
Remark
If revisionVersion or fixVersion is NULL, it will not be returned.
- Parameters:
majorVersion – [out] The major version number.
minorVersion – [out] The minor version number.
revisionVersion – [out] The revision version number.
fixVersion – [out] The fix version number.
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetLicenseInfo(LicenseInfo &info)¶
Get the License Info object.
This function retrieves the license information for the kinematics library.
- Parameters:
info – [out] License information structure to be filled with the license details.
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetAllRobotIDs(AllRobotIDs &ids)¶
Get IDs of robots that set in the kinematics module.
This function retrieves the IDs of all robots that are currently set in the kinematics module.
- Parameters:
ids – [out] Resulting collection of robot IDs.
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetRobotParam(const RobotParam &robotParam)¶
Sets or updates the robot parameters in the kinematics engine.
Configures the robot parameters including mechanical specifications, joint limits, tool settings, and other operational parameters. If the robot ID already exists, its parameters will be updated.
Note
This function must be called before performing any kinematics calculations or motion operations for the robot.
- Parameters:
robotParam – [in] Reference to a RobotParam object containing all the configuration parameters for the robot
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetRobotParam(int robotId, RobotParam &robotParam)¶
Retrieves the current parameters of a specified robot.
Gets all the configured parameters for a robot including its mechanical specifications, joint limits, tool settings, and other operational parameters.
- Parameters:
robotId – [in] ID of the robot whose parameters to retrieve
robotParam – [out] Reference to a RobotParam object that will be filled with the robot’s parameters
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC ReleaseRobot(int robotId)¶
Releases resources associated with a specified robot.
Frees all memory and resources allocated for the robot in the kinematics engine. The robot ID will be invalidated and must be re-initialized with SetRobotParam before using again.
Warning
Ensure all motion has stopped and no operations are pending before releasing a robot.
- Parameters:
robotId – [in] ID of the robot to release
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetToolCoordinate(int robotId, const coordinate::CartesianPose &toolCoordinate)¶
Set the tool coordinate to the robot of the given ID.
This function sets the tool coordinate for a robot with the specified ID in the kinematics engine.
- Parameters:
robotId – [in] ID number of the robot
toolCoordinate – [in] tool offset and rotation
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetToolLinkParam(const int robotId, const double toolLinkMass, const coordinate::Point3d &toolLinkOrigin)¶
Set the tool link parameter to the robot of the given ID.
This function sets the tool link parameter for a robot with the specified ID in the kinematics engine.
Remark
The tool link is assumed to be a point mass when applying the inertia matrix.
- Parameters:
robotId – [in] ID number of the robot
toolLinkMass – [in] Mass of the tool link
toolLinkOrigin – [in] Position of the center of mass of the tool link.
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetToolLinkParam(const int robotId, const LinkParam &toolLinkParam)¶
Set the tool link parameter to the robot of the given ID.
This function sets the tool link parameter for a robot with the specified ID in the kinematics engine.
- Parameters:
robotId – [in] ID number of the robot
toolLinkParam – [in] Link parameter of the tool link
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetToolInfo(const int robotId, const coordinate::CartesianPose &toolCoordinate, const double toolLinkMass, const coordinate::Point3d &toolLinkOrigin)¶
Set the tool information to the robot of the given ID.
This function sets the tool information for a robot with the specified ID in the kinematics engine.
Remark
The tool link is assumed to be a point mass when applying the inertia matrix.
- Parameters:
robotId – [in] ID number of the robot
toolCoordinate – [in] tool offset and rotation
toolLinkMass – [in] Mass of the tool link
toolLinkOrigin – [in] Position of the center of mass of the tool link.
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetToolInfo(const int robotId, const coordinate::CartesianPose &toolCoordinate, const LinkParam &toolLinkParam)¶
Set the tool information to the robot of the given ID.
This function sets the tool information for a robot with the specified ID in the kinematics engine.
- Parameters:
robotId – [in] ID number of the robot
toolCoordinate – [in] tool offset and rotation
toolLinkParam – [in] Link parameter of the tool link
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC ClearToolInfo(const int robotId)¶
Clear the tool information to the robot of the given ID.
This function clears the tool information for a robot with the specified ID in the kinematics engine.
- Parameters:
robotId – [in] ID number of the robot
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetWorkCoordinate(int robotId, const coordinate::CartesianPose &workCoordinate)¶
Set the work coordinate to the robot of the given ID.
This function sets the work coordinate for a robot with the specified ID in the kinematics engine.
- Parameters:
robotId – [in] ID number of the robot
workCoordinate – [in] work coordinate values
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetToolCoordinate(int robotId, coordinate::CartesianPose &toolCoordinate)¶
Get the tool coordinate of the robot of the given ID.
This function retrieves the tool coordinate for a robot with the specified ID from the kinematics engine.
- Parameters:
robotId – [in] ID number of the robot
toolCoordinate – [out] result
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetToolLinkParam(const int robotId, LinkParam &toolLinkParam)¶
Get the tool link parameter to the robot of the given ID.
This function retrieves the tool link parameter for a robot with the specified ID from the kinematics engine.
- Parameters:
robotId – [in] ID number of the robot
toolLinkParam – [out] Link parameter of the tool link
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetWorkCoordinate(int robotId, coordinate::CartesianPose &workCoordinate)¶
Get the work coordinate of the robot of the given ID.
This function retrieves the work coordinate for a robot with the specified ID from the kinematics engine.
- Parameters:
robotId – [in] ID number of the robot
workCoordinate – [out] result
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetCommandState(RobotState &robotState)¶
Retrieves the current command state of a single robot.
Gets the commanded state information including target positions, velocities, and other command parameters for the robot.
- Parameters:
robotState – [out] Reference to a RobotState object that will be filled with the current command state data
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetCommandState(RobotState *robotState, int num)¶
Retrieves the current command state of multiple robots.
Gets the commanded state information for an array of robots including target positions, velocities, and other command parameters.
Note
The robotState array must be pre-allocated with sufficient space for num elements before calling this function.
- Parameters:
robotState – [out] Pointer to an array of RobotState objects that will be filled with command state data
num – [in] Number of robots to retrieve states for (size of robotState array)
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetFeedbackState(RobotState &robotState)¶
Retrieves the current feedback state of a single robot.
Gets the actual measured state information including current positions, velocities, and other feedback parameters from the robot’s sensors.
Note
This function returns the actual measured values from the robot, as opposed to GetCommandState which returns target values.
- Parameters:
robotState – [out] Reference to a RobotState object that will be filled with the current feedback state data
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetFeedbackState(RobotState *robotState, int num)¶
Retrieves the current feedback state of multiple robots.
Gets the actual measured state information for an array of robots including current positions, velocities, and other feedback parameters from the robots’ sensors.
Note
The robotState array must be pre-allocated with sufficient space for num elements before calling this function
This function returns actual measured values, as opposed to GetCommandState which returns target values
- Parameters:
robotState – [out] Pointer to an array of RobotState objects that will be filled with feedback state data
num – [in] Number of robots to retrieve states for (size of robotState array)
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC CalcForwardKinematics(const int robotId, const double inputJointPosition[], coordinate::CartesianPose &outputToolPose, char &s, char &e, char &r)¶
Calculates the forward kinematics with configuration flags.
Computes the tool pose (position and orientation) given the joint positions and returns the robot’s configuration flags (S, E, R).
Note
The configuration flags (s,e,r) help identify the specific robot pose when multiple solutions exist for the same tool position.
- Parameters:
robotId – [in] The ID of the target robot
inputJointPosition – [in] Array of joint positions in degrees/mm (size must match robot’s DOF)
outputToolPose – [out] Resulting tool pose in Cartesian space
s – [out] Shoulder configuration flag (Left/Right)
e – [out] Elbow configuration flag (Above/Below)
r – [out] Wrist configuration flag (Flip/No-Flip)
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC CalcForwardKinematics(const int robotId, const double inputJointPosition[], coordinate::CartesianPose &outputToolPose)¶
Calculates the forward kinematics without configuration flags.
Simplified version that computes only the tool pose from given joint positions, without returning the robot’s configuration flags.
See also
CalcForwardKinematics for version with configuration flags
- Parameters:
robotId – [in] The ID of the target robot
inputJointPosition – [in] Array of joint positions in degrees/mm (size must match robot’s DOF)
outputToolPose – [out] Resulting tool pose in Cartesian space
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC CalcInverseKinematics(const int robotId, const coordinate::CartesianPose &inputToolPose, double outputJointPosition[], char s = 0, char e = 0, char r = 0)¶
Calculates the inverse kinematics to find joint positions for a desired tool pose.
Computes the required joint positions to achieve a specified tool pose in Cartesian space. Configuration flags (s,e,r) can be specified to select a specific solution when multiple inverse kinematics solutions exist.
Note
When configuration flags are set to 0, the function will try to find a solution that maintains the current robot configuration. This is useful for continuous motions to avoid sudden configuration changes.
- Parameters:
robotId – [in] The ID of the target robot
inputToolPose – [in] Desired tool pose in Cartesian space
outputJointPosition – [out] Array to store the calculated joint positions in degrees/mm
s – [in] Shoulder configuration flag (Left/Right, default=0)
0: Use current configuration
1: Left shoulder configuration
-1: Right shoulder configuration
e – [in] Elbow configuration flag (Above/Below, default=0)
0: Use current configuration
1: Above elbow configuration
-1: Below elbow configuration
r – [in] Wrist configuration flag (Flip/No-Flip, default=0)
0: Use current configuration
1: No-Flip wrist configuration
-1: Flip wrist configuration
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC EStop(int robotId)¶
Executes an emergency stop on the specified robot.
Immediately halts all robot motion and transitions the robot to an error state. This is a safety-critical function that should be used in emergency situations or when immediate motion termination is required.
Note
This function implements a Level 1 emergency stop condition
All ongoing motions will be immediately terminated
The robot will enter an error state with MotionErrorCode set to ‘UserEStop’
Robot must be reset and re-enabled after an emergency stop
Warning
Use this function only in emergency situations
The stop is immediate and may cause mechanical stress
For normal operation termination, use controlled stop functions instead
- Parameters:
robotId – [in] ID of the robot to emergency stop
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetMotion(int robotId, const coordinate::Trajectory &traj)¶
Sets a new motion trajectory for the robot.
Configures a basic motion trajectory for the robot to follow. The trajectory must be defined before starting the motion.
- Parameters:
robotId – [in] ID of the target robot
traj – [in] Trajectory parameters defining the motion path
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetMotion(int robotId, const coordinate::Trajectory &traj, const coordinate::PoseArray &additionalPose)¶
Sets a motion trajectory with additional pose information.
Configures a motion trajectory with supplementary pose data, useful for complex motions requiring intermediate positions.
- Parameters:
robotId – [in] ID of the target robot
traj – [in] Trajectory parameters defining the motion path
additionalPose – [in] Array of additional poses for the motion
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC ClearMotion(int robotId)¶
Clears all pending motion commands for the robot.
Removes all queued motion commands and resets the motion planning system to its initial state.
Note
This function does not stop current motion. Use StopMotion if you need to halt the robot’s current movement.
- Parameters:
robotId – [in] ID of the target robot
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC StartMotion(int robotId)¶
Starts executing the configured motion trajectory.
Begins execution of the most recently set motion trajectory. The robot must be properly initialized and in a valid state.
- Parameters:
robotId – [in] ID of the target robot
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC StopMotion(int robotId)¶
Stops the current robot motion.
Performs a controlled stop of the robot’s current motion. This is a smoother stop compared to emergency stop.
Note
This is a controlled stop that decelerates the robot according to its motion parameters.
- Parameters:
robotId – [in] ID of the target robot
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC PauseMotion(int robotId)¶
Temporarily pauses the current motion.
Suspends the current motion while maintaining the motion queue. The motion can be resumed using ResumeMotion.
- Parameters:
robotId – [in] ID of the target robot
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC ResumeMotion(int robotId)¶
Resumes a previously paused motion.
Continues execution of a motion that was suspended by PauseMotion. The robot will continue from its current position along the original trajectory.
Note
The motion will resume with a smooth acceleration to maintain safe operation.
- Parameters:
robotId – [in] ID of the target robot
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetMotionState(int robotId, wmx3Api::kinematics::constants::MotionState &motionState)¶
Retrieves the current motion state of the robot.
Gets the current state of the robot’s motion system, including whether it’s moving, stopped, paused, or in an error state.
- Parameters:
robotId – [in] ID of the target robot
motionState – [out] Reference to store the current motion state
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetMotionErrorInfo(int robotId, MotionErrorInfo &errorInfo)¶
Retrieves detailed information about any motion errors.
Gets comprehensive error information when the robot is in an error state, including error codes, descriptions, and related data.
- Parameters:
robotId – [in] ID of the target robot
errorInfo – [out] Reference to store the error information
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC ClearMotionError(int robotId)¶
Clears the motion error state of the robot.
Resets error conditions and allows the robot to resume normal operation after an error has been addressed.
Warning
Ensure the cause of the error has been resolved before clearing the error state.
- Parameters:
robotId – [in] ID of the target robot
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC Wait(int robotId, int triggerType = KinematicsEventData::EventTriggerMotionEnd, long msec = INFINITE)¶
Waits for a specific robot event to occur.
Blocks execution until the specified event occurs or timeout is reached. Commonly used to wait for motion completion or specific robot states.
- Parameters:
robotId – [in] ID of the target robot
triggerType – [in] Type of event to wait for (default: motion end)
msec – [in] Timeout in milliseconds (default: INFINITE)
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC Wait(wmx3Api::EventInput *inputEvent, long msec = INFINITE)¶
Waits for a custom event input.
Waits for a specific event defined by the EventInput object. Useful for synchronizing with external events or conditions.
- Parameters:
inputEvent – [in] Pointer to the event input definition
msec – [in] Timeout in milliseconds (default: INFINITE)
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC Wait(int inputEventModuleId, void *pInputData, int inputDataSize, long msec = INFINITE)¶
Waits for an event with custom input data.
Advanced wait function that can handle module-specific events with custom data parameters.
- Parameters:
inputEventModuleId – [in] ID of the event module
pInputData – [in] Pointer to custom input data
inputDataSize – [in] Size of the input data in bytes
msec – [in] Timeout in milliseconds (default: INFINITE)
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC StartPTPPos(const PTPParam &ptpParam)¶
Initiates a Point-to-Point motion using joint parameters.
Starts a PTP motion using the specified motion parameters. The motion is defined in joint space.
- Parameters:
ptpParam – [in] PTP motion parameters including velocities and accelerations
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC StartPTPPos(const PTPParam &ptpParam, const coordinate::CartesianPose &targetJointPosition, char s = 0, char e = 0, char r = 0)¶
Initiates a Point-to-Point motion to a Cartesian target.
Starts a PTP motion to reach a specified Cartesian pose, with optional configuration flags for inverse kinematics.
- Parameters:
ptpParam – [in] PTP motion parameters
targetJointPosition – [in] Target pose in Cartesian space
s – [in] Shoulder configuration flag (default: 0)
e – [in] Elbow configuration flag (default: 0)
r – [in] Wrist configuration flag (default: 0)
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC StartToolPTPMov(const PTPParam &ptpParam, const coordinate::CartesianPose &displacement, const char &s = 0, const char &e = 0, const char &r = 0)¶
Initiates a Point-to-Point tool motion with displacement.
Starts a PTP motion relative to the current tool position, moving by the specified displacement.
- Parameters:
ptpParam – [in] PTP motion parameters
displacement – [in] Relative displacement in Cartesian space
s – [in] Shoulder configuration flag (default: 0)
e – [in] Elbow configuration flag (default: 0)
r – [in] Wrist configuration flag (default: 0)
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetDestinationOfCurrentMotion(int robotId, coordinate::CartesianPose &result)¶
Retrieves the target position of the current motion.
Gets the final destination pose that the robot is moving towards in the current motion command.
- Parameters:
robotId – [in] ID of the target robot
result – [out] Reference to store the destination pose
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC OverrideVelocityByRatio(int robotId, double velOverrideGain, double accOverrideGain, double decOverrideGain)¶
Overrides the motion velocity and acceleration parameters.
Modifies the current motion’s velocity and acceleration by applying scaling factors to the original values.
Note
Override values should typically be between 0.0 and 1.0 for safe operation. Values greater than 1.0 will increase speed/acceleration beyond original parameters.
- Parameters:
robotId – [in] ID of the target robot
velOverrideGain – [in] Velocity scaling factor (1.0 = 100%)
accOverrideGain – [in] Acceleration scaling factor (1.0 = 100%)
decOverrideGain – [in] Deceleration scaling factor (1.0 = 100%)
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetFittingOn(const int robotId, const bool fittingOn)¶
Enables or disables the fitting function for a robot.
Controls whether the robot should use fitting data for motion compensation. When enabled, the robot will apply fitting data to adjust its movements based on previously calculated fitting parameters.
Note
Fitting must be properly configured with SetFittingData before enabling.
- Parameters:
robotId – [in] ID of the target robot
fittingOn – [in] True to enable fitting, false to disable
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetFittingData(const int robotId, const int jointId, const TorqueConstantsParam &fittingData)¶
Sets the fitting data parameters for a specific joint.
Configures the torque constant parameters used for motion compensation on a particular joint of the robot. This data is used when fitting is enabled to improve motion accuracy.
See also
SetFittingOn to enable/disable the fitting function
- Parameters:
robotId – [in] ID of the target robot
jointId – [in] ID of the joint to configure
fittingData – [in] Torque constant parameters for the joint
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetFittingData(const int robotId, const int jointId, TorqueConstantsParam &fittingData)¶
Retrieves the current fitting data parameters for a specific joint.
Gets the torque constant parameters currently configured for motion compensation on a particular joint of the robot.
- Parameters:
robotId – [in] ID of the target robot
jointId – [in] ID of the joint to query
fittingData – [out] Reference to store the retrieved torque constant parameters
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC CalcFittingData(const int robotId)¶
Calculates fitting data for all joints of the robot.
Performs the computation of torque constant parameters for motion compensation based on the robot’s current state and configuration. This function should be called before using fitting-based motion control.
Note
The calculated data can be retrieved using GetFittingData for each joint.
- Parameters:
robotId – [in] ID of the target robot
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC ClearFittingData(const int robotId)¶
Clears all fitting data for a robot.
Removes all previously calculated or set fitting parameters for all joints of the specified robot. This effectively resets the motion compensation system to its default state.
Note
After clearing, new fitting data must be calculated or set before enabling fitting-based motion control.
- Parameters:
robotId – [in] ID of the target robot
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC SetCollisionParam(const int robotId, const CollisionParam &collisionParam)¶
Sets the collision detection parameters for a robot.
Configures the parameters used by the collision detection system to determine when a collision has occurred. These parameters include thresholds and sensitivity settings for collision detection.
Note
Proper configuration of collision parameters is crucial for safe operation of the robot.
- Parameters:
robotId – [in] ID of the target robot
collisionParam – [in] Collision detection parameters to be set
- Returns:
0 if success, otherwise return error code.
-
WMX3APIFUNC GetCollisionParam(const int robotId, CollisionParam &collisionParam)¶
Retrieves the current collision detection parameters for a robot.
Gets the current configuration of the collision detection system, including thresholds and sensitivity settings used to determine when a collision has occurred.
- Parameters:
robotId – [in] ID of the target robot
collisionParam – [out] Reference to store the retrieved collision parameters
- Returns:
0 if success, otherwise return error code.
Public Static Functions
-
static WMX3APIFUNC ErrorToString(int errCode, char *pString, unsigned int size)¶
Get a string representation of the specified error code.
This function retrieves a string that describes the error associated with the given error code.
- Parameters:
errCode – [in] The error code to get the string representation of.
pString – [out] A char array that will contain the string representation of the error.
size – [in] The size of the char array in number of characters.
- Returns:
0 if success, otherwise return error code.
-
static WMX3APIFUNC ErrorToStringU(int errCode, TCHAR *pString, unsigned int size)¶
Get a string representation of the specified error code.
This function is used to convert an error code into a human-readable string.
- Parameters:
errCode – [in] The error code to get the string representation of.
pString – [out] A char array that will contain the string representation of the error.
size – [in] The size of the char array in number of characters.
- Returns:
-
static WMX3APIFUNC GetLibVersion(int *majorVersion, int *minorVersion, int *revisionVersion = NULL, int *fixVersion = NULL)¶
Get the version of the kinematics library.
This function retrieves the version of the kinematics library currently loaded in the WMX3 engine.
Remark
If revisionVersion or fixVersion is NULL, it will not be returned.
- Parameters:
majorVersion – [out] The major version number.
minorVersion – [out] The minor version number.
revisionVersion – [out] The revision version number.
fixVersion – [out] The fix version number.
- Returns:
0 if success, otherwise return error code.
-
Kinematics(WMX3Api *f)¶