Class AdvMotion
Defined in File AdvancedMotionApi.h
Nested Relationships
Nested Types
Class Documentation
-
class AdvMotion
This class contains advanced position command functions.
Public Functions
-
inline AdvMotion(AdvancedMotion *f)
-
bool IsDeviceValid()
-
WMX3APIFUNC CreateSplineBuffer(int channel, unsigned int points)
Allocate buffer memory for a spline execution channel.
Allocate buffer memory for a spline execution channel.
When the WMX3 engine is started, no memory is allocated for execution of spline motion commands. This function must be called before a spline motion command can be executed.
Remark
Each channel has a separate buffer memory space. This function must be called for each channel before that channel can execute spline motion commands. Each channel can execute one spline motion command at one time. To execute two spline motion commands at the same time, buffer memory space must be allocated for two channels. However, if two spline motion commands are executed sequentially with no overlap, only one channel is required, even if the spline motion commands control different axes.
Allocating buffer memory space is an operation that can fail due to lack of memory space or fragmentation of memory. For deterministic operation, this function should be called during initialization to allocate memory for all spline execution channels that will potentially be used by the program.
The maximum size of the buffer memory space of a spline execution channel is 2GB-1Byte (2147483647 bytes). Specifying a larger size will cause this function to return the RequestedBufferTooLarge error.
It is not necessary to call this function again after buffer memory has been allocated once. (When the WMX3 engine is restarted, this function must be called again to allocate buffer memory.)
Buffer memory that has been allocated can be freed using the FreeSplineBuffer function. After freeing the buffer memory of a spline execution channel, this function can be called again to reallocate a different amount of buffer memory.
It is not necessary to free allocated memory using FreeSplineBuffer before exiting the program. Any allocated memory is automatically freed when the WMX3 engine is closed.
The GetSplineBufferPoints function can be used to find the amount of buffer memory currently allocated to a spline execution channel.
The GetSplineBytesPerPoint function can be used to convert the buffer memory size from points to bytes.
See also
- Parameters:
channel – [in] The spline execution channel. The maximum number of available channels is maxSplineChannel.
points – [in] The number of points to allocate memory for. Each spline point occupies one point in the memory. Setting the sampleMultiplier parameter of a VelAccLimitedSplineCommand to a value greater than 1 will multiply the number of points occupied by one spline point. For example, if sampleMultiplier is set to 10, each point in the spline will require 10 points worth of buffer memory to store.
-
WMX3APIFUNC FreeSplineBuffer(int channel)
Free buffer memory for a spline execution channel.
Free buffer memory for a spline execution channel.
This function frees the buffer memory that has been allocated with the CreateSplineBuffer function. This allows CreateSplineBuffer to be called again to allocate a different amount of memory.
Remark
It is not necessary to call this function before exiting the program, as any allocated memory is automatically freed when the WMX3 engine closes.
The freed memory, after a brief delay, will become available for the system to use for another purpose.
- Parameters:
channel – [in] The spline execution channel. The maximum number of available channels is maxSplineChannel.
-
WMX3APIFUNC GetSplineBufferPoints(int channel, unsigned int *pPoints)
Get the amount of buffer memory currently allocated to a spline execution channel.
Get the amount of buffer memory currently allocated to a spline execution channel.
This function obtains the amount of buffer memory currently allocated to a spline execution channel, in units of points.
Remark
To convert the buffer memory size from the number of points to bytes, use the GetSplineBytesPerPoint function.
If no buffer memory has been allocated to the specified channel yet, this function will return 0 in the pPoints parameter.
- Parameters:
channel – [in] The spline execution channel. The maximum number of available channels is maxSplineChannel.
pPoints – [out] A pointer to an unsigned int that will contain the number of points that can be stored in the buffer memory.
-
WMX3APIFUNC GetSplineBytesPerPoint(unsigned int *pBytes)
Get the number of bytes required per point data in the spline execution buffer memory.
Get the number of bytes required per point data in the spline execution buffer memory.
This function obtains the number of bytes of memory required to store one point data in the spline execution buffer memory. This can be used to calculate the number of bytes of buffer memory required to store a particular number of points. For example, if this function returns 192, the number of bytes required to store 100000 points is 192*100000 = 19200000, or approximately 18.3MB.
Remark
- Parameters:
pBytes – [out] A pointer to an unsigned int that will contain the number of bytes of memory required per point data.
-
WMX3APIFUNC StartCSplinePos(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds)
Start a cubic spline motion command in which the time at each point is specified. The point positions are specified as absolute positions.
Start a cubic spline motion command in which the time at each point is specified. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point in order at the specified times. The velocities and accelerations of the commanded axes will be continuous throughout the entire motion, so the resulting path will be smooth. However, if the points and times are not specified carefully, the commanded axes may reach a very high velocity or acceleration during the motion (although the velocity and acceleration will still be continuous).
Remark
This type of spline is suitable if the time at which each point is traversed must be specified.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
The time at each point must be specified in ascending order, or else an error will be returned. The first time will automatically be set to 0, and does not need to be passed to this function. If the first time passed to this function is equal to 0, that time will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will decelerate to a stop along the spline path using the approximate maximum composite acceleration that would be applied to the axes when executing the spline command.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
-
WMX3APIFUNC StartCSplinePos(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic spline motion command in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
Start a cubic spline motion command in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point, completing the spline using the specified total time. The velocities and accelerations of the commanded axes will be continuous throughout the entire motion, so the resulting path will be smooth. The velocity along the spline will be relatively constant, so one or more commanded axes may undergo high acceleration if there is a sharp corner in the given point data.
Remark
The time at which each point is traversed is calculated taking into account the distance between the points, the acceleration at the beginning, and the deceleration at the end.
This type of spline is suitable for motion where the total time to complete the spline is important, and there is no sharp corner in the given point data. If there is a sharp corner in the point data, one or more commanded axes may undergo high acceleration, even if the velocity along the spline is relatively constant. At these sharp corners, the velocity may also suddenly and momentarily increase or decrease.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will decelerate to a stop along the spline path using the approximate maximum composite acceleration that would be applied to the axes when executing the spline command.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCSplinePos(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic spline motion command in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
Start a cubic spline motion command in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point, traveling along the spline using the specified motion profile. The velocities and accelerations of the commanded axes will be continuous throughout the entire motion, so the resulting path will be smooth. The velocity along the spline will be relatively constant, so one or more commanded axes may have high acceleration if there is a sharp corner in the given point data.
Remark
Compared to StartCSplinePos, this function has the following differences:
The velocity, acceleration, jerk, etc. that is used is directly specified instead of being calculated from the specified time.
All available profile shapes in ProfileType can be used.
Acceleration and deceleration along the spline path can stretch over several points or a fraction of a point. With StartCSplinePos, acceleration along the spline path occurs only between the first point and second point, and deceleration along the spline path occurs only between the last point and second to last point.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will gradually stop along the spline path using the deceleration parameters specified in the profile argument.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
If a large value is specified for the sampleMultiplier parameter, the time and distance between points will become smaller from the added sample points, and may cause the TimeBetweenPointsTooClose or DistanceBetweenPointsTooClose errors to be returned. If this occurs, reduce the sampleMultiplier.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCSplinePos(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
Start a cubic spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point, traveling along the spline at the specified velocity and acceleration, while staying within the velocity and acceleration limits of each individual axis.
Remark
This type of spline is suitable for point data containing sharp corners. Each axis will decelerate at corners to stay within the velocity and acceleration limits of that axis. The entire spline is considered when calculating the deceleration, so the axes may start to decelerate from several points before the sharp corner. The deceleration is optimized so that the spline will be traversed in approximately the shortest amount of time possible with the given velocity and acceleration constraints.
Because the velocities and accelerations along the spline are sampled at certain non-constant intervals (that are typically greater than one cycle), there will be some approximation and the velocities and accelerations during some cycles may exceed the specified composite values or the limits by a small percentage. Increasing the sample count can improve the accuracy of the velocity and acceleration limits.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will decelerate to a stop along the spline path using the approximate maximum composite acceleration that would be applied to the axes when executing the spline command.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
If a large value is specified for the sampleMultiplier parameter, the time and distance between points will become smaller from the added sample points, and may cause the TimeBetweenPointsTooClose or DistanceBetweenPointsTooClose errors to be returned. If this occurs, reduce the sampleMultiplier.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCSplineMov(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds)
Start a cubic spline motion command in which the time at each point is specified. The point positions are specified as relative positions.
Start a cubic spline motion command in which the time at each point is specified. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
-
WMX3APIFUNC StartCSplineMov(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic spline motion command in which the total time to complete the spline is specified. The point positions are specified as relative positions.
Start a cubic spline motion command in which the total time to complete the spline is specified. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCSplineMov(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic spline motion command in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
Start a cubic spline motion command in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCSplineMov(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
Start a cubic spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCSplinePos(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds, Trigger *pTrigger)
Start a triggered cubic spline motion command in which the time at each point is specified. The point positions are specified as absolute positions.
Start a triggered cubic spline motion command in which the time at each point is specified. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point in order at the specified times. The velocities and accelerations of the commanded axes will be continuous throughout the entire motion, so the resulting path will be smooth. However, if the points and times are not specified carefully, the commanded axes may reach a very high velocity or acceleration during the motion (although the velocity and acceleration will still be continuous).
Remark
This type of spline is suitable if the time at which each point is traversed must be specified.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
The time at each point must be specified in ascending order, or else an error will be returned. The first time will automatically be set to 0, and does not need to be passed to this function. If the first time passed to this function is equal to 0, that time will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will decelerate to a stop along the spline path using the approximate maximum composite acceleration that would be applied to the axes when executing the spline command.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCSplinePos(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic spline motion command in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
Start a triggered cubic spline motion command in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point, completing the spline using the specified total time. The velocities and accelerations of the commanded axes will be continuous throughout the entire motion, so the resulting path will be smooth. The velocity along the spline will be relatively constant, so one or more commanded axes may undergo high acceleration if there is a sharp corner in the given point data.
Remark
The time at which each point is traversed is calculated taking into account the distance between the points, the acceleration at the beginning, and the deceleration at the end.
This type of spline is suitable for motion where the total time to complete the spline is important, and there is no sharp corner in the given point data. If there is a sharp corner in the point data, one or more commanded axes may undergo high acceleration, even if the velocity along the spline is relatively constant. At these sharp corners, the velocity may also suddenly and momentarily increase or decrease.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will decelerate to a stop along the spline path using the approximate maximum composite acceleration that would be applied to the axes when executing the spline command.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCSplinePos(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic spline motion command in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
Start a triggered cubic spline motion command in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point, traveling along the spline using the specified motion profile. The velocities and accelerations of the commanded axes will be continuous throughout the entire motion, so the resulting path will be smooth. The velocity along the spline will be relatively constant, so one or more commanded axes may have high acceleration if there is a sharp corner in the given point data.
Remark
Compared to StartCSplinePos, this function has the following differences:
The velocity, acceleration, jerk, etc. that is used is directly specified instead of being calculated from the specified time.
All available profile shapes in ProfileType can be used.
Acceleration and deceleration along the spline path can stretch over several points or a fraction of a point. With StartCSplinePos, acceleration along the spline path occurs only between the first point and second point, and deceleration along the spline path occurs only between the last point and second to last point.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will gradually stop along the spline path using the deceleration parameters specified in the profile argument.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
If a large value is specified for the sampleMultiplier parameter, the time and distance between points will become smaller from the added sample points, and may cause the TimeBetweenPointsTooClose or DistanceBetweenPointsTooClose errors to be returned. If this occurs, reduce the sampleMultiplier.
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCSplinePos(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
Start a triggered cubic spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point, traveling along the spline at the specified velocity and acceleration, while staying within the velocity and acceleration limits of each individual axis.
Remark
This type of spline is suitable for point data containing sharp corners. Each axis will decelerate at corners to stay within the velocity and acceleration limits of that axis. The entire spline is considered when calculating the deceleration, so the axes may start to decelerate from several points before the sharp corner. The deceleration is optimized so that the spline will be traversed in approximately the shortest amount of time possible with the given velocity and acceleration constraints.
Because the velocities and accelerations along the spline are sampled at certain non-constant intervals (that are typically greater than one cycle), there will be some approximation and the velocities and accelerations during some cycles may exceed the specified composite values or the limits by a small percentage. Increasing the sample count can improve the accuracy of the velocity and acceleration limits.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will decelerate to a stop along the spline path using the approximate maximum composite acceleration that would be applied to the axes when executing the spline command.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
If a large value is specified for the sampleMultiplier parameter, the time and distance between points will become smaller from the added sample points, and may cause the TimeBetweenPointsTooClose or DistanceBetweenPointsTooClose errors to be returned. If this occurs, reduce the sampleMultiplier.
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCSplineMov(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds, Trigger *pTrigger)
Start a triggered cubic spline motion command in which the time at each point is specified. The point positions are specified as relative positions.
Start a triggered cubic spline motion command in which the time at each point is specified. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCSplineMov(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic spline motion command in which the total time to complete the spline is specified. The point positions are specified as relative positions.
Start a triggered cubic spline motion command in which the total time to complete the spline is specified. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCSplineMov(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic spline motion command in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
Start a triggered cubic spline motion command in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCSplineMov(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
Start a triggered cubic spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCSplinePos(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds, TriggerEvents *pTriggerEvents)
Start a triggered cubic spline motion command with multiple trigger events in which the time at each point is specified. The point positions are specified as absolute positions.
Start a triggered cubic spline motion command with multiple trigger events in which the time at each point is specified. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point in order at the specified times. The velocities and accelerations of the commanded axes will be continuous throughout the entire motion, so the resulting path will be smooth. However, if the points and times are not specified carefully, the commanded axes may reach a very high velocity or acceleration during the motion (although the velocity and acceleration will still be continuous).
Remark
This type of spline is suitable if the time at which each point is traversed must be specified.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
The time at each point must be specified in ascending order, or else an error will be returned. The first time will automatically be set to 0, and does not need to be passed to this function. If the first time passed to this function is equal to 0, that time will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will decelerate to a stop along the spline path using the approximate maximum composite acceleration that would be applied to the axes when executing the spline command.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCSplinePos(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic spline motion command with multiple trigger events in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
Start a triggered cubic spline motion command with multiple trigger events in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point, completing the spline using the specified total time. The velocities and accelerations of the commanded axes will be continuous throughout the entire motion, so the resulting path will be smooth. The velocity along the spline will be relatively constant, so one or more commanded axes may undergo high acceleration if there is a sharp corner in the given point data.
Remark
The time at which each point is traversed is calculated taking into account the distance between the points, the acceleration at the beginning, and the deceleration at the end.
This type of spline is suitable for motion where the total time to complete the spline is important, and there is no sharp corner in the given point data. If there is a sharp corner in the point data, one or more commanded axes may undergo high acceleration, even if the velocity along the spline is relatively constant. At these sharp corners, the velocity may also suddenly and momentarily increase or decrease.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will decelerate to a stop along the spline path using the approximate maximum composite acceleration that would be applied to the axes when executing the spline command.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCSplinePos(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic spline motion command with multiple trigger events in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
Start a triggered cubic spline motion command with multiple trigger events in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point, traveling along the spline using the specified motion profile. The velocities and accelerations of the commanded axes will be continuous throughout the entire motion, so the resulting path will be smooth. The velocity along the spline will be relatively constant, so one or more commanded axes may have high acceleration if there is a sharp corner in the given point data.
Remark
Compared to StartCSplinePos, this function has the following differences:
The velocity, acceleration, jerk, etc. that is used is directly specified instead of being calculated from the specified time.
All available profile shapes in ProfileType can be used.
Acceleration and deceleration along the spline path can stretch over several points or a fraction of a point. With StartCSplinePos, acceleration along the spline path occurs only between the first point and second point, and deceleration along the spline path occurs only between the last point and second to last point.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will gradually stop along the spline path using the deceleration parameters specified in the profile argument.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
If a large value is specified for the sampleMultiplier parameter, the time and distance between points will become smaller from the added sample points, and may cause the TimeBetweenPointsTooClose or DistanceBetweenPointsTooClose errors to be returned. If this occurs, reduce the sampleMultiplier.
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCSplinePos(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic spline motion command with multiple trigger events in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
Start a triggered cubic spline motion command with multiple trigger events in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
During a cubic spline motion, the commanded axes will traverse each point, traveling along the spline at the specified velocity and acceleration, while staying within the velocity and acceleration limits of each individual axis.
Remark
This type of spline is suitable for point data containing sharp corners. Each axis will decelerate at corners to stay within the velocity and acceleration limits of that axis. The entire spline is considered when calculating the deceleration, so the axes may start to decelerate from several points before the sharp corner. The deceleration is optimized so that the spline will be traversed in approximately the shortest amount of time possible with the given velocity and acceleration constraints.
Because the velocities and accelerations along the spline are sampled at certain non-constant intervals (that are typically greater than one cycle), there will be some approximation and the velocities and accelerations during some cycles may exceed the specified composite values or the limits by a small percentage. Increasing the sample count can improve the accuracy of the velocity and acceleration limits.
The first point will automatically be set to the current position of the commanded axes, and does not need to be passed to this function. If the first point passed to this function is equal to the current position of the commanded axes, that point will be ignored.
When stopping the spline motion using the Stop function, the interpolating axes will decelerate to a stop along the spline path using the approximate maximum composite acceleration that would be applied to the axes when executing the spline command.
The minimum time between points is 1 microsecond (1e-3 milliseconds). Exceeding this limit will cause the TimeBetweenPointsTooClose error to be returned.
The minimum distance between points is 1e-6 user units. If there are consecutive points with less than this distance, the latter point will be ignored. If this causes the number of points to be less than 2 (excluding the first point), the PointCountBelowMinimum error will be returned.
If a large value is specified for the sampleMultiplier parameter, the time and distance between points will become smaller from the added sample points, and may cause the TimeBetweenPointsTooClose or DistanceBetweenPointsTooClose errors to be returned. If this occurs, reduce the sampleMultiplier.
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCSplineMov(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds, TriggerEvents *pTriggerEvents)
Start a triggered cubic spline motion command with multiple trigger events in which the time at each point is specified. The point positions are specified as relative positions.
Start a triggered cubic spline motion command with multiple trigger events in which the time at each point is specified. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCSplineMov(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic spline motion command with multiple trigger events in which the total time to complete the spline is specified. The point positions are specified as relative positions.
Start a triggered cubic spline motion command with multiple trigger events in which the total time to complete the spline is specified. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCSplineMov(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic spline motion command with multiple trigger events in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
Start a triggered cubic spline motion command with multiple trigger events in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCSplineMov(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic spline motion command with multiple trigger events in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
Start a triggered cubic spline motion command with multiple trigger events in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
This is a relative position version of the StartCSplinePos function, where all point positions are specified relative to the command positions of the commanded axes at the time that this function is executed.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCBSplinePos(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds)
Start a cubic basis spline motion command in which the time at each point is specified. The point positions are specified as absolute positions.
Start a cubic basis spline motion command in which the time at each point is specified. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
-
WMX3APIFUNC StartCBSplinePos(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic basis spline motion command in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
Start a cubic basis spline motion command in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCBSplinePos(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic basis spline motion command in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
Start a cubic basis spline motion command in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCBSplinePos(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic basis spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
Start a cubic basis spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCBSplineMov(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds)
Start a cubic basis spline motion command in which the time at each point is specified. The point positions are specified as relative positions.
Start a cubic basis spline motion command in which the time at each point is specified. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
-
WMX3APIFUNC StartCBSplineMov(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic basis spline motion command in which the total time to complete the spline is specified. The point positions are specified as relative positions.
Start a cubic basis spline motion command in which the total time to complete the spline is specified. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCBSplineMov(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic basis spline motion command in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
Start a cubic basis spline motion command in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCBSplineMov(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint)
Start a cubic basis spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
Start a cubic basis spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
-
WMX3APIFUNC StartCBSplinePos(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds, Trigger *pTrigger)
Start a triggered cubic basis spline motion command in which the time at each point is specified. The point positions are specified as absolute positions.
Start a triggered cubic basis spline motion command in which the time at each point is specified. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCBSplinePos(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic basis spline motion command in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
Start a triggered cubic basis spline motion command in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCBSplinePos(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic basis spline motion command in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
Start a triggered cubic basis spline motion command in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCBSplinePos(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic basis spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
Start a triggered cubic basis spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCBSplineMov(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds, Trigger *pTrigger)
Start a triggered cubic basis spline motion command in which the time at each point is specified. The point positions are specified as relative positions.
Start a triggered cubic basis spline motion command in which the time at each point is specified. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCBSplineMov(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic basis spline motion command in which the total time to complete the spline is specified. The point positions are specified as relative positions.
Start a triggered cubic basis spline motion command in which the total time to complete the spline is specified. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCBSplineMov(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic basis spline motion command in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
Start a triggered cubic basis spline motion command in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCBSplineMov(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, Trigger *pTrigger)
Start a triggered cubic basis spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
Start a triggered cubic basis spline motion command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
-
WMX3APIFUNC StartCBSplinePos(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds, TriggerEvents *pTriggerEvents)
Start a triggered cubic basis spline motion command with multiple trigger events in which the time at each point is specified. The point positions are specified as absolute positions.
Start a triggered cubic basis spline motion command with multiple trigger events in which the time at each point is specified. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCBSplinePos(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic basis spline motion command with multiple trigger events in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
Start a triggered cubic basis spline motion command with multiple trigger events in which the total time to complete the spline is specified. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCBSplinePos(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic basis spline motion command with multiple trigger events in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
Start a triggered cubic basis spline motion command with multiple trigger events in which the spline is traversed using a motion profile. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCBSplinePos(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic basis spline motion command with multiple trigger events in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
Start a triggered cubic basis spline motion command with multiple trigger events in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as absolute positions.
This function is similar to the StartCSplinePos function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCBSplineMov(int channel, PointTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, double *pPointTimeMilliseconds, TriggerEvents *pTriggerEvents)
Start a triggered cubic basis spline motion command with multiple trigger events in which the time at each point is specified. The point positions are specified as relative positions.
Start a triggered cubic basis spline motion command with multiple trigger events in which the time at each point is specified. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a PointTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pPointTimeMilliseconds – [in] An array of doubles that contain the spline time data. The N-th index of the array specifies the time data of the N-th index of the pPoint array. The length of the array must be equal to numPoints. The times are specified in units of milliseconds.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCBSplineMov(int channel, TotalTimeSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic basis spline motion command with multiple trigger events in which the total time to complete the spline is specified. The point positions are specified as relative positions.
Start a triggered cubic basis spline motion command with multiple trigger events in which the total time to complete the spline is specified. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a TotalTimeSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCBSplineMov(int channel, ProfileSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic basis spline motion command with multiple trigger events in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
Start a triggered cubic basis spline motion command with multiple trigger events in which the spline is traversed using a motion profile. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a ProfileSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC StartCBSplineMov(int channel, VelAccLimitedSplineCommand *pSplineCommand, unsigned int numPoints, SplinePoint *pPoint, TriggerEvents *pTriggerEvents)
Start a triggered cubic basis spline motion command with multiple trigger events in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
Start a triggered cubic basis spline motion command with multiple trigger events in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis. The point positions are specified as relative positions.
This function is similar to the StartCSplineMov function, except the specified points are not necessarily traversed (except for the first point and last point). Instead, the spline path will be pulled toward each point so that it travels close to that point.
Remark
The motion will begin when the specified multi-event trigger condition is satisfied.
See also
- Parameters:
channel – [in] The spline channel to execute the spline motion command.
pSplineCommand – [in] A pointer to a VelAccLimitedSplineCommand that contains the spline parameters.
numPoints – [in] The number of points in the pPoint array that is passed to this function. This value must be at least 2.
pPoint – [in] An array of SplinePoint objects that contain the spline point data. The length of the array must be equal to numPoints.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
-
WMX3APIFUNC CreatePathIntplBuffer(int axis, unsigned int points)
Allocate buffer memory to an axis for the execution of path interpolation commands.
Allocate buffer memory to an axis for the execution of path interpolation commands.
When the WMX3 engine is started, no memory is allocated for the execution of path interpolation commands. This function allocates memory to execute the following path interpolation commands:
Remark
If any of the above commands are called before this function, a default buffer memory for maxPathInterpolateAppendPoints will be allocated. If the memory allocation fails, or if more than maxPathInterpolateAppendPoints points are specified, the path interpolation command will return an error. To execute a path interpolation command with more than maxPathInterpolateAppendPoints points, this function must be called beforehand, specifying the required number of points.
The buffer memory allocated to the axis assigned to axis[0] of the path interpolation command will be used to execute the path interpolation. The buffer memory of the remaining interpolation axes are not used.
Allocating buffer memory space is an operation that can fail due to lack of memory space or fragmentation of memory. For deterministic operation, this function should be called during initialization to allocate memory for all axes that will potentially be the first axis of a path interpolation motion command.
The maximum size of the path interpolation buffer memory space of each axis is 2GB-1Byte (2147483647 bytes). Specifying a larger size will cause this function to return the RequestedBufferTooLarge error.
It is not necessary to call this function again after buffer memory has been allocated once. (When the WMX3 engine is restarted, this function must be called again to allocate buffer memory.)
Buffer memory that has been allocated can be freed using the FreePathIntplBuffer function. After freeing the path interpolation buffer memory of an axis, this function can be called again to reallocate a different amount of buffer memory.
It is not necessary to free allocated memory using FreePathIntplBuffer before exiting the program. Any allocated memory is automatically freed when the WMX3 engine is closed.
The GetPathIntplBufferPoints function can be used to find the amount of path interpolation buffer memory currently allocated to an axis.
The GetPathIntplBytesPerPoint function can be used to convert the buffer memory size from points to bytes.
See also
- Parameters:
axis – [in] The axis to allocate the buffer memory.
points – [in] The number of points to allocate memory for. Each path interpolation segment and each circular interpolation segment inserted by auto smoothing occupies one point in the memory.
-
WMX3APIFUNC FreePathIntplBuffer(int axis)
Free path interpolation buffer memory for an axis.
Free path interpolation buffer memory for an axis.
This function frees the buffer memory that has been allocated with the CreatePathIntplBuffer function. This allows CreatePathIntplBuffer to be called again to allocate a different amount of memory.
Remark
It is not necessary to call this function before exiting the program, as any allocated memory is automatically freed when the WMX3 engine closes.
The freed memory, after a brief delay, will become available for the system to use for another purpose.
- Parameters:
axis – [in] The axis to free the buffer memory.
-
WMX3APIFUNC GetPathIntplBufferPoints(int axis, unsigned int *pPoints)
Get the amount of path interpolation buffer memory currently allocated to an axis.
Get the amount of path interpolation buffer memory currently allocated to an axis.
This function obtains the amount of path interpolation buffer memory currently allocated to an axis, in units of points (interpolation segments).
Remark
To convert the buffer memory size from the number of points to bytes, use the GetPathIntplBytesPerPoint function.
If no buffer memory has been allocated to the specified channel yet, this function will return 0 in the pPoints parameter.
- Parameters:
axis – [in] The axis to read the buffer memory size.
pPoints – [out] A pointer to an unsigned int that will contain the number of points that can be stored in the buffer memory.
-
WMX3APIFUNC GetPathIntplBytesPerPoint(unsigned int *pBytes)
Get the number of bytes required per point data in the path interpolation buffer memory.
Get the number of bytes required per point data in the path interpolation buffer memory.
This function obtains the number of bytes of memory required to store one point data in the path interpolation buffer memory. This can be used to calculate the number of bytes of buffer memory required to store a particular number of points. For example, if this function returns 440, the number of bytes required to store 100000 points is 440*100000 = 44000000, or approximately 44MB.
Remark
- Parameters:
pBytes – [out] A pointer to an unsigned int that will contain the number of bytes of memory required per point data.
-
WMX3APIFUNC StartPathIntplPos(PathIntplCommand *pPathIntplCommand, unsigned int numAddlCommands = 0, PathIntplAdditionalCommand *pPathIntplAddlCommand = NULL)
Start an absolute position path interpolation motion command. This motion combines line interpolation and circular interpolation in one path.
Start an absolute position path interpolation motion command. This motion combines line interpolation and circular interpolation in one path.
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
Remark
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters. All positions are specified as absolute positions.
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntplAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC StartPathIntplMov(PathIntplCommand *pPathIntplCommand, unsigned int numAddlCommands = 0, PathIntplAdditionalCommand *pPathIntplAddlCommand = NULL)
Start a relative position path interpolation motion command. This motion combines line interpolation and circular interpolation in one path.
Start a relative position path interpolation motion command. This motion combines line interpolation and circular interpolation in one path.
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
Remark
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters. All positions are specified as relative positions (relative to the command positions at the time that this function is executed).
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntplAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC StartPathIntplPos(PathIntplCommand *pPathIntplCommand, Trigger *pTrigger, unsigned int numAddlCommands = 0, PathIntplAdditionalCommand *pPathIntplAddlCommand = NULL)
Start an absolute position triggered path interpolation motion command. This motion combines line interpolation and circular interpolation in one path.
Start an absolute position triggered path interpolation motion command. This motion combines line interpolation and circular interpolation in one path.
This function starts a path interpolation motion with a trigger condition. The motion will only begin when the specified trigger condition is satisfied. All positions are specified as absolute positions.
Remark
The StaggeredDistanceCompletion trigger type is not supported by this function. Specifying this trigger type will cause the function to return an error.
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntplAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC StartPathIntplMov(PathIntplCommand *pPathIntplCommand, Trigger *pTrigger, unsigned int numAddlCommands = 0, PathIntplAdditionalCommand *pPathIntplAddlCommand = NULL)
Start a relative position triggered path interpolation motion command. This motion combines line interpolation and circular interpolation in one path.
Start a relative position triggered path interpolation motion command. This motion combines line interpolation and circular interpolation in one path.
This function starts a path interpolation motion with a trigger condition. The motion will only begin when the specified trigger condition is satisfied. All positions are specified as relative positions (relative to the command positions at the time that this function is executed).
Remark
The StaggeredDistanceCompletion trigger type is not supported by this function. Specifying this trigger type will cause the function to return an error.
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntplAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC StartPathIntplPos(PathIntplCommand *pPathIntplCommand, TriggerEvents *pTriggerEvents, unsigned int numAddlCommands = 0, PathIntplAdditionalCommand *pPathIntplAddlCommand = NULL)
Start an absolute position triggered path interpolation motion command with multiple trigger events. This motion combines line interpolation and circular interpolation in one path.
Start an absolute position triggered path interpolation motion command with multiple trigger events. This motion combines line interpolation and circular interpolation in one path.
This function starts a path interpolation motion with a multi-event trigger condition. The motion will only begin when the specified multi-event trigger condition is satisfied. All positions are specified as absolute positions.
Remark
The StaggeredDistanceCompletion trigger type is not supported by this function. Specifying this trigger type will cause the function to return an error.
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntplAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC StartPathIntplMov(PathIntplCommand *pPathIntplCommand, TriggerEvents *pTriggerEvents, unsigned int numAddlCommands = 0, PathIntplAdditionalCommand *pPathIntplAddlCommand = NULL)
Start a relative position triggered path interpolation motion command with multiple trigger events. This motion combines line interpolation and circular interpolation in one path.
Start a relative position triggered path interpolation motion command with multiple trigger events. This motion combines line interpolation and circular interpolation in one path.
This function starts a path interpolation motion with a multi-event trigger condition. The motion will only begin when the specified multi-event trigger condition is satisfied. All positions are specified as relative positions (relative to the command positions at the time that this function is executed).
Remark
The StaggeredDistanceCompletion trigger type is not supported by this function. Specifying this trigger type will cause the function to return an error.
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntplAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC OverridePathIntplVelocityMultiplier(int axis, double multiplier)
Override a path interpolation motion using a velocity multiplier.
Override a path interpolation motion using a velocity multiplier.
This function can be called while executing a path interpolation to change the profile velocity by the specified factor. The interpolating axes will accelerate or decelerate to the new velocity using the acceleration or deceleration of the path interpolation command.
Remark
This function may be called multiple times. Each time this function is called, the new velocity is calculated as the original profile velocity of the path interpolation multiplied by the specified velocity multiplier.
All other profile parameters, including the starting velocity and end velocity, are not changed by this function (except as noted below). The target positions of the path interpolation are not changed.
If a different profile is specified for each segment of the path, the velocities of all profiles are multiplied by the specified multiplier. The end velocities of all profiles are also multiplied by the specified multiplier, except for the end velocity of the final segment of the path.
The velocity multiplier must be between 0 and 2 inclusive. For example, to set the velocity to 50% of the original profile velocity, pass 0.5 to the multiplier argument. If 1 is passed to the multiplier argument, the velocity will be set equal to the original profile velocity of the path interpolation.
If 0 is passed to the multiplier argument, the path interpolation will be paused as if the Pause function is called. The path interpolation can be resumed by calling this function again with a nonzero multiplier (the path interpolation can also be resumed by calling the Resume function, in which case the motion will be resumed using the multiplier immediately before it was paused).
This function can also be used in place of the Resume function to resume a path interpolation that has been paused with the Pause function.
If the velocity after applying the multiplier is below 1 user unit per second, the new velocity will be set to 1 user unit per second.
Either of the two axes executing path interpolation can be passed to the axis argument. This operation of this function will be the same regardless of which of the axes is specified.
When this function is called, the profile of the path interpolation will be recalculated. The standard behavior of overrides apply (see Acceleration Reset).
If the specified axis is not executing a path interpolation command started with StartPathIntplPos or StartPathIntplMov, this function will return an error.
- Parameters:
axis – [in] The axis executing the path interpolation.
multiplier – [in] The velocity multiplier to apply.
-
WMX3APIFUNC StartPathIntpl3DPos(PathIntpl3DCommand *pPathIntplCommand, unsigned int numAddlCommands = 0, PathIntpl3DAdditionalCommand *pPathIntplAddlCommand = NULL)
Start an absolute position 3D path interpolation motion. This motion command combines line interpolation and circular interpolation in one path.
Start an absolute position 3D path interpolation motion. This motion command combines line interpolation and circular interpolation in one path.
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
Remark
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters. All positions are specified as absolute positions.
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntpl3DAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC StartPathIntpl3DMov(PathIntpl3DCommand *pPathIntplCommand, unsigned int numAddlCommands = 0, PathIntpl3DAdditionalCommand *pPathIntplAddlCommand = NULL)
Start a relative position 3D path interpolation motion. This motion command combines line interpolation and circular interpolation in one path.
Start a relative position 3D path interpolation motion. This motion command combines line interpolation and circular interpolation in one path.
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
Remark
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters. All positions are specified as relative positions (relative to the command positions at the time that this function is executed).
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntpl3DAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC StartPathIntpl3DPos(PathIntpl3DCommand *pPathIntplCommand, Trigger *pTrigger, unsigned int numAddlCommands = 0, PathIntpl3DAdditionalCommand *pPathIntplAddlCommand = NULL)
Start an absolute position triggered 3D path interpolation motion. This motion command combines line interpolation and circular interpolation in one path.
Start an absolute position triggered 3D path interpolation motion. This motion command combines line interpolation and circular interpolation in one path.
This function starts a path interpolation motion with a trigger condition. The motion will only begin when the specified trigger condition is satisfied. All positions are specified as absolute positions.
Remark
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntpl3DAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC StartPathIntpl3DMov(PathIntpl3DCommand *pPathIntplCommand, Trigger *pTrigger, unsigned int numAddlCommands = 0, PathIntpl3DAdditionalCommand *pPathIntplAddlCommand = NULL)
Start a relative position triggered 3D path interpolation motion. This motion command combines line interpolation and circular interpolation in one path.
Start a relative position triggered 3D path interpolation motion. This motion command combines line interpolation and circular interpolation in one path.
This function starts a path interpolation motion with a trigger condition. The motion will only begin when the specified trigger condition is satisfied. All positions are specified as relative positions (relative to the command positions at the time that this function is executed).
Remark
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters.
pTrigger – [in] A pointer to an object of the Trigger class that specifies the trigger condition.
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntpl3DAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC StartPathIntpl3DPos(PathIntpl3DCommand *pPathIntplCommand, TriggerEvents *pTriggerEvents, unsigned int numAddlCommands = 0, PathIntpl3DAdditionalCommand *pPathIntplAddlCommand = NULL)
Start an absolute position triggered 3D path interpolation motion command with multiple trigger events. This motion combines line interpolation and circular interpolation in one path.
Start an absolute position triggered 3D path interpolation motion command with multiple trigger events. This motion combines line interpolation and circular interpolation in one path.
This function starts a path interpolation motion with a multi-event trigger condition. The motion will only begin when the specified multi-event trigger condition is satisfied. All positions are specified as absolute positions.
Remark
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntpl3DAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC StartPathIntpl3DMov(PathIntpl3DCommand *pPathIntplCommand, TriggerEvents *pTriggerEvents, unsigned int numAddlCommands = 0, PathIntpl3DAdditionalCommand *pPathIntplAddlCommand = NULL)
Start a relative position triggered 3D path interpolation motion command with multiple trigger events. This motion combines line interpolation and circular interpolation in one path.
Start a relative position triggered 3D path interpolation motion command with multiple trigger events. This motion combines line interpolation and circular interpolation in one path.
This function starts a path interpolation motion with a multi-event trigger condition. The motion will only begin when the specified multi-event trigger condition is satisfied. All positions are specified as relative positions (relative to the command positions at the time that this function is executed).
Remark
This function allocates memory dynamically when called for the first time for the first interpolating axis (axis[0]) after starting the WMX3 engine. See CreatePathIntplBuffer for additional information. See Function Calls Related to Memory Allocation for additional information regarding dynamically allocated memory.
The numAddlCommands and pPathIntplAddlCommand optional arguments can be specified to append additional segments to the path interpolation command after the segments defined in pPathIntplCommand. The pPathIntplAddlCommand argument is specified as a pointer to an array, and any number of additional commands may be specified as long as the path interpolation memory buffer for the commanded axis (created with CreatePathIntplBuffer) is large enough to hold all segments that are defined in pPathIntplCommand and pPathIntplAddlCommand.
See also
- Parameters:
pPathIntplCommand – [in] A pointer to a PathIntplCommand that contains the path interpolation parameters.
pTriggerEvents – [in] A pointer to an object of the TriggerEvents class that contains the trigger events.
numAddlCommands – [in] An optional argument that specifies the number of additional commands to append after pPathIntplCommand.
pPathIntplAddlCommand – [in] An optional argument that is a pointer to an array of PathIntpl3DAdditionalCommand objects. The size of the array should be equal to numAddlCommands.
-
WMX3APIFUNC OverridePathIntpl3DVelocityMultiplier(int axis, double multiplier)
Override a 3D path interpolation motion using a velocity multiplier.
Override a 3D path interpolation motion using a velocity multiplier.
This function can be called while executing a 3D path interpolation to change the profile velocity by the specified factor. The interpolating axes will accelerate or decelerate to the new velocity using the acceleration or deceleration of the 3D path interpolation command.
Remark
This function may be called multiple times. Each time this function is called, the new velocity is calculated as the original profile velocity of the 3D path interpolation multiplied by the specified velocity multiplier.
All other profile parameters, including the starting velocity and end velocity, are not changed by this function (except as noted below). The target positions of the 3D path interpolation are not changed.
If a different profile is specified for each segment of the path, the velocities of all profiles are multiplied by the specified multiplier. The end velocities of all profiles are also multiplied by the specified multiplier, except for the end velocity of the final segment of the path.
The velocity multiplier must be between 0 and 2 inclusive. For example, to set the velocity to 50% of the original profile velocity, pass 0.5 to the multiplier argument. If 1 is passed to the multiplier argument, the velocity will be set equal to the original profile velocity of the 3D path interpolation.
If 0 is passed to the multiplier argument, the path interpolation will be paused as if the Pause function is called. The path interpolation can be resumed by calling this function again with a nonzero multiplier (the path interpolation can also be resumed by calling the Resume function, in which case the motion will be resumed using the multiplier immediately before it was paused).
This function can also be used in place of the Resume function to resume a path interpolation that has been paused with the Pause function.
If the velocity after applying the multiplier is below 1 user unit per second, the new velocity will be set to 1 user unit per second.
Any of the three axes executing 3D path interpolation can be passed to the axis argument. The operation of this function will be the same regardless of which of the axes is specified.
When this function is called, the profile of the 3D path interpolation will be recalculated. The standard behavior of overrides apply (see Acceleration Reset).
If the specified axis is not executing a 3D path interpolation command started with StartPathIntpl3DPos or StartPathIntpl3DMov, this function will return an error.
- Parameters:
axis – [in] The axis executing the 3D path interpolation.
multiplier – [in] The velocity multiplier to apply.
-
WMX3APIFUNC CreatePathIntplWithRotationBuffer(int channel, unsigned int points)
Allocate buffer memory for a path interpolation with rotation channel.
Allocate buffer memory for a path interpolation with rotation channel.
When the WMX3 engine is started, no memory is allocated for execution of path interpolation with rotation. This function must be called before a path interpolation with rotation channel can execute motion commands.
Remark
Each channel has a separate buffer memory space. This function must be called for each path interpolation channel before that channel can execute motion commands.
Allocating buffer memory space is an operation that can fail due to lack of memory space or fragmentation of memory. For deterministic operation, this function should be called during initialization to allocate memory for all path interpolation channels that will potentially be used by the program.
The maximum size of the buffer memory space of a path interpolation with rotation channel is 2GB-1Byte (2147483647 bytes). Specifying a larger size will cause this function to return the RequestedBufferTooLarge error.
It is not necessary to call this function again after buffer memory has been allocated once. The ClearPathIntplWithRotation function will clear the contents of the buffer memory, but will not free the buffer memory itself. (When the WMX3 engine is restarted, this function must be called again to allocate buffer memory.)
Buffer memory that has been allocated can be freed using the FreePathIntplWithRotationBuffer function. After freeing the buffer memory of a path interpolation with rotation channel, this function can be called again to reallocate a different amount of buffer memory.
It is not necessary to free allocated memory using FreePathIntplWithRotationBuffer before exiting the program. Any allocated memory is automatically freed when the WMX3 engine is closed.
The GetPathIntplWithRotationBytesPerPoint function can be used to convert the buffer memory size from points to bytes.
See also
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
points – [in] The number of points to allocate memory for. Each linear or circular interpolation segment in the path occupies one point in the memory, and an additional point if an auto smoothing segment is inserted.
-
WMX3APIFUNC FreePathIntplWithRotationBuffer(int channel)
Free buffer memory for a path interpolation with rotation channel.
Free buffer memory for a path interpolation with rotation channel.
This function frees the buffer memory that has been allocated with the CreatePathIntplWithRotationBuffer function. This allows CreatePathIntplWithRotationBuffer to be called again to allocate a different amount of memory.
Remark
It is not necessary to call this function before exiting the program, as any allocated memory is automatically freed when the WMX3 engine closes.
The freed memory, after a brief delay, will become available for the system to use for another purpose.
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
-
WMX3APIFUNC GetPathIntplWithRotationBytesPerPoint(unsigned int *pBytes)
Get the number of bytes required per point data in the path interpolation with rotation buffer memory.
Get the number of bytes required per point data in the path interpolation with rotation buffer memory.
This function obtains the number of bytes of memory required to store one point data in the path interpolation with rotation buffer memory. This can be used to calculate the number of bytes of buffer memory required to store a particular number of points. For example, if this function returns 448, the number of bytes required to store 10000 points is 448*10000 = 4480000, or about 4MB.
Remark
- Parameters:
pBytes – [out] A pointer to an unsigned int that will contain the number of bytes of memory required per point data.
-
WMX3APIFUNC SetPathIntplWithRotationConfiguration(int channel, PathIntplWithRotationConfiguration *pConfig)
Set the configuration data for a path interpolation with rotation channel.
Set the configuration data for a path interpolation with rotation channel.
This function configures a path interpolation with rotation channel with data required for operation, such as the commanded axes.
Remark
This function must be called before interpolation commands can be added to the path interpolation with rotation channel with the AddPathIntplWithRotationCommand function.
Before configuring a path interpolation with rotation channel, buffer memory for path interpolation with rotation must be allocated using the CreatePathIntplWithRotationBuffer function.
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
pConfig – [in] A pointer to an PathIntplWithRotationConfiguration object that contains the path interpolation with rotation configuration data.
-
WMX3APIFUNC AddPathIntplWithRotationCommand(int channel, PathIntplWithRotationCommand *pCommand)
Add interpolation commands to a path interpolation with rotation channel.
Add interpolation commands to a path interpolation with rotation channel.
This function adds interpolation commands to a path interpolation with rotation channel. The added commands are not executed until the StartPathIntplWithRotation function is called.
Remark
Before adding point segment commands, buffer memory for path interpolation with rotation must be allocated using the CreatePathIntplWithRotationBuffer function.
Before adding point segment commands, the path interpolation channel must be configured using the SetPathIntplWithRotationConfiguration function.
Calling this function for the first time after clearing a path interpolation with rotation channel fixes the starting position of the X axis, Y axis, rotational axis, and if enabled, the Z axis on the path. Moving the X axis, Y axis, rotational axis, or Z axis after calling this function will move the axis off the path and cause the StartPathIntplWithRotation function to return the PathInterpolationAxesHaveBeenMoved error. If this occurs, the path interpolation with rotation channel must be cleared and the path must be defined again.
See also
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
pCommand – [in] A pointer to a PathIntplWithRotationCommand object that contains the path interpolation with rotation command data.
-
WMX3APIFUNC StartPathIntplWithRotation(int channel)
Execute motion for a path interpolation with rotation channel.
Execute motion for a path interpolation with rotation channel.
This function moves the axes of a path interpolation with rotation channel to the end of the path, using the configuration parameters set for the path interpolation with rotation channel.
Remark
It is possible to execute the path interpolation with rotation only partway along the path using the StartPathIntplWithRotation(int channel, double pos) or StartPathIntplWithRotation(int channel, unsigned int point) functions or by stopping execution with the Stop function. If this function is called afterthe path has been executed partway, the execution will continue from the current position.
If a path interpolation with rotation is executed partway, and then a commanded axis is moved using a different function, this function will return an error. If the path interpolation with rotation is stopped with another function such as ExecQuickStop, this function will return an error. In this case, the path must be reset by calling ClearPathIntplWithRotation and then the path must be defined again.
Point segment commands must be added to the path interpolation with rotation channel using the AddPathIntplWithRotationCommand function before this function is called. This function can be executed as long as the path contains at least one point segment.
See also
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
-
WMX3APIFUNC StartPathIntplWithRotation(int channel, Trigger *pTrigger)
Execute triggered motion for a path interpolation with rotation channel. The motion starts when the trigger condition is satisfied.
Execute triggered motion for a path interpolation with rotation channel. The motion starts when the trigger condition is satisfied.
This function is similar to StartPathIntplWithRotation(int channel), except the path interpolation will start executing after the specified trigger condition is satisfied.
Remark
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
pTrigger – [in] A pointer to an Trigger object that defines the trigger condition.
-
WMX3APIFUNC StartPathIntplWithRotation(int channel, TriggerEvents *pTriggerEvents)
Execute triggered motion for a path interpolation with rotation channel with multiple trigger events. The motion starts when the trigger condition is satisfied.
Execute triggered motion for a path interpolation with rotation channel with multiple trigger events. The motion starts when the trigger condition is satisfied.
This function is similar to StartPathIntplWithRotation(int channel), except the path interpolation will start executing after the specified multi-event trigger condition is satisfied.
Remark
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
pTriggerEvents – [in] A pointer to an TriggerEvents object that defines the trigger events.
-
WMX3APIFUNC StartPathIntplWithRotation(int channel, double pos)
Execute motion to the specified position for a path interpolation with rotation channel.
Execute motion to the specified position for a path interpolation with rotation channel.
This function moves the axes of a path interpolation with rotation channel along the path to the specified position, using the configuration parameters set for the path interpolation with rotation channel. The position is specified as the distance along the path starting from the beginning of the path. If the specified position is greater than the length of the path, the path interpolation will be executed to the end of the path.
Remark
If the path interpolation with rotation has been executed partway along the path using this function, the StartPathIntplWithRotation(int channel, unsigned int point) function, or by stopping execution with the Stop function, this function can be used to backtrack along the path by specifying a smaller position than the current position. If the specified position is less than zero, the path interpolation will backtrack to the beginning of the path. The motion of the rotational axis during backtracking will be identical as during the forward motion.
This function is able to move the axes to any position along the path, even positions that are partway along segments.
It is not trivial to convert a specific X and Y position along the path to a distance that can be passed to this function. This function should mostly be used to move relative distances from the current position along the path (this position can be obtained from the PathIntplWithRotationStatus.pos status). To move to a specific point, use the StartPathIntplWithRotation(int channel, unsigned int point) function instead.
See also
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
pos – [in] The target position along the path to move to.
-
WMX3APIFUNC StartPathIntplWithRotation(int channel, double pos, Trigger *pTrigger)
Execute triggered motion to the specified position for a path interpolation with rotation channel. The motion starts when the trigger condition is satisfied.
Execute triggered motion to the specified position for a path interpolation with rotation channel. The motion starts when the trigger condition is satisfied.
This function is similar to StartPathIntplWithRotation(int channel, double pos), except the path interpolation will start executing after the specified trigger condition is satisfied.
Remark
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
pos – [in] The target position along the path to move to.
pTrigger – [in] A pointer to an Trigger object that defines the trigger condition.
-
WMX3APIFUNC StartPathIntplWithRotation(int channel, double pos, TriggerEvents *pTriggerEvents)
Execute triggered motion to the specified position for a path interpolation with rotation channel with multiple trigger events. The motion starts when the trigger condition is satisfied.
Execute triggered motion to the specified position for a path interpolation with rotation channel with multiple trigger events. The motion starts when the trigger condition is satisfied.
This function is similar to StartPathIntplWithRotation(int channel, double pos), except the path interpolation will start executing after the specified multi-event trigger condition is satisfied.
Remark
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
pos – [in] The target position along the path to move to.
pTriggerEvents – [in] A pointer to an TriggerEvents object that defines the trigger events.
-
WMX3APIFUNC StartPathIntplWithRotation(int channel, unsigned int point)
Execute motion to the specified point for a path interpolation with rotation channel.
Execute motion to the specified point for a path interpolation with rotation channel.
This function moves the axes of a path interpolation with rotation along the path to the specified point, using the configuration parameters set for the path interpolation with rotation channel. The points are defined as the indices of the command segment added with the AddPathIntplWithRotationCommand function. Auto smoothing segments inserted between linear interpolations do not increment this index. The axes will move to the position at the beginning of this command segment.
Remark
If the path interpolation with rotation has been executed partway along the path using this function, the StartPathIntplWithRotation(int channel, double pos) function, or by stopping execution with the Stop function, this function can be used to backtrack along the path by specifying a point from earlier in the path. The motion of the rotational axis during backtracking will be identical as during the forward motion.
It is possible to specify a point equal to the total number of command segments in the path. In this case, the axis will move to the end of the path. If the specified point is greater than the total number of command segments in the path, the axis will also move to the end of the path.
See also
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
point – [in] The target point to move to.
-
WMX3APIFUNC StartPathIntplWithRotation(int channel, unsigned int point, Trigger *pTrigger)
Execute triggered motion to the specified point for a path interpolation with rotation channel. The motion starts when the trigger condition is satisfied.
Execute triggered motion to the specified point for a path interpolation with rotation channel. The motion starts when the trigger condition is satisfied.
This function is similar to StartPathIntplWithRotation(int channel, unsigned int point), except the path interpolation will start executing after the specified trigger condition is satisfied.
Remark
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
point – [in] The target point to move to.
pTrigger – [in] A pointer to an Trigger object that defines the trigger condition.
-
WMX3APIFUNC StartPathIntplWithRotation(int channel, unsigned int point, TriggerEvents *pTriggerEvents)
Execute triggered motion to the specified point for a path interpolation with rotation channel with multiple trigger events. The motion starts when the trigger condition is satisfied.
Execute triggered motion to the specified point for a path interpolation with rotation channel with multiple trigger events. The motion starts when the trigger condition is satisfied.
This function is similar to StartPathIntplWithRotation(int channel, unsigned int point), except the path interpolation will start executing after the specified multi-event trigger condition is satisfied.
Remark
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
point – [in] The target point to move to.
pTriggerEvents – [in] A pointer to an TriggerEvents object that defines the trigger events.
-
WMX3APIFUNC ClearPathIntplWithRotation(int channel)
Clear all data for a path interpolation with rotation channel.
Clear all data for a path interpolation with rotation channel.
This function clears all data for a path interpolation with rotation channel, including any existing point segment commands and configuration settings. Use this function if a path interpolation with rotation channel must be reset.
Remark
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
-
WMX3APIFUNC GetPathIntplWithRotationStatus(int channel, PathIntplWithRotationStatus *pStatus)
Get the current status for a path inteprolation with rotation channel.
Get the current status for a path inteprolation with rotation channel.
Use this function to get the status of a path interpolation with rotation channel.
Remark
- Parameters:
channel – [in] The channel of the path interpolation with rotation. The maximum number of available channels is maxPathIntplWithRotationChannel.
pStatus – [out] A pointer to a PathIntplWithRotationStatus class object that will contain the status of the path interpolation with rotation channel.
-
WMX3APIFUNC CreatePathIntplLookaheadBuffer(int channel, unsigned int points)
Allocate buffer memory for a path interpolation with look ahead channel.
Allocate buffer memory for a path interpolation with look ahead channel.
When the WMX3 engine is started, no memory is allocated for execution of path interpolation with look ahead. This function must be called before a path interpolation with look ahead channel can execute motion commands.
Remark
Each channel has a separate buffer memory space. This function must be called for each path interpolation channel before that channel can execute motion commands.
Allocating buffer memory space is an operation that can fail due to lack of memory space or fragmentation of memory. For deterministic operation, this function should be called during initialization to allocate memory for all path interpolation channels that will potentially be used by the program.
The maximum size of the buffer memory space of a path interpolation with look ahead channel is 2GB-1Byte (2147483647 bytes). Specifying a larger size will cause this function to return the RequestedBufferTooLarge error.
It is not necessary to call this function again after buffer memory has been allocated once. The ClearPathIntplLookahead function will clear the contents of the buffer memory, but will not free the buffer memory itself. (When the WMX3 engine is restarted, this function must be called again to allocate buffer memory.)
Buffer memory that has been allocated can be freed using the FreePathIntplLookaheadBuffer function. After freeing the buffer memory of a path interpolation with look ahead channel, this function can be called again to reallocate a different amount of buffer memory.
It is not necessary to free allocated memory using FreePathIntplLookaheadBuffer before exiting the program. Any allocated memory is automatically freed when the WMX3 engine is closed.
The GetPathIntplLookaheadBytesPerPoint function can be used to convert the buffer memory size from points to bytes.
See also
- Parameters:
channel – [in] The channel of the path interpolation with look ahead. The maximum number of available channels is maxPathIntplLookaheadChannel.
points – [in] The number of points to allocate memory for. Each linear or circular interpolation segment in the path occupies at least two points, and more if the segment distance is greater than the sample distance. For example, a linear interpolation with a length of 500 user units and a sample distance of 10 user units will occupy 500 / 10 = 50 points.
-
WMX3APIFUNC FreePathIntplLookaheadBuffer(int channel)
Free buffer memory for a path interpolation with lookahead channel.
Free buffer memory for a path interpolation with lookahead channel.
This function frees the buffer memory that has been allocated with the CreatePathIntplLookaheadBuffer function. This allows CreatePathIntplLookaheadBuffer to be called again to allocate a different amount of memory.
Remark
It is not necessary to call this function before exiting the program, as any allocated memory is automatically freed when the WMX3 engine closes.
The freed memory, after a brief delay, will become available for the system to use for another purpose.
- Parameters:
channel – [in] The channel of the path interpolation with look ahead. The maximum number of available channels is maxPathIntplLookaheadChannel.
-
WMX3APIFUNC GetPathIntplLookaheadBytesPerPoint(unsigned int *pBytes)
Get the number of bytes required per point data in the path interpolation with look ahead buffer memory.
Get the number of bytes required per point data in the path interpolation with look ahead buffer memory.
This function obtains the number of bytes of memory required to store one point data in the path interpolation with rotation buffer memory. This can be used to calculate the number of bytes of buffer memory required to store a particular number of points. For example, if this function returns 288, the number of bytes required to store 10000 points is 288*10000 = 2880000, or about 3MB.
Remark
- Parameters:
pBytes – [out] A pointer to an unsigned int that will contain the number of bytes of memory required per point data.
-
WMX3APIFUNC SetPathIntplLookaheadConfiguration(int channel, PathIntplLookaheadConfiguration *pConfig)
Set the configuration data for a path interpolation with lookahead channel.
Set the configuration data for a path interpolation with lookahead channel.
This function configures a path interpolation with look ahead channel with data required for operation, such as the commanded axes and the axis velocity and acceleration limits.
Remark
This function must be called before interpolation commands can be added to the path interpolation with look ahead channel with the AddPathIntplLookaheadCommand function.
After points are added to the path interpolation with look ahead channel, the configuration cannot be changed with this function until the channel is cleared with the ClearPathIntplLookahead function or the channel buffer is freed and then reallocated with the FreePathIntplLookaheadBuffer and CreatePathIntplLookaheadBuffer functions.
Before configuring a path interpolation with look ahead channel, buffer memory for path interpolation with look ahead must be allocated using the CreatePathIntplLookaheadBuffer function.
See also
- Parameters:
channel – [in] The channel of the path interpolation with look ahead. The maximum number of available channels is maxPathIntplLookaheadChannel.
pConfig – [in] A pointer to an PathIntplLookaheadConfiguration object that contains the path interpolation with look ahead configuration data.
-
WMX3APIFUNC AddPathIntplLookaheadCommand(int channel, PathIntplLookaheadCommand *pCommand)
Add interpolation commands to a path interpolation with look ahead channel.
Add interpolation commands to a path interpolation with look ahead channel.
This function adds interpolation commands to a path interpolation with look ahead channel. The added commands are not executed until the StartPathIntplLookahead function is called.
Remark
Commands may be added while a path interpolation with look ahead channel is executing. Doing so can modify the velocity and acceleration profiles of the path interpolation, including the velocity and acceleration profiles of point segments that were already in the buffer. For example, adding point segments before an executing path interpolation finishes will cause the path interpolation to continue executing at the commanded velocity without decelerating until the newly added point segments have been traversed.
Before adding point segment commands, buffer memory for path interpolation with look ahead must be allocated using the CreatePathIntplLookaheadBuffer function.
Before adding point segment commands, the path interpolation channel must be configured using the SetPathIntplLookaheadConfiguration function.
When adding more commands than maxPathIntplLookaheadAppendPoints commands to the path interpolation with look ahead channel, use the overloaded AddPathIntplLookaheadCommand function with the numCommands argument and specify all commands with one function call. Calling the AddPathIntplLookaheadCommand function multiple times instead could cause the velocity along the path to not be ideal.
See also
- Parameters:
channel – [in] The channel of the path interpolation with look ahead. The maximum number of available channels is maxPathIntplLookaheadChannel.
pCommand – [in] A pointer to a PathIntplLookaheadCommand object that contains the path interpolation with look ahead command data.
-
WMX3APIFUNC AddPathIntplLookaheadCommand(int channel, unsigned int numCommands, PathIntplLookaheadCommand *pCommand)
Add multiple interpolation commands to a path interpolation with look ahead channel.
Add multiple interpolation commands to a path interpolation with look ahead channel.
This function is an overloaded version of the AddPathIntplLookaheadCommand function that allows multiple PathIntplLookaheadCommand commands to be specified with one function call.
Remark
Each PathIntplLookaheadCommand can contain at most maxPathIntplLookaheadAppendPoints points. When a larger number of points needs to be added, this function should be used instead of calling AddPathIntplLookaheadCommand multiple times. The execution time is much faster when specifying all points at once with this function.
See also
- Parameters:
channel – [in] The channel of the path interpolation with look ahead. The maximum number of available channels is maxPathIntplLookaheadChannel.
numCommands – [in] The number of commands that will be specified. This is the size of the PathIntplLookaheadCommand array passed to the pCommand argument. This must be greater than or equal to 1.
pCommand – [in] A pointer to an array of PathIntplLookaheadCommand objects that contains the path interpolation with look ahead command data.
-
WMX3APIFUNC StartPathIntplLookahead(int channel)
Start the motion for a path interpolation with look ahead channel.
Start the motion for a path interpolation with look ahead channel.
Point segment commands must be added to the path interpolation with look ahead channel using the AddPathIntplLookaheadCommand function before this function is called. This function can be executed as long as the path contains at least one point segment.
Remark
See also
- Parameters:
channel – [in] The channel of the path interpolation with look ahead. The maximum number of available channels is maxPathIntplLookaheadChannel.
-
WMX3APIFUNC StopPathIntplLookahead(int channel)
Stop the motion for a path interpolation with look ahead channel.
Stop the motion for a path interpolation with look ahead channel.
This function stops the motion for a path interpolation with look ahead channel. The axes will decelerate along the commanded path using the compositeAcc specified for the path interpolation.
Remark
After the axes stop, the path interpolation can be resumed by calling the StartPathIntplLookahead function again. The velocity and acceleration profiles along the path will be recalculated.
- Parameters:
channel – [in] The channel of the path interpolation with look ahead. The maximum number of available channels is maxPathIntplLookaheadChannel.
-
WMX3APIFUNC ClearPathIntplLookahead(int channel)
Clear all data for a path interpolation with look ahead channel.
Clear all data for a path interpolation with look ahead channel.
This function clears all data for a path interpolation with look ahead channel, including any existing point segment commands and statuses. Use this function if a path interpolation with look ahead channel must be reset.
Remark
- Parameters:
channel – [in] The channel of the path interpolation with look ahead. The maximum number of available channels is maxPathIntplLookaheadChannel.
-
WMX3APIFUNC GetPathIntplLookaheadStatus(int channel, PathIntplLookaheadStatus *pStatus)
Get the current status for a path interpolation with look ahead channel.
Get the current status for a path interpolation with look ahead channel.
Use this function to get the status of a path interpolation with look ahead channel.
Remark
- Parameters:
channel – [in] The channel of the path interpolation with look ahead. The maximum number of available channels is maxPathIntplLookaheadChannel.
pStatus – [out] A pointer to a PathIntplLookaheadStatus class object that will contain the status of the path interpolation with look ahead channel.
-
WMX3APIFUNC StartCoordinatedPos(CoordinatedPosCommand *pPosCommand)
Start an interpolation between two axes, where one axis executes a normal position command and the second axis travels a specified distance in the same amount of time.
Start an interpolation between two axes, where one axis executes a normal position command and the second axis travels a specified distance in the same amount of time.
This function executes coordinated motion for two axes. The first axis executes a regular position command with the specified profile, and the second axis travels the specified distance in the same time as the first axis position command. The velocity of the second axis increases at a constant rate until the midpoint, and then decreases at a constant rate until the axis reaches the target position. The axis2SmoothRatio can be specified to convert that amount of the second axis velocity profile into a parabolic profile.
Remark
The following plot shows the second axis velocity profile when the axis2SmoothRatio is 0.

The following plot shows the second axis velocity profile when the axis2SmoothRatio is 0.5.

The following plot shows the second axis velocity profile when the axis2SmoothRatio is 1.

- Parameters:
pPosCommand – [in] A pointer to a CoordinatedPosCommand that contains the coordinated position command parameters.
-
WMX3APIFUNC StartCoordinatedPos(unsigned int numCommands, CoordinatedPosCommand *pPosCommand)
Start multiple interpolations, each between pairs of two axes, where one axis executes a normal position command and the second axis travels a specified distance in the same amount of time.
Start multiple interpolations, each between pairs of two axes, where one axis executes a normal position command and the second axis travels a specified distance in the same amount of time.
This command executes the StartCoordinatedPos function for multiple axes.
Remark
- Parameters:
numCommands – [in] The number of coordinated position commands. Each command controls a pair of two axes.
pPosCommand – [in] A pointer to an array of objects of the CoordinatedPosCommand class that contain the parameters of the coordinated position commands. The number of objects in the array must be equal to numCommands.
-
WMX3APIFUNC StartCoordinatedPos(CoordinatedJerkRatioPosCommand *pPosCommand)
Start an interpolation between two or more axes, where one axis executes a normal position command and the remaining axes travel the specified distances in the same amount of time.
Start an interpolation between two or more axes, where one axis executes a normal position command and the remaining axes travel the specified distances in the same amount of time.
This function executes coordinated motion for two or more axes. The first axis executes a regular position command with the specified profile, and the remaining axes travel the specified distances in the same time as the first axis position command. Each remaining axis accelerates at the specified acceleration, stops accelerating at a velocity calculated from the movement distance and acceleration, and decelerates at the same magnitude at the specified acceleration to finish the motion in the same time as the first axis. If it is impossible to finish the motion in the same time as the first axis with the specified acceleration, the acceleration is increased. The acceleration and deceleration segments will have velocity profile that is partway between trapezoidal and S-curve depending on the specified jerk ratio (the jerk ratio is the ratio between 0 and 1 for which the acceleration changes during the acceleration and deceleration segments).
Remark
The following plot shows how the velocity profile of one of the remaining axes changes as the movement distance is increased while keeping the acceleration fixed. The jerk ratio is set to 0 (same as the trapezoidal profile) so that the shape of the profile can be easily seen.

Compared to the StartCoordinatedPos(CoordinatedPosCommand *pPosCommand) function, it is possible to specify multiple follower axes, and the velocity profiles of the follower axes are calculated differently.
- Parameters:
pPosCommand – [in] A pointer to a CoordinatedJerkRatioPosCommand that contains the coordinated position command parameters.
-
WMX3APIFUNC StartTwoLinkLinearPos(TwoLinkLinearCommand *pTwoLinkCommand)
Start a two link motion in which the profile is generated by simulating a rotary axis connected to a linear axis with two links. A motion profile is generated for the rotary axis, and the linear axis follows the simulated motion of the rotary axis. The target position is specified in absolute coordinates.
Start a two link motion in which the profile is generated by simulating a rotary axis connected to a linear axis with two links. A motion profile is generated for the rotary axis, and the linear axis follows the simulated motion of the rotary axis. The target position is specified in absolute coordinates.
This function simulates a rotary axis connected to the commanded linear axis with two links. A profile is generated for the rotary axis and the linear axis follows the simulated motion of the rotary axis as if it is pulled by the two links.
Remark
The following figure shows the arrangment of the axes:

When R = 0 degrees, the two links will be fully outstretched and L will be equal to Lmax.
When R = 180 degrees (or Rspan / 2), the two links will be folded and L will be equal to Lmin.
The length of the links, L1 and L2, are specified as positive values. L1 must be less than or equal to L2, as otherwise, the rotary axis is unable to turn 360 degrees.
Lzero is the location of the rotary axis along the linear axis. Lzero can be positive, negative, or 0. Lmin and Lmax are calculated from L1, L2, and Lzero, as follows:
Lmin = Lzero + L2 - L1
Lmax = Lzero + L1 + L2
Lpolarity can be set to -1 to flip the two link arrangement horizontally about Lzero. If Lpolarity is -1, Lmin and Lmax are instead calculated as follows:
Lmin = Lzero - L2 + 1
Lmax = Lzero - L1 - L2.
Rspan determines the number of units in one rotation of the rotary axis. The profile parameters used by the rotary axis are specified using the same units. For example, if Rspan is 1000 [units], a velocity of 10000 [units/second] will move the rotary axis at a velocity of 10 rotations per second.
Rzero determines the position of the rotary axis when the two links are fully outstretched and L equals Lmax.
Rspan and Rzero are shown in the following diagram:

The target position is specified for the linear axis (unless specifyTargetInRotaryCoordinates is set). The starting and target positions of the simulated rotary axis is calculated based on the current and target positions of the commanded linear axis. A motion profile is generated for the simulated rotary axis and the linear axis will follow the motion of the rotary axis.
If the target position is between Lmin and Lmax, the commanded linear axis will move to that position. If the target position is outside this range, the linear axis will move in the direction of the target position, but will change directions whenever it reaches Lmin or Lmax. The linear axis will move a total distance equal to the target position minus the initial position. It is possible for the linear axis to move back and forth betwen Lmin and Lmax multiple times if the target position is far enough. The motion profile generated for the rotary axis will decelerate to zero velocity whenever the linear axis moves to Lmin or Lmax.
- Parameters:
pTwoLinkCommand – [in] A pointer to a TwoLinkLinearCommand that contains the two link motion parameters.
-
WMX3APIFUNC StartTwoLinkLinearMov(TwoLinkLinearCommand *pTwoLinkCommand)
Start a two link motion in which the profile is generated by simulating a rotary axis connected to a linear axis with two links. A motion profile is generated for the rotary axis, and the linear axis follows the simulated motion of the rotary axis. The target position is specified in relative coordinates.
Start a two link motion in which the profile is generated by simulating a rotary axis connected to a linear axis with two links. A motion profile is generated for the rotary axis, and the linear axis follows the simulated motion of the rotary axis. The target position is specified in relative coordinates.
This function is similar to StartTwoLinkLinearPos, except the target position is specified in relative coordinates (relative to the current position of the commanded axis).
Remark
- Parameters:
pTwoLinkCommand – [in] A pointer to a TwoLinkLinearCommand that contains the two link motion parameters.
-
WMX3APIFUNC StartTwoLinkRotaryPos(TwoLinkRotaryCommand *pTwoLinkCommand)
Start a two link motion in which the profile is generated by simulating a linear axis connected to a rotary axis with two links. A motion profile is generated for the linear axis, and the rotary axis follows the simulated motion of the linear axis. The target position is specified in absolute coordinates.
Start a two link motion in which the profile is generated by simulating a linear axis connected to a rotary axis with two links. A motion profile is generated for the linear axis, and the rotary axis follows the simulated motion of the linear axis. The target position is specified in absolute coordinates.
This function is similar to StartTwoLinkLinearPos, except the commanded axis is the rotary axis and the simulated axis is the linear axis.
Remark
The axis commanded by this function must be a rotary axis (the Single Turn Mode parameter must be set to true).
Rspan is set equal to the Single Turn Encoder Count parameter (after being adjusted by the Gear Ratio Numerator and Gear Ratio Denominator parameters).
If the target position is between 0 and Rspan, the direction of motion will be adjusted so that the total distance moved is at most Rspan / 2.
The direction of rotation will be the same for the entire motion, and will be in the direction of the target position compared to the current position. The axis may rotate multiple times if the target position is outside the range from 0 to Rspan.
The motion profile generated for the linear axis will decelerate to zero velocity each time the linear axis moves to Lmin (at R = Rspan / 2) or Lmax (at R = 0).
- Parameters:
pTwoLinkCommand – [in] A pointer to a TwoLinkRotaryCommand that contains the two link motion parameters.
-
WMX3APIFUNC StartTwoLinkRotaryMov(TwoLinkRotaryCommand *pTwoLinkCommand)
Start a two link motion in which the profile is generated by simulating a linear axis connected to a rotary axis with two links. A motion profile is generated for the linear axis, and the rotary axis follows the simulated motion of the linear axis. The target position is specified in relative coordinates.
Start a two link motion in which the profile is generated by simulating a linear axis connected to a rotary axis with two links. A motion profile is generated for the linear axis, and the rotary axis follows the simulated motion of the linear axis. The target position is specified in relative coordinates.
This function is similar to StartTwoLinkRotaryPos, except the target position is specified in relative coordinates (relative to the current position of the commanded axis).
Remark
- Parameters:
pTwoLinkCommand – [in] A pointer to a TwoLinkRotaryCommand that contains the two link motion parameters.
-
WMX3APIFUNC StartTwoLinkUntetheredLinearPos(TwoLinkLinearCommand *pTwoLinkCommand)
Start a two link motion in which the profile is generated by simulating a rotary axis connected to a linear axis with two links. A motion profile is generated for the rotary axis, and the linear axis follows the simulated motion of the rotary axis. The target position is specified in absolute coordinates.
Start a two link motion in which the profile is generated by simulating a rotary axis connected to a linear axis with two links. A motion profile is generated for the rotary axis, and the linear axis follows the simulated motion of the rotary axis. The target position is specified in absolute coordinates.
This function is similar to StartTwoLinkLinearPos, except L2 is not tethered to the linear axis, and may move up and down freely. L2 is always oriented parallel to the linear axis. The following image shows this arrangement:
Remark

- Parameters:
pTwoLinkCommand – [in] A pointer to a TwoLinkLinearCommand that contains the two link motion parameters.
-
WMX3APIFUNC StartTwoLinkUntetheredLinearMov(TwoLinkLinearCommand *pTwoLinkCommand)
Start a two link motion in which the profile is generated by simulating a rotary axis connected to a linear axis with two links. A motion profile is generated for the rotary axis, and the linear axis follows the simulated motion of the rotary axis. The target position is specified in relative coordinates.
Start a two link motion in which the profile is generated by simulating a rotary axis connected to a linear axis with two links. A motion profile is generated for the rotary axis, and the linear axis follows the simulated motion of the rotary axis. The target position is specified in relative coordinates.
This function is similar to StartTwoLinkUntetheredLinearPos, except the target position is specified in relative coordinates (relative to the current position of the commanded axis).
Remark
- Parameters:
pTwoLinkCommand – [in] A pointer to a TwoLinkLinearCommand that contains the two link motion parameters.
-
WMX3APIFUNC StartTwoLinkUntetheredRotaryPos(TwoLinkRotaryCommand *pTwoLinkCommand)
Start a two link motion in which the profile is generated by simulating a linear axis connected to a rotary axis with two links. A motion profile is generated for the linear axis, and the rotary axis follows the simulated motion of the linear axis. The target position is specified in absolute coordinates.
Start a two link motion in which the profile is generated by simulating a linear axis connected to a rotary axis with two links. A motion profile is generated for the linear axis, and the rotary axis follows the simulated motion of the linear axis. The target position is specified in absolute coordinates.
This function is similar to StartTwoLinkRotaryPos, except L2 is not tethered to the linear axis, and may move up and down freely. L2 is always oriented parallel to the linear axis. Also see the image in the discussion of StartTwoLinkUntetheredLinearPos.
Remark
- Parameters:
pTwoLinkCommand – [in] A pointer to a TwoLinkRotaryCommand that contains the two link motion parameters.
-
WMX3APIFUNC StartTwoLinkUntetheredRotaryMov(TwoLinkRotaryCommand *pTwoLinkCommand)
Start a two link motion in which the profile is generated by simulating a linear axis connected to a rotary axis with two links. A motion profile is generated for the linear axis, and the rotary axis follows the simulated motion of the linear axis. The target position is specified in relative coordinates.
Start a two link motion in which the profile is generated by simulating a linear axis connected to a rotary axis with two links. A motion profile is generated for the linear axis, and the rotary axis follows the simulated motion of the linear axis. The target position is specified in relative coordinates.
This function is similar to StartTwoLinkUntetheredRotaryPos, except the target position is specified in relative coordinates (relative to the current position of the commanded axis).
Remark
- Parameters:
pTwoLinkCommand – [in] A pointer to a TwoLinkRotaryCommand that contains the two link motion parameters.
-
WMX3APIFUNC SimulatePosAtTime(SimulatePathIntplCommand *pPathIntplCommand, double timeMilliseconds, double *pPos1, double *pPos2, double *pMoveDistance, double *pRemainDistance, double *pTotalDistance)
Simulate a path interpolation command without moving any axes. The move distance, remain distance, and total distance after the path interpolation runs for a specified amount of time are returned.
Simulate a path interpolation command without moving any axes. The move distance, remain distance, and total distance after the path interpolation runs for a specified amount of time are returned.
- Parameters:
pPathIntplCommand – [in] A pointer to an object of the SimulatePathIntplCommand class that contains the parameters for the path interpolation.
timeMilliseconds – [in] The amount of time elapsed. This value is in units of milliseconds.
pPos1 – [out] A pointer to a double type variable that will contain the position that the first axis is at after the specified amount of time elapses.
pPos2 – [out] A pointer to a double type variable that will contain the position that the second axis is at after the specified amount of time elapses.
pMoveDistance – [out] A pointer to a double type variable that will contain the total distance moved along the path in the two dimensional plane formed by the first and second axes.
pRemainDistance – [out] A pointer to a double type variable that will contain the total distance remaining in the path in the two dimensional plane formed by the first and second axes.
pTotalDistance – [out] A pointer to a double type variable that will contain the total distance along the entire path in the two dimensional plane formed by the first and second axes. This value is always equal to the sum of the values returned by pMoveDistance and pRemainDistance.
-
WMX3APIFUNC SimulateTimeAtPos(SimulatePathIntplCommand *pPathIntplCommand, double specificPos1, double specificPos2, unsigned int minimumSearchIndex, double *pMoveTimeMilliseconds, double *pRemainTimeMilliseconds, double *pTotalTimeMilliseconds)
Simulate a path interpolation command without moving any axes. The elapsed time and remaining time after the axis reaches the specified position are returned.
Simulate a path interpolation command without moving any axes. The elapsed time and remaining time after the axis reaches the specified position are returned.
This function simulates a path interpolation command, and calculates the time at which the axes reach a particular position during the path interpolation. If the axes do not pass the specified position during the entire path interpolation, this function will return an error. The specified position must be within 1 user unit of the path for this function to consider the interpolating axes to have crossed the position.
Remark
By setting the minimumSearchIndex value appropriately, simulations can be performed for path interpolations in which the path crosses the specified position multiple times.
For example, if the path crosses the specified position during the interpolation segments at indices 0, 2, and 4:
minimumSearchIndex = 0 will cause the simulation to calculate the move time, remain time, and total time for the first time that the path crosses the specified position.
minimumSearchIndex = 1 or 2 will cause the simulation to calculate the move time, remain time, and total time for the second time that the path crosses the specified position.
minimumSearchIndex = 3 or 4 will cause the simulation to calculate the move time, remain time, and total time for the third time that the path crosses the specified position.
- Parameters:
pPathIntplCommand – [in] A pointer to an object of the SimulatePathIntplCommand class that contains the parameters for the path interpolation.
specificPos1 – [in] The position of the first axis at which to calculate the move time, remain time, and total time of the path interpolation command.
specificPos2 – [in] The position of the second axis at which to calculate the move time, remain time, and total time of the path interpolation command.
minimumSearchIndex – [in] The minimum index of the interpolation segments defined in pPathIntplCommand at which to search for the specified positions.
pMoveTimeMilliseconds – [out] A pointer to a double type variable that will contain the amount of time elapsed when the axes reach the position of specificPos1 and specificPos2. The units are milliseconds.
pRemainTimeMilliseconds – [out] A pointer to a double type variable that will contain the amount of time remaining in the path interpolation when the axes reach the position of specificPos1 and specificPos2. The units are milliseconds.
pTotalTimeMilliseconds – [out] A pointer to a double type variable that will contain the total time of the path interpolation. This value is always equal to the sum of the values returned by pMoveTime and pRemainTime. The units are milliseconds.
-
WMX3APIFUNC SimulateTimeAtDist(SimulatePathIntplCommand *pPathIntplCommand, double specificDistance, double *pMoveTimeMilliseconds, double *pRemainTimeMilliseconds, double *pTotalTimeMilliseconds)
Simulate a path interpolation command without moving any axes. The move time, remain time, and total time after the path interpolation runs for the specified distance are returned.
Simulate a path interpolation command without moving any axes. The move time, remain time, and total time after the path interpolation runs for the specified distance are returned.
- Parameters:
pPathIntplCommand – [in] A pointer to an object of the SimulatePathIntplCommand class that contains the parameters for the path interpolation.
specificDistance – [in] The distance along the path at which to calculate the move time, remain time, and total time of the path interpolation command.
pMoveTimeMilliseconds – [out] A pointer to a double type variable that will contain the amount of time elapsed when the axes travel along the path a distance equal to specificDistance. The units are milliseconds.
pRemainTimeMilliseconds – [out] A pointer to a double type variable that will contain the amount of time remaining in the path interpolation when the axes travel along the path a distance equal to specificDistance. The units are milliseconds.
pTotalTimeMilliseconds – [out] A pointer to a double type variable that will contain the total time of the path interpolation. This value is always equal to the sum of the values returned by pMoveTime and pRemainTime. The units are milliseconds.
-
WMX3APIFUNC SimulatePosAtTime(SimulatePathIntpl3DCommand *pPathIntplCommand, double timeMilliseconds, double *pPos1, double *pPos2, double *pPos3, double *pMoveDistance, double *pRemainDistance, double *pTotalDistance)
Simulate a 3D path interpolation command without moving any axes. The move distance, remain distance, and total distance after the 3D path interpolation runs for a specified amount of time are returned.
Simulate a 3D path interpolation command without moving any axes. The move distance, remain distance, and total distance after the 3D path interpolation runs for a specified amount of time are returned.
- Parameters:
pPathIntplCommand – [in] A pointer to an object of the SimulatePathIntpl3DCommand class that contains the parameters for the 3D path interpolation.
timeMilliseconds – [in] The amount of time elapsed. This value is in units of milliseconds.
pPos1 – [out] A pointer to a double type variable that will contain the position that the first axis is at after the specified amount of time elapses.
pPos2 – [out] A pointer to a double type variable that will contain the position that the second axis is at after the specified amount of time elapses.
pPos3 – [out] A pointer to a double type variable that will contain the position that the third axis is at after the specified amount of time elapses.
pMoveDistance – [out] A pointer to a double type variable that will contain the total distance moved along the three dimensional path.
pRemainDistance – [out] A pointer to a double type variable that will contain the total distance remaining in the three dimensional path.
pTotalDistance – [out] A pointer to a double type variable that will contain the total distance along the entire three dimensional path. This value is always equal to the sum of the values returned by pMoveDistance and pRemainDistance.
-
WMX3APIFUNC SimulateTimeAtPos(SimulatePathIntpl3DCommand *pPathIntplCommand, double specificPos1, double specificPos2, double specificPos3, unsigned int minimumSearchIndex, double *pMoveTimeMilliseconds, double *pRemainTimeMilliseconds, double *pTotalTimeMilliseconds)
Simulate a 3D path interpolation command without moving any axes. The elapsed time and remaining time after the axis reaches the specified position are returned.
Simulate a 3D path interpolation command without moving any axes. The elapsed time and remaining time after the axis reaches the specified position are returned.
This function simulates a 3D path interpolation command, and calculates the time at which the axes reach a particular position during the 3D path interpolation. If the axes do not pass the specified position during the entire 3D path interpolation, this function will return an error. The specified position must be within 1 user unit of the path for this function to consider the interpolating axes to have crossed the position.
Remark
By setting the minimumSearchIndex value appropriately, simulations can be performed for path interpolations in which the path crosses the specified position multiple times.
For example, if the path crosses the specified position during the interpolation segments at indices 0, 2, and 4:
minimumSearchIndex = 0 will cause the simulation to calculate the move time, remain time, and total time for the first time that the path crosses the specified position.
minimumSearchIndex = 1 or 2 will cause the simulation to calculate the move time, remain time, and total time for the second time that the path crosses the specified position.
minimumSearchIndex = 3 or 4 will cause the simulation to calculate the move time, remain time, and total time for the third time that the path crosses the specified position.
- Parameters:
pPathIntplCommand – [in] A pointer to an object of the SimulatePathIntpl3DCommand class that contains the parameters for the 3D path interpolation.
specificPos1 – [in] The position of the first axis at which to calculate the move time, remain time, and total time of the 3D path interpolation command.
specificPos2 – [in] The position of the second axis at which to calculate the move time, remain time, and total time of the 3D path interpolation command.
specificPos3 – [in] The position of the third axis at which to calculate the move time, remain time, and total time of the 3D path interpolation command.
minimumSearchIndex – [in] The minimum index of the interpolation segments defined in pPathIntplCommand at which to search for the specified positions.
pMoveTimeMilliseconds – [out] A pointer to a double type variable that will contain the amount of time elapsed when the axes reach the position in three dimensions specified by specificPos1, specificPos2, and specificPos3. The units are milliseconds.
pRemainTimeMilliseconds – [out] A pointer to a double type variable that will contain the amount of time remaining in the 3D path interpolation when the axes reach the position in three dimensions specified by specificPos1, specificPos2, and specificPos3. The units are milliseconds.
pTotalTimeMilliseconds – [out] A pointer to a double type variable that will contain the total time of the 3D path interpolation. This value is always equal to the sum of the values returned by pMoveTime and pRemainTime. The units are milliseconds.
-
WMX3APIFUNC SimulateTimeAtDist(SimulatePathIntpl3DCommand *pPathIntplCommand, double specificDistance, double *pMoveTimeMilliseconds, double *pRemainTimeMilliseconds, double *pTotalTimeMilliseconds)
Simulate a 3D path interpolation command without moving any axes. The move time, remain time, and total time after the 3D path interpolation runs for the specified distance are returned.
Simulate a 3D path interpolation command without moving any axes. The move time, remain time, and total time after the 3D path interpolation runs for the specified distance are returned.
- Parameters:
pPathIntplCommand – [in] A pointer to an object of the SimulatePathIntpl3DCommand class that contains the parameters for the 3D path interpolation.
specificDistance – [in] The distance along the path at which to calculate the move time, remain time, and total time of the 3D path interpolation command.
pMoveTimeMilliseconds – [out] A pointer to a double type variable that will contain the amount of time elapsed when the axes travel along the path a distance equal to specificDistance. The units are milliseconds.
pRemainTimeMilliseconds – [out] A pointer to a double type variable that will contain the amount of time remaining in the 3D path interpolation when the axes travel along the path a distance equal to specificDistance. The units are milliseconds.
pTotalTimeMilliseconds – [out] A pointer to a double type variable that will contain the total time of the 3D path interpolation. This value is always equal to the sum of the values returned by pMoveTime and pRemainTime. The units are milliseconds.
Public Members
-
AdvancedMotion *amApi
-
class CoordinatedJerkRatioPosCommand
This class contains data for a coordinated position command with two or more axes.
Public Functions
-
CoordinatedJerkRatioPosCommand()
Public Members
-
PosCommand posCommand
The position command of the first axis.
-
int followerAxis[constants::maxAxes]
The axis numbers of the follower axes. The first followerAxisCount indices should contain the axis numbers.
-
double followerAxisTarget[constants::maxAxes]
The target positions of the follower axes. The first followerAxisCount indices should contain the target positions.
-
double followerAxisAcc[constants::maxAxes]
The accelerations of the follower axes. The first followerAxisCount indices should contain the accelerations.
-
double followerAxisJerkAccRatio[constants::maxAxes]
The jerk ratios of the follower axes. The first followerAxisCount indices should contain the jerk ratios.
-
CoordinatedJerkRatioPosCommand()
-
class CoordinatedPosCommand
This class contains data for a coordinated position command.
Public Functions
-
CoordinatedPosCommand()
Public Members
-
PosCommand posCommand
The position command of the first axis.
-
int axis2
The second axis of the motion command.
-
double axis2Target
The target position of the second axis.
-
double axis2SmoothRatio
The smoothing ratio of the second axis, specified as a value between 0 and 1.
-
CoordinatedPosCommand()
-
class PathIntpl3DAdditionalCommand
This class contains data for additional interpolation segment data for 3D path interpolation.
Public Functions
-
PathIntpl3DAdditionalCommand()
Public Members
-
Profile profile[constants::maxPathInterpolateAppendPoints]
The profile of the motion command for each segment.
-
unsigned int numPoints
The number of segments in the path interpolation. This value must be at least 1 and at most maxPathInterpolateAppendPoints.
-
PathIntplSegmentType::T type[constants::maxPathInterpolateAppendPoints]
The segment types of the segments in the path interpolation.
-
double target[constants::max3DPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
The target positions for each segment.
-
double circleIntermediateTarget[constants::max3DPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
For circular interpolation segments, the intermediate position that the arc travels through. This value only affects circular interpolation segments. This value should be specified in the indices for which type is Circular.
-
double timeMilliseconds[constants::maxPathInterpolateAppendPoints]
The pause time for pause segments, in units of milliseconds. This value only affects pause segments. This value should be specified in the indices for which type is Pause.
-
double autoSmoothRadius[constants::maxPathInterpolateAppendPoints]
The distance along the linear interpolation to replace with a circular interpolation if enableAutoSmooth is set to enabled. If either linear interpolation is shorter than this value, this value will be reduced to equal the shorter of the two linear interpolations.
-
PathIntpl3DAdditionalCommand()
-
class PathIntpl3DCommand
This class contains data for a 3D path interpolation motion command.
Public Functions
-
PathIntpl3DCommand()
Public Members
-
int axis[constants::max3DPathInterpolateDimensions]
The axes of the motion command.
-
Profile profile[constants::maxPathInterpolateAppendPoints]
The profile of the motion command for each segment.
-
unsigned int numPoints
The number of segments in the path interpolation. This value must be at least 1 and at most maxPathInterpolateAppendPoints.
-
PathIntplSegmentType::T type[constants::maxPathInterpolateAppendPoints]
The segment types of the segments in the path interpolation.
-
double target[constants::max3DPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
The target positions for each segment.
-
double circleIntermediateTarget[constants::max3DPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
For circular interpolation segments, the intermediate position that the arc travels through. This value only affects circular interpolation segments. This value should be specified in the indices for which type is Circular.
-
double timeMilliseconds[constants::maxPathInterpolateAppendPoints]
The pause time for pause segments, in units of milliseconds. This value only affects pause segments. This value should be specified in the indices for which type is Pause.
-
char enableAutoSmooth
0: Disable auto smoothing, 1: Enable auto smoothing. If enabled, circular interpolations will automatically be inserted between two consecutive linear interpolations to smooth out the transition and prevent the interpolating axes from changing the velocity suddenly.
-
double autoSmoothRadius[constants::maxPathInterpolateAppendPoints]
The distance along the linear interpolation to replace with a circular interpolation if enableAutoSmooth is set to enabled. If either linear interpolation is shorter than this value, this value will be reduced to equal the shorter of the two linear interpolations.
-
char enableConstProfile
If set to 0, a separate profile will be calculated for each interpolation segment. If set to 1, only one profile will be calculated for the entire path (only the first index of the profile array will be used).
-
unsigned int numOutputs
The number of times to set an output during the path interpolation. The outputs should be defined using the first numOutputs indices of the outputType, outputPoint, outputByteAddr, outputBitAddr, outputValue, and outputTriggerValue arrays.
-
PathIntplOutputType::T outputType[constants::maxPathInterpolateOutputs]
The trigger condition of each path interpolation output. Trigger conditions are only evaluated after trigger conditions in all earlier indices have triggered.
-
unsigned int outputPoint[constants::maxPathInterpolateOutputs]
The segment parameter for the RemainingTime, CompletedTime, RemainingDist, CompletedDist, and DistanceRatio trigger conditions.
-
double outputTriggerValue[constants::maxPathInterpolateOutputs]
The time parameter for the RemainingTime and CompletedTime trigger conditions, or the distance parameter for the RemainingDist and CompletedDist trigger conditions, or the ratio parameter for the DistanceRatio trigger condition.
-
PathIntplOutputSource::T outputSource[constants::maxPathInterpolateOutputs]
The source of the output to set when the trigger condition is satisfied.
-
int outputByteAddr[constants::maxPathInterpolateOutputs]
The byte address of the output to set when the trigger condition is satisfied.
-
char outputBitAddr[constants::maxPathInterpolateOutputs]
The bit of the output to set when the trigger condition is satisfied.
-
char outputValue[constants::maxPathInterpolateOutputs]
The value to set the output to when the trigger condition is satisfied (0 or 1).
-
PathIntpl3DCommand()
-
class PathIntplAdditionalCommand
This class contains data for additional interpolation segment data for path interpolation.
Public Functions
-
PathIntplAdditionalCommand()
Public Members
-
Profile profile[constants::maxPathInterpolateAppendPoints]
The profile of the motion command for each segment.
-
unsigned int numPoints
The number of segments in the path interpolation. This value must be at least 1 and at most maxPathInterpolateAppendPoints.
-
PathIntplSegmentType::T type[constants::maxPathInterpolateAppendPoints]
The segment types of the segments in the path interpolation.
-
char direction[constants::maxPathInterpolateAppendPoints]
For circular interpolation segments, 1 for counterclockwise and -1 for clockwise motion. This value only affects circular interpolation segments. This value should be specified in the indices for which type is Circular.
-
double target[constants::maxPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
The target positions for each segment.
-
double centerPos[constants::maxPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
The center positions for circular interpolation segments. This value only affects circular interpolation segments. This value should be specified in the indices for which type is Circular.
-
double timeMilliseconds[constants::maxPathInterpolateAppendPoints]
The pause time for pause segments, in units of milliseconds. This value only affects pause segments. This value should be specified in the indices for which type is Pause.
-
double autoSmoothRadius[constants::maxPathInterpolateAppendPoints]
The distance along the linear interpolation to replace with a circular interpolation if enableAutoSmooth is set to enabled. If either linear interpolation is shorter than this value, this value will be reduced to equal the shorter of the two linear interpolations.
-
PathIntplAdditionalCommand()
-
class PathIntplCommand
This class contains data for a path interpolation motion command.
Public Functions
-
PathIntplCommand()
Public Members
-
int axis[constants::maxPathInterpolateDimensions]
The axes of the motion command.
-
Profile profile[constants::maxPathInterpolateAppendPoints]
The profile of the motion command for each segment.
-
unsigned int numPoints
The number of segments in the path interpolation. This value must be at least 1 and at most maxPathInterpolateAppendPoints.
-
PathIntplSegmentType::T type[constants::maxPathInterpolateAppendPoints]
The segment types of the segments in the path interpolation.
-
char direction[constants::maxPathInterpolateAppendPoints]
For circular interpolation segments, 1 for counterclockwise and -1 for clockwise motion. This value only affects circular interpolation segments. This value should be specified in the indices for which type is Circular.
-
double target[constants::maxPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
The target positions for each segment.
-
double centerPos[constants::maxPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
The center positions for circular interpolation segments. This value only affects circular interpolation segments. This value should be specified in the indices for which type is Circular.
-
double timeMilliseconds[constants::maxPathInterpolateAppendPoints]
The pause time for pause segments, in units of milliseconds. This value only affects pause segments. This value should be specified in the indices for which type is Pause.
-
char enableAutoSmooth
0: Disable auto smoothing, 1: Enable auto smoothing. If enabled, circular interpolations will automatically be inserted between two consecutive linear interpolations to smooth out the transition and prevent either axis from changing the velocity suddenly.
-
double autoSmoothRadius[constants::maxPathInterpolateAppendPoints]
The distance along the linear interpolation to replace with a circular interpolation if enableAutoSmooth is set to enabled. If either linear interpolation is shorter than this value, this value will be reduced to equal the shorter of the two linear interpolations.
-
char enableConstProfile
If set to 0, a separate profile will be calculated for each interpolation segment. If set to 1, only one profile will be calculated for the entire path (only the first index of the profile array will be used).
-
unsigned int numOutputs
The number of times to set an output during the path interpolation. The outputs should be defined using the first numOutputs indices of the outputType, outputPoint, outputByteAddr, outputBitAddr, outputValue, and outputTriggerValue arrays.
-
PathIntplOutputType::T outputType[constants::maxPathInterpolateOutputs]
The trigger condition of each path interpolation output. Trigger conditions are only evaluated after trigger conditions in all earlier indices have triggered.
-
unsigned int outputPoint[constants::maxPathInterpolateOutputs]
The segment parameter for the RemainingTime, CompletedTime, RemainingDist, CompletedDist, and DistanceRatio trigger conditions.
-
double outputTriggerValue[constants::maxPathInterpolateOutputs]
The time parameter for the RemainingTime and CompletedTime trigger conditions, or the distance parameter for the RemainingDist and CompletedDist trigger conditions, or the ratio parameter for the DistanceRatio trigger condition.
-
PathIntplOutputSource::T outputSource[constants::maxPathInterpolateOutputs]
The source of the output to set when the trigger condition is satisfied.
-
int outputByteAddr[constants::maxPathInterpolateOutputs]
The byte address of the output to set when the trigger condition is satisfied.
-
char outputBitAddr[constants::maxPathInterpolateOutputs]
The bit of the output to set when the trigger condition is satisfied.
-
char outputValue[constants::maxPathInterpolateOutputs]
The value to set the output to when the trigger condition is satisfied (0 or 1).
-
PathIntplCommand()
-
class PathIntplCoordinateType
This enumerator class enumerates the coordinate types of path interpolations. The coordinate type determines how the coordinates are specified when defining positions in a path interpolation.
Public Types
-
enum T
Values:
-
enumerator Absolute
The points are specified in absolute coordinates.
-
enumerator RelativeFromStart
The points are specified in coordinates relative from the start of the path.
-
enumerator RelativeFromEnd
The points are specified in coordinates relative from the current end of the path.
-
enumerator Absolute
-
enum T
-
class PathIntplLookaheadCommand
This class contains data for path interpolation with look ahead.
Public Functions
-
PathIntplLookaheadCommand()
Public Members
-
unsigned int numPoints
The number of points (segments) to append to the path interpolation with look ahead.
-
PathIntplLookaheadCommandPoint point[constants::maxPathIntplLookaheadAppendPoints]
An array of PathIntplLookaheadCommandPoint objects that define the parameters for each point. The first numPoints indices must contain the point parameter data.
-
PathIntplLookaheadCommand()
-
class PathIntplLookaheadCommandPoint
This class contains data for one point in the path interpolation with look ahead motion command.
Public Functions
-
PathIntplLookaheadCommandPoint()
Public Members
-
PathIntplLookaheadSegmentType::T type
The segment type of this point. The segment type determines whether this point is a linear or circular interpolation, and if it is a circular interpolation, the parameters that define the arc.
-
union wmx3Api::AdvMotion::PathIntplLookaheadCommandPoint::Data data
-
union Data
This union defines the structs containing parameters for each segment type. The parameters should be specified in the struct corresponding to the PathIntplLookaheadSegmentType of this point.
Public Functions
-
Data()
Public Members
-
struct wmx3Api::AdvMotion::PathIntplLookaheadCommandPoint::Data::Linear linear
-
struct wmx3Api::AdvMotion::PathIntplLookaheadCommandPoint::Data::CenterAndLengthCircular centerAndLengthCircular
-
struct wmx3Api::AdvMotion::PathIntplLookaheadCommandPoint::Data::CenterAndEndCircular centerAndEndCircular
-
struct wmx3Api::AdvMotion::PathIntplLookaheadCommandPoint::Data::ThroughAndEndCircular throughAndEndCircular
-
struct wmx3Api::AdvMotion::PathIntplLookaheadCommandPoint::Data::LengthAndEndCircular lengthAndEndCircular
-
struct wmx3Api::AdvMotion::PathIntplLookaheadCommandPoint::Data::RadiusAndEndCircular radiusAndEndCircular
-
struct wmx3Api::AdvMotion::PathIntplLookaheadCommandPoint::Data::ThroughAndEnd3DCircular throughAndEnd3DCircular
-
struct wmx3Api::AdvMotion::PathIntplLookaheadCommandPoint::Data::Sleep sleep
-
struct wmx3Api::AdvMotion::PathIntplLookaheadCommandPoint::Data::SetOutputBit setOutputBit
-
struct CenterAndEndCircular
This structure contains the arguments for the CenterAndEndCircular segment type.
Public Members
-
int axis[2]
The two axes commanded by this circular segment. The axes commanded in this circular segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double centerPos[2]
The center position of the circular segment, specified as the absolute positions of the two interpolating axes. The center position must be at least 1e-6 user units away from the start position and end position.
-
double endPos[2]
The end position of the circular segment, specified as the absolute positions of the two interpolating axes. The end position must be at least 1e-6 user units away from the center position, but can be the same position as the start position.
-
unsigned char clockwise
If set to 0, the motion will be in the counterclockwise direction. If set to 1, the motion will be in the clockwise direction.
-
bool setSegmentCompositeVel
When set to TRUE, this point will override the compositeVel configured for the entire path with segmentCompositeVel while executing this segment. This allows the composite velocity along the path to be adjusted for specific parts of the path.
-
double segmentCompositeVel
This value is ignored if setSegmentCompositeVel is set to FALSE. This value overrides the compositeVel configured for the entire path during the execution of the segment defined in this class. This value has no effect if set to 0. This value has no effect if the type is not Linear or one of the circular segment types.
-
unsigned int auxiliaryAxisCount
The number of auxiliary axes commanded by this segment. Auxiliary axes interpolate with the circular interpolation to move to the specified target position.
-
int auxiliaryAxis[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the auxiliary axes that are commanded by this segment. The auxiliaryAxisCount member of this struct determines the number of axes defined in this array. The axes commanded in this segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double auxiliaryTarget[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the target positions of the auxiliary axes.
-
int axis[2]
-
struct CenterAndLengthCircular
This structure contains the arguments for the CenterAndLengthCircular segment type.
Public Members
-
int axis[2]
The two axes commanded by this circular segment. The axes commanded in this circular segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double centerPos[2]
The center position of the circular segment, specified as the absolute positions of the two interpolating axes. The center position must be at least 1e-6 user units away from the start position.
-
double arcLengthDegree
The arc length of the circular segment, in units of degrees.
-
unsigned char clockwise
If set to 0, a positive arcLengthDegree will result in motion in the counterclockwise direction. If set to 1, a positive arcLengthDegree will result in motion in the clockwise direction.
-
bool setSegmentCompositeVel
When set to TRUE, this point will override the compositeVel configured for the entire path with segmentCompositeVel while executing this segment. This allows the composite velocity along the path to be adjusted for specific parts of the path.
-
double segmentCompositeVel
This value is ignored if setSegmentCompositeVel is set to FALSE. This value overrides the compositeVel configured for the entire path during the execution of the segment defined in this class. This value has no effect if set to 0. This value has no effect if the type is not Linear or one of the circular segment types.
-
unsigned int auxiliaryAxisCount
The number of auxiliary axes commanded by this segment. Auxiliary axes interpolate with the circular interpolation to move to the specified target position.
-
int auxiliaryAxis[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the auxiliary axes that are commanded by this segment. The auxiliaryAxisCount member of this struct determines the number of axes defined in this array. The axes commanded in this segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double auxiliaryTarget[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the target positions of the auxiliary axes.
-
int axis[2]
-
struct LengthAndEndCircular
This structure contains the arguments for the LengthAndEndCircular segment type.
Public Members
-
int axis[2]
The two axes commanded by this circular segment. The axes commanded in this circular segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double endPos[2]
The end position of the circular segment, specified as the absolute positions of the two interpolating axes. The end position must be at least 1e-6 user units away from the start position.
-
double arcLengthDegree
The arc length of the circular segment, in units of degrees.
-
unsigned char clockwise
If set to 0, a positive arcLengthDegree will result in motion in the counterclockwise direction. If set to 1, a positive arcLengthDegree will result in motion in the clockwise direction.
-
bool setSegmentCompositeVel
When set to TRUE, this point will override the compositeVel configured for the entire path with segmentCompositeVel while executing this segment. This allows the composite velocity along the path to be adjusted for specific parts of the path.
-
double segmentCompositeVel
This value is ignored if setSegmentCompositeVel is set to FALSE. This value overrides the compositeVel configured for the entire path during the execution of the segment defined in this class. This value has no effect if set to 0. This value has no effect if the type is not Linear or one of the circular segment types.
-
unsigned int auxiliaryAxisCount
The number of auxiliary axes commanded by this segment. Auxiliary axes interpolate with the circular interpolation to move to the specified target position.
-
int auxiliaryAxis[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the auxiliary axes that are commanded by this segment. The auxiliaryAxisCount member of this struct determines the number of axes defined in this array. The axes commanded in this segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double auxiliaryTarget[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the target positions of the auxiliary axes.
-
int axis[2]
-
struct Linear
This structure contains the arguments for the Linear segment type.
Public Members
-
unsigned int axisCount
The number of axes in the linear segment. This determines the number of axes that will be defined in the axis array.
-
int axis[constants::maxPathIntplLookaheadDimensions]
An array containing the axes that are commanded in this linear segment. The axisCount member of this struct determines the number of axes defined in this array. The axes commanded in this linear segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double target[constants::maxPathIntplLookaheadDimensions]
An array containing the absolute target positions for the axes commanded by this linear segment. The target position will be set for the axis defined in the same index of the axis array.
-
double smoothRadius
The distance along this linear segment and the distance along the next linear segment to replace with a circular segment. This value has no effect if the type of this segment is circular, if the type of the next segment is circular, or if this segment and the next segment do not exist in the same 3D space. Two linear segments are considered to exist in the same 3D space if the number of axes shared between them is 3 or less. Increasing the smoothing radius will allow the linear segments to be traversed at a higher velocity, but because of the larger radius of smoothing, the path will stray a greater amount from the original commanded path. Whenever there is a sequence of three or more linear segments, the radius of smoothing will automatically be adjusted to prevent one smoothing segment from causing the next smoothing segment to have a tiny radius.
-
bool setSegmentCompositeVel
When set to TRUE, this point will override the compositeVel configured for the entire path with segmentCompositeVel while executing this segment. This allows the composite velocity along the path to be adjusted for specific parts of the path.
-
double segmentCompositeVel
This value is ignored if setSegmentCompositeVel is set to FALSE. This value overrides the compositeVel configured for the entire path during the execution of the segment defined in this class. This value has no effect if set to 0. This value has no effect if the type is not Linear or one of the circular segment types.
-
unsigned int auxiliaryAxisCount
The number of auxiliary axes commanded by this segment. Auxiliary axes interpolate with the circular interpolation to move to the specified target position.
-
int auxiliaryAxis[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the auxiliary axes that are commanded by this segment. The auxiliaryAxisCount member of this struct determines the number of axes defined in this array. The axes commanded in this segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double auxiliaryTarget[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the target positions of the auxiliary axes.
-
unsigned int axisCount
-
struct RadiusAndEndCircular
This structure contains the arguments for the RadiusAndEndCircular segment type.
Public Members
-
int axis[2]
The two axes commanded by this circular segment. The axes commanded in this circular segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double endPos[2]
The end position of the circular segment, specified as the absolute positions of the two interpolating axes. The end position must be at least 1e-6 user units away from the start position.
-
double radius
The arc radius of the circular segment. A positive radius generates an arc of equal to or less than 180 degrees. A negative radius generates an arc of equal to or greater than 180 degrees. A radius with an absolute value smaller than half the distance to the end point generates an arc of 180 degrees.
-
unsigned char clockwise
If set to 0, the motion will be in the counterclockwise direction. If set to 1, the motion will be in the clockwise direction.
-
bool setSegmentCompositeVel
When set to TRUE, this point will override the compositeVel configured for the entire path with segmentCompositeVel while executing this segment. This allows the composite velocity along the path to be adjusted for specific parts of the path.
-
double segmentCompositeVel
This value is ignored if setSegmentCompositeVel is set to FALSE. This value overrides the compositeVel configured for the entire path during the execution of the segment defined in this class. This value has no effect if set to 0. This value has no effect if the type is not Linear or one of the circular segment types.
-
unsigned int auxiliaryAxisCount
The number of auxiliary axes commanded by this segment. Auxiliary axes interpolate with the circular interpolation to move to the specified target position.
-
int auxiliaryAxis[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the auxiliary axes that are commanded by this segment. The auxiliaryAxisCount member of this struct determines the number of axes defined in this array. The axes commanded in this segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double auxiliaryTarget[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the target positions of the auxiliary axes.
-
int axis[2]
-
struct SetOutputBit
This structure contains arguments for the SetOutputBit segment type.
Public Members
-
PathIntplOutputType::T type
The trigger condition of the output. Trigger conditions are evaluated during the execution of the next segment in the path that is not a SetOutputBit segment.
-
double triggerValue
The time parameter for the RemainingTime and CompletedTime trigger conditions, or the distance parameter for the RemainingDist and CompletedDist trigger conditions, or the ratio parameter for the DistanceRatio trigger condition.
-
PathIntplOutputSource::T source
The source of the output to set when the trigger condition is satisfied.
-
unsigned int byteAddress
The byte address of the output.
-
unsigned char bitAddress
The bit address of the output.
-
unsigned char value
The value (0 or 1) to set the output to.
-
PathIntplOutputType::T type
-
struct Sleep
This structure contains arguments for the Sleep segment type.
Public Members
-
unsigned int milliseconds
The time in milliseconds to pause motion.
-
unsigned int milliseconds
-
struct ThroughAndEnd3DCircular
This structure contains the arguments for the ThroughAndEnd3DCircular segment type.
Public Members
-
int axis[3]
The three axes commanded by this circular segment. The axes commanded in this circular segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double throughPos[3]
A through point that the axes will pass through during the circular segment, specified as the absolute positions of the three interpolating axes. The through position must be at least 1e-6 user units away from the start position and end position.
-
double endPos[3]
The end position of the circular segment, specified as the absolute positions of the three interpolating axes. The end position must be at least 1e-6 user units away from the start position and through position.
-
bool setSegmentCompositeVel
When set to TRUE, this point will override the compositeVel configured for the entire path with segmentCompositeVel while executing this segment. This allows the composite velocity along the path to be adjusted for specific parts of the path.
-
double segmentCompositeVel
This value is ignored if setSegmentCompositeVel is set to FALSE. This value overrides the compositeVel configured for the entire path during the execution of the segment defined in this class. This value has no effect if set to 0. This value has no effect if the type is not Linear or one of the circular segment types.
-
unsigned int auxiliaryAxisCount
The number of auxiliary axes commanded by this segment. Auxiliary axes interpolate with the circular interpolation to move to the specified target position.
-
int auxiliaryAxis[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the auxiliary axes that are commanded by this segment. The auxiliaryAxisCount member of this struct determines the number of axes defined in this array. The axes commanded in this segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double auxiliaryTarget[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the target positions of the auxiliary axes.
-
int axis[3]
-
struct ThroughAndEndCircular
This structure contains the arguments for the ThroughAndEndCircular segment type.
Public Members
-
int axis[2]
The two axes commanded by this circular segment. The axes commanded in this circular segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double throughPos[2]
A through point that the axes will pass through during the circular segment, specified as the absolute positions of the two interpolating axes. The through position must be at least 1e-6 user units away from the start position and end position.
-
double endPos[2]
The end position of the circular segment, specified as the absolute positions of the two interpolating axes. The end position must be at least 1e-6 user units away from the start position and through position.
-
bool setSegmentCompositeVel
When set to TRUE, this point will override the compositeVel configured for the entire path with segmentCompositeVel while executing this segment. This allows the composite velocity along the path to be adjusted for specific parts of the path.
-
double segmentCompositeVel
This value is ignored if setSegmentCompositeVel is set to FALSE. This value overrides the compositeVel configured for the entire path during the execution of the segment defined in this class. This value has no effect if set to 0. This value has no effect if the type is not Linear or one of the circular segment types.
-
unsigned int auxiliaryAxisCount
The number of auxiliary axes commanded by this segment. Auxiliary axes interpolate with the circular interpolation to move to the specified target position.
-
int auxiliaryAxis[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the auxiliary axes that are commanded by this segment. The auxiliaryAxisCount member of this struct determines the number of axes defined in this array. The axes commanded in this segment must be a subset of the axes configured to be commanded by this path interpolation channel (see PathIntplLookaheadConfiguration).
-
double auxiliaryTarget[constants::maxPathIntplLookaheadAuxiliaryAxes]
An array containing the target positions of the auxiliary axes.
-
int axis[2]
-
Data()
-
PathIntplLookaheadCommandPoint()
-
class PathIntplLookaheadConfiguration
This class contains the configuration data for a path interpolation with look ahead channel.
Public Functions
-
PathIntplLookaheadConfiguration()
Public Members
-
unsigned int axisCount
The axis count of the path interpolation with look ahead channel. This determines the number of axes that will be defined in the axis array. The maximum number of axes that may be controlled is maxPathIntplLookaheadDimensions.
-
int axis[constants::maxPathIntplLookaheadDimensions]
An array containing the axes that can be used in the path interpolation with look ahead channel. Only the axes defined here may be commanded in the interpolation segments of the path interpolation. The axisCount member of this class determines the number of axes defined in this array.
-
double velocityLimit[constants::maxPathIntplLookaheadDimensions]
An array containing the velocity limits of each axis, in user units per second. The velocity limit will be applied to the axis defined in the same index of the axis array. If set to 0, that axis will have no velocity limit.
-
double accLimit[constants::maxPathIntplLookaheadDimensions]
An array containing the acceleration limits of each axis, in user units per second squared. The acceleration limit will be applied to the axis defined in the same index of the axis array. If set to 0, that axis will have no acceleration limit.
-
double compositeVel
The composite velocity along the interpolation path, in user units per second. This is the velocity at which the interpolating axes travel along the path. A nonzero value must be specified. The actual velocity at each point along the path will be reduced based on the velocity and acceleration limits of each axis.
-
double compositeAcc
The composite acceleration along the interpolation path, in user units per second squared. This is the acceleration at which the interpolating axes travel along the path. A nonzero value must be specified. The actual acceleration at each point along the path will be reduced based on the velocity and acceleration limits of each axis.
-
double sampleDistance
The distance between the samples taken to calculate the velocity and acceleration limits. Increasing this value will reduce the precision of the generated look ahead profile. This can cause the acceleration or velocity to stray further from the specified limits, or cause jitter in the acceleration. However, increasing this value will also increase the look ahead distance, meaning that the look ahead algorithm will be able to detect sudden changes in the velocity or acceleration along the path from farther away. The distance of the path that can be stored in the buffer of a path interpolation with look ahead channel is equal to this value multiplied by maxPathIntplLookaheadAppendPoints. Attempting to add segments to the path exceeding this distance will cause the ChannelNotEnoughSpace to be returned. As the motion continues along the path, buffer space is freed so more segments can be added to the path.
-
bool setOverrideTime
When set to TRUE, the override time can be specified with the overrideTimePointsPerMillisecond parameter. The override time determines the amount of time that points appended to the path will not affect the velocity and acceleration along the path. This parameter is only applicable when adding points to the path while the path is executing motion. When this parameter is set to FALSE, the default override time of 1ms per 2000 points remaining in the path (minimum 8ms) is used. Most users should keep this parameter at FALSE.
-
unsigned int overrideTimePointsPerMillisecond
If the setOverrideTime parameter is set to TRUE, this parameter determines the override time when points are appended to the path while in motion. This parameter is specified in units of points per millisecond. A larger value will allocate a shorter override time (as 1ms is allocated for a larger number of points) and a smaller value will allocate a longer override time. A shorter override time may be suitable for fast CPUs and a longer override time may be suitable for slow CPUs. As an example, if this parameter is set to 1000, there are 30000 points remaining in the path, and 20000 more points are added, the allocated override time is (30000 + 20000) / 1000 = 50ms. This parameter can be useful if the command position suddenly changes along the path when using a very slow CPU, or to potentially slightly reduce the time taken to traverse the path when using a very fast CPU. This parameter has no effect when points are appended to the path while not in motion. The lastOverridePointsPerMillisecond status can be read after appending points to the path while in motion to see how many points were actually processed per millisecond. The lastOverridePointsPerMillisecond status will contain 0 if the lastOverrideTimeMilliseconds status is also 0. If this occurs, points should be appended while a larger number of points remain in the path, or a larger number of points should be appended at once.
-
bool setAngleTolerance
When set to TRUE, the angle tolerance between interpolation segments is set to the value of angleToleranceDegrees. When set to FALSE, the angle tolerance between interpolation segments is set to the default value of 1 degree. See the description of angleToleranceDegrees for additional information.
-
double angleToleranceDegrees
This value is ignored if setAngleTolerance is set to FALSE. This value sets the tolerance for the change in direction at the interface between two interpolation segments. If this tolerance is exceeded, the interpolating axes will stop at the interface. If the change in direction is less than this value, the interpolation axes will turn the corner without coming to a stop. Two linear interpolations that move in the same direction have a 0 degree change in direction. Two linear interpolations that move in opposite directions will have a 180 degree change in direction. The change in direction is always between 0 and 180 degrees. This parameter is specified in units of degrees.
-
PathIntplLookaheadCoordinateType::T coordinateType
The type of coordinates to use when specifying the axis positions in the path.
-
bool stopOnEmptyBuffer
If set to TRUE, the state of the path interpolation with look ahead channel will automatically change to Stopped when the last command in the buffer is executed and the buffer becomes empty.
-
bool setSmoothingTime
If set to TRUE, a moving average filter will be applied to the individual axes of the path interpolation with look ahead command. This will alter the shape of the path. If set to FALSE, the path interpolation with look ahead motion profile will be generated normally.
-
double firstSmoothingTimeMilliseconds[constants::maxPathIntplLookaheadDimensions]
If the setSmoothingTime is set to TRUE, this parameter specifies the first smoothing time to apply to the individual axes of the path interpolation with look ahead in units of milliseconds. This is the smoothing time applied during the first pass of the two-pass filter. When this value is converted from milliseconds to cycles, it must be less than maxPathIntplLookaheadSmoothingCycles cycles.
-
double secondSmoothingTimeMilliseconds[constants::maxPathIntplLookaheadDimensions]
If the setSmoothingTime is set to TRUE, this parameter specifies the second smoothing time to apply to the individual axes of the path interpolation with look ahead in units of milliseconds. This is the smoothing time applied during the second pass of the two-pass filter. When this value is converted from milliseconds to cycles, it must be less than maxPathIntplLookaheadSmoothingCycles cycles.
-
PathIntplLookaheadConfiguration()
-
class PathIntplLookaheadCoordinateType
This enumerator class enumerates the coordinate types of path interpolations with look ahead. The coordinate type determines how the coordinates are specified when defining positions in a path interpolation with look ahead.
Public Types
-
enum T
Values:
-
enumerator Absolute
The points are specified in absolute coordinates.
-
enumerator RelativeFromPreviousPoint
The points are specified in coordinates relative from the previous point.
-
enumerator RelativeFromStart
The points are specified in coordinates relative from the start of the path.
-
enumerator Absolute
-
enum T
-
class PathIntplLookaheadSegmentType
This enumerator class enumerates the segment types of motion segments in a path interpolation with look ahead.
Public Types
-
enum T
Values:
-
enumerator Linear
The segment is a linear interpolation segment.
-
enumerator CenterAndLengthCircular
The segment is a circular interpolation segment defined by the center point and arc length.
-
enumerator CenterAndEndCircular
The segment is a circular interpolation segment defined by the center point and end point.
-
enumerator ThroughAndEndCircular
The segment is a circular interpolation segment defined by an intermediate through point and end point.
-
enumerator LengthAndEndCircular
The segment is a circular interpolation segment defined by the end point and arc length.
-
enumerator RadiusAndEndCircular
The segment is a circular interpolation segment defined by the end point and arc radius.
-
enumerator ThroughAndEnd3DCircular
The segment is a three-dimensional circular interpolation segment defined by an intermediate through point and end point.
-
enumerator Sleep
The motion is paused for a specified period when this command is executed. The axes will decelerate to zero velocity wherever this command is in the path.
-
enumerator SetOutputBit
An I/O output bit is set when this command is executed.
-
enumerator Linear
-
enum T
-
class PathIntplLookaheadState
This enumerator class enumerates the states of a path interpolation with look ahead channel.
Public Types
-
enum T
Values:
-
enumerator Idle
The path interpolation with look ahead channel is idle and is not executing any commands.
-
enumerator Configured
The path interpolation with look ahead channel is configured but is not executing any commands.
-
enumerator Executing
The path interpolation with look ahead channel is executing commands.
-
enumerator Stopping
The path interpolation with look ahead channel is stopping motion.
-
enumerator Stopped
The path interpolation with look ahead channel has stopped motion.
-
enumerator Idle
-
enum T
-
class PathIntplLookaheadStatus
This class contains status data for a path interpolation with look ahead channel.
Public Functions
-
PathIntplLookaheadStatus()
Public Members
-
PathIntplLookaheadState::T state
The state of the path interpolation with look ahead channel.
-
unsigned int remainBuffer
The number of point data in the buffer that have not been executed yet. Each point data occupies one space in the buffer allocated with CreatePathIntplLookaheadBuffer. Each command that is added to the buffer with AddPathIntplLookaheadCommand may occupy one or more buffer spaces, depending on the type of command and parameters such as sampleDistance.
-
unsigned int freeBuffer
The number of additional point data that can be stored in the buffer memory. Buffer memory is allocated with the CreatePathIntplLookaheadBuffer function. Buffer memory is freed as the path interpolation with look ahead channel executes commands.
-
unsigned int executedBuffer
The number of point data that have been executed by the path interpolation with look ahead channel. As additional point data may be added to the buffer as it executes, this value may become greater than the size of the buffer memory. This value is cleared when the ClearPathIntplLookahead function is called.
-
unsigned int maxBuffer
The total size of the buffer memory for storing point data, in units of points. This value is equal to the amount specified to the CreatePathIntplLookaheadBuffer function. The number of bytes of memory that each point occupies can be obtained with the GetPathIntplLookaheadBytesPerPoint function.
-
unsigned int remainCommandCount
The number of commands remaining in the path. Commands are added to the path interpolation with the AddPathIntplLookaheadCommand function. Each command may occupy one or more point data spaces in the buffer. This value only decreases when a command completes. For linear and circular interpolation commands, this value decreases when the axes reach the target position. For sleep commands, this value decreases after the sleep time elapses.
-
unsigned int executedCommandCount
The number of commands that have been executed. This value only increases when a command completes. For linear and circular interpolation commands, this value increases when the axes reach the target position. For sleep commands, this value increases after the sleep time elapses.
-
unsigned int totalCommandCount
The total number of commands that have been added to the path. This value is equal to remainCommandCount plus executedCommandCount. This value is cleared when the ClearPathIntplLookahead function is called.
-
double lastOverrideTimeMilliseconds
The number of milliseconds taken to calculate the look ahead velocity and acceleration profiles the last time that points were appended to the path while in motion. This status can be helpful when setting the optional parameter overrideTimePointsPerMillisecond.
-
double lastOverridePointsPerMillisecond
The number of points processed per millisecond when calculating the look ahead velocity and acceleration profiles the last time that points were appended to the path while in motion. This status can be helpful when setting the optional parameter overrideTimePointsPerMillisecond.
-
PathIntplLookaheadStatus()
-
class PathIntplOutputSource
This enumerator class enumerates the output sources of outputs in a path interpolation.
-
class PathIntplOutputType
This enumerator class enumerates the output types of outputs in a path interpolation.
Public Types
-
enum T
Values:
-
enumerator Immediate
The output will be set immediately after reaching the specified segment.
-
enumerator RemainingTime
The output will be set when the time remaining until the end of the specified segment (in milliseconds) is less than the specified trigger value.
-
enumerator CompletedTime
The output will be set when the time elapsed after the start of the specified segment (in milliseconds) is greater than the specified trigger value.
-
enumerator RemainingDist
The output will be set when the distance remaining until the end of the specified segment (in user units) is less than the specified trigger value.
-
enumerator CompletedDist
The output will be set when the distance completed after the start of the specified segment (in user units) is greater than the specified trigger value.
-
enumerator DistanceRatio
The output will be set when the specified ratio (0-1) of the specified point has been traveled.
-
enumerator Immediate
-
enum T
-
class PathIntplSegmentType
This enumerator class enumerates the segment types of motion segments in a path interpolation.
-
class PathIntplWithRotationCommand
This class contains data for a path interpolation with rotation command.
Public Functions
-
PathIntplWithRotationCommand()
Public Members
-
unsigned int numPoints
The number of points (segments) to append to the path interpolation with rotation.
-
PathIntplWithRotationCommandPoint point[constants::maxPathIntplWithRotationAppendPoints]
An array of PathIntplWithRotationCommandPoint objects that defined the parameters for each point. The first numPoints indices must contain the point parameter data.
-
PathIntplWithRotationCommand()
-
class PathIntplWithRotationCommandPoint
This class contains data for one point in the path interpolation with rotation motion command.
Public Functions
-
PathIntplWithRotationCommandPoint()
Public Members
-
PathIntplSegmentType::T type
The segment type of this point. The segment type determines whether this point is a linear or circular interpolation.
-
Profile profile
The profile for this point. If the enableConstProfile parameter is set to 1, only the profile for the first point is used.
-
char direction
For circular interpolation segments, 1 for counterclockwise and -1 for clockwise motion. This value should be specified in the indices for which type is Circular.
-
double target[constants::maxPathInterpolateDimensions]
The target positions for the X and Y axes.
-
double centerPos[constants::maxPathInterpolateDimensions]
The X and Y axis center positions for circular interpolation segments. This value should be specified in the indices for which type is Circular.
-
double autoSmoothRadius
The distance along the linear interpolation to replace with a circular interpolation if enableAutoSmooth is set to 1. If either linear interpolation is shorter than this value, this value will be reduced to equal the shorter of the two linear interpolations.
-
double zAxisTarget
The target position for the Z axis, if the enableZAxis parameter is set to 1.
-
char useLocalCenterOfRotation
If this value is set to 1 and the enableLocalCenterOfRotation option is set to 1, during the execution of this segment, the rotational axis will face perpendicular to the vector from the current X and Y axis positions to the localCenterOfRotation of this segment. If this value is set to 0, the rotational axis will face in the direction of motion during the execution of this segment. This value has no effect if the enableLocalCenterOfRotation option is set to 0.
-
char localCenterOfRotationDirection
If useLocalCenterOfRotation is set to 1 for this segment and the enableLocalCenterOfRotation option is set to 1 for the path, this value is used to specify whether the path travels around the local center of rotation in the clockwise direction or counterclockwise direction. Specifying 1 for this value indicates motion in the counterclockwise direction and specifying -1 for this value indicates motion in the clockwise direction. Specifying the incorrect direction will cause the rotational axis to face the opposite direction when executing this segment. This value has no effect if the useLocalCenterOfRotation value is set to 0 for this segment or the enableLocalCenterOfRotation option is set to 0 for this path.
-
double localCenterOfRotation[constants::maxPathInterpolateDimensions]
If useLocalCenterOfRotation is set to 1 for this segment and the enableLocalCenterOfRotation option is set to 1 for the path, this value is used to specify the local center of rotation for this segment. During the execution of this segment, the rotational axis will face perpendicular to the vector from the current X and Y positions to this position. This value has no effect if the useLocalCenterOfRotation value is set to 0 for this segment or the enableLocalCenterOfRotation option is set to 0 for this path.
-
PathIntplWithRotationCommandPoint()
-
class PathIntplWithRotationConfiguration
This class contains the configuration data for a path interpolation with rotation channel.
Public Functions
-
PathIntplWithRotationConfiguration()
Public Members
-
int axis[constants::maxPathInterpolateDimensions]
The X and Y axes commanded by the path interpolation with rotation.
-
char enableAutoSmooth
0: Disable auto smoothing, 1: Enable auto smoothing. If enabled, circular interpolations will automatically be inserted between two consecutive linear interpolations to smooth out the transition and prevent sudden velocity changes in either axis.
-
char axisCoordinateFlip[constants::maxPathInterpolateDimensions]
If set to 1 for either or both axes, the coordinates of that axis will be flipped about the starting point of the path interpolation. Thus, target positions in the positive direction will move the axis in the negative direction instead. The motion of the axes due to the rotational axis will also be reversed.
-
int rotationalAxis
The rotational axis commanded by the path interpolation with rotation. This axis must be a single turn axis.
-
char rotationalAxisPolarity
The polarity of the rotational axis. 0 or 1 for normal and -1 for reversed polarity.
-
char disableRotationalAxis
0: Rotational axis is enabled. 1: Rotational axis is disabled, and the path interpolation with rotation will operate similarly to a regular path interpolation command. This option may be useful for verifying only the X and Y axis path without rotating the workpiece.
-
char disableXYRotationalMotion
0: The X and Y axes are rotated around the center of rotation when the rotational axis moves. 1: The X and Y axes are not rotated around the center of rotation when the rotational axis moves. This option may be useful for verifying the X and Y axis path.
-
double centerOfRotation[constants::maxPathInterpolateDimensions]
The center of rotation. Whenever the rotational axis moves, the entire path will rotate about this point.
-
PathIntplCoordinateType::T coordinateType
The type of coordinates to use when specifying the X and Y axis positions in the path.
-
char enableZAxis
0: Z axis is disabled. 1: Z axis is enabled. The Z axis is an additional axis that may be commanded during the path interpolation with rotation. The Z axis is not affected by the rotational axis, and interpolates between points linearly. The Z axis does not affect the velocity of the X and Y axes (all velocities are defined as the velocities of just the X and Y axes).
-
int zAxis
The Z axis commanded by the path interpolation. This parameter is ignored if the enableZAxis parameter is set to 0.
-
char enableConstProfile
0: A separate profile will be generated for each interpolation segment. 1: Only one profile will be generated for the entire path (only the profile specified for the first segment will be used).
-
char enableLocalCenterOfRotation
0: The rotational axis will face the direction of motion along the path during the execution of each segment. 1: For segments for which useLocalCenterOfRotation is set to 1, the rotational axis will face perpendicular to the vector from the current X and Y positions along the path to the local center of rotation specified in localCenterOfRotation for that segment.
-
double angleCorrectionMinimumAngle
The minimum angle between two segments to pause and apply angle correction, in units of degrees. At the interface between two segments, if the direction along the path changes by this amount or more, the motion along the path will decelerate to a stop and the rotational axis will rotate by the difference using the angleCorrectionProfile. If this value is set to a value greater than 180 degrees, no angle correction will occur at any segment. If this value is set to 0, angle correction will occur at the end of every segment.
-
Profile angleCorrectionProfile
The profile to use to move the rotational axis during angle correction motion. This profile must be specified even if the angleCorrectionMinimumAngle parameter is greater than 180, because an angle correction operation is automatically inserted at the beginning of the interpolation if the initial position of the rotary axis does not match the direction of the first interpolation segment in the path.
-
unsigned int numOutputs
The number of times to set an output during the path interpolation. The outputs are defined using the first numOutputs indices of the outputType, outputPoint, outputByteAddr, outputBitAddr, outputValue, and outputTriggerValue arrays.
-
PathIntplOutputType::T outputType[constants::maxPathInterpolateOutputs]
The trigger condition of each path interpolation output. Trigger conditions are only evaluated after trigger conditions in all earlier indices have triggered.
-
unsigned int outputPoint[constants::maxPathInterpolateOutputs]
The segment parameter for the RemainingTime, CompletedTime, RemainingDist, CompletedDist, and DistanceRatio trigger conditions.
-
double outputTriggerValue[constants::maxPathInterpolateOutputs]
The time parameter for the RemainingTime and CompletedTime trigger conditions, or the distance parameter for the RemainingDist and CompletedDist trigger conditions, or the ratio parameter for the DistanceRatio trigger condition.
-
PathIntplOutputSource::T outputSource[constants::maxPathInterpolateOutputs]
The source of the output to set when the trigger condition is satisfied.
-
int outputByteAddr[constants::maxPathInterpolateOutputs]
The byte address of the output to set when the trigger condition is satisfied.
-
char outputBitAddr[constants::maxPathInterpolateOutputs]
The bit of the output to set when the trigger condition is satisfied.
-
char outputValue[constants::maxPathInterpolateOutputs]
The value to set the output to when the trigger condition is satisfied (0 or 1).
-
PathIntplWithRotationConfiguration()
-
class PathIntplWithRotationState
This enumerator class enumerates the path interpolation with rotation states.
-
class PathIntplWithRotationStatus
This class contains status data for a path interpolation with rotation channel.
Public Functions
-
PathIntplWithRotationStatus()
Public Members
-
PathIntplWithRotationState::T state
The state of the path interpolation with rotation channel.
-
unsigned int freeBuffer
The number of additional point data that can be stored in the buffer memory. Buffer memory is allocated with the CreatePathIntplWithRotationBuffer function. Each segment in the path occupies one point in the buffer memory, and auto smoothing segments inserted between linear interpolations also each occupy one point in the buffer memory.
-
unsigned int executedBuffer
The number of point data that have been executed at the current position in the path.
-
unsigned int maxBuffer
The total number of point data that can be stored in the buffer memory. This status counts buffer memory that is both occupied and unoccupied by point data.
-
unsigned int totalBuffer
The number of point data that is stored in the buffer memory. This status is equal to maxBuffer - freeBuffer.
-
unsigned int executedCommandCount
The number of command segments that have been executed at the current position in the path. Command segments are added to the path with the AddPathIntplWithRotationCommand function. Auto smoothing segments inserted between linear interpolations are not counted.
-
unsigned int totalCommandCount
The total number of command segments that are stored in the buffer memory.
-
double pos
The distance along the path between the current position and the start of the path. The units are in user units of the X and Y axes.
-
double totalDist
The total distance along the path between the start of the path and the end of the path. This distance may change with the addition of auto smoothing segments. The units are in user units of the X and Y axes.
-
PathIntplWithRotationStatus()
-
class PointTimeSplineCommand
This class contains data for a spline command in which the time at each point is specified.
Public Functions
-
PointTimeSplineCommand()
Public Members
-
unsigned int dimensionCount
The number of axes in the spline. This value must be between 1 and maxSplineDimensions.
-
int axis[constants::maxSplineDimensions]
The axes of the spline motion command. The axes are specified in the first dimensionCount indices.
-
PointTimeSplineCommand()
-
class ProfileSplineCommand
This class contains data for a spline command in which the spline is traversed using a motion profile.
Public Functions
-
ProfileSplineCommand()
Public Members
-
unsigned int dimensionCount
The number of axes in the spline. This value must be between 1 and maxSplineDimensions.
-
int axis[constants::maxSplineDimensions]
The axes of the spline motion command. The axes are specified in the first dimensionCount indices.
-
unsigned char ignoreDimensionForDistanceCalc[constants::maxSplineDimensions]
This value can be set to 1 to ignore particular axes when calculating the distances between points. The distance between points is used to calculate the time at which that point is traversed, with longer distances receiving a proportionally longer amount of time to traverse. This parameter allows axes which should not be considered for this distance calculation (for example, rotary axes) to be ignored.
-
unsigned int sampleMultiplier
If set to 2 or higher, it will increase the number of point samples by that factor. For example, if the number of points is 100 and sampleMultiplier is 5, a total of 500 samples will be taken. The additional samples are spaced so that each pair of adjacent points will have the same number of samples. This has the effect of reducing fluctuations of the velocity along the spline.
-
unsigned char sampleMultiplierCubicDistribution
If set to 1, the additional samples taken by the SampleMultiplier parameter will follow a cubic distribution, so that more samples are taken near the original points. Enabling this option can potentially reduce fluctuations in the velocity. The number of samples taken is not changed whether this option is enabled or not.
-
ProfileSplineCommand()
-
class SimulatePathIntpl3DCommand
This class contains data for simulating a 3D path interpolation motion.
Public Functions
-
SimulatePathIntpl3DCommand()
Public Members
-
int axis[constants::max3DPathInterpolateDimensions]
The axes of the simulation.
-
Profile profile[constants::maxPathInterpolateAppendPoints]
The profile of the simulation for each segment.
-
unsigned int numPoints
The number of segments in the path interpolation.
-
PathIntplSegmentType::T type[constants::maxPathInterpolateAppendPoints]
The segment types of the segments in the path interpolation.
-
double target[constants::max3DPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
The target positions for each segment.
-
double circleIntermediateTarget[constants::max3DPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
For circular interpolation segments, the intermediate position that the arc travels through. This value only affects circular interpolation segments. This value should be specified in the indices for which type is Circular.
-
double timeMilliseconds[constants::maxPathInterpolateAppendPoints]
The pause time for pause segments, in units of milliseconds. This value only affects pause segments. This value should be specified in the indices for which type is Pause.
-
char enableAutoSmooth
0: Disable auto smoothing, 1: Enable auto smoothing. If enabled, circular interpolations will automatically be inserted between two consecutive linear interpolations to smooth out the transition and prevent the interpolating axes from changing the velocity suddenly.
-
double autoSmoothRadius[constants::maxPathInterpolateAppendPoints]
The distance along the linear interpolation to replace with a circular interpolation if enableAutoSmooth is set to enabled. If either linear interpolation is shorter than this value, this value will be reduced to equal the shorter of the two linear interpolations.
-
char enableConstProfile
If set to 0, a separate profile will be calculated for each interpolation segment. If set to 1, only one profile will be calculated for the entire path (only the first index of the profile array will be used).
-
char setStartPos
0: The start positions of the axes are set to the command positions of the axes at the time the simulation is started; 1: The start positions of the axes are set to the values in startPos.
-
double startPos[constants::max3DPathInterpolateDimensions]
If setStartPos is 1, the start positions of the axes of the simulated path interpolation command are set to these values.
-
SimulatePathIntpl3DCommand()
-
class SimulatePathIntplCommand
This class contains data for simulating a path interpolation motion command.
Public Functions
-
SimulatePathIntplCommand()
Public Members
-
int axis[constants::maxPathInterpolateDimensions]
The axes of the simulation.
-
Profile profile[constants::maxPathInterpolateAppendPoints]
The profile of the simulation for each segment.
-
unsigned int numPoints
The number of segments in the path interpolation.
-
PathIntplSegmentType::T type[constants::maxPathInterpolateAppendPoints]
The segment types of the segments in the path interpolation.
-
char direction[constants::maxPathInterpolateAppendPoints]
For circular interpolation segments, 1 for counterclockwise and -1 for clockwise motion. This value only affects circular interpolation segments. This value should be specified in the indices for which type is Circular.
-
double target[constants::maxPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
The target positions for each segment.
-
double centerPos[constants::maxPathInterpolateDimensions][constants::maxPathInterpolateAppendPoints]
The center positions for circular interpolation segments.
-
double timeMilliseconds[constants::maxPathInterpolateAppendPoints]
The pause time for pause segments, in units of milliseconds. This value only affects pause segments. This value should be specified in the indices for which type is Pause.
-
char enableAutoSmooth
0: Disable auto smoothing, 1: Enable auto smoothing. If enabled, circular interpolations will automatically be inserted between two consecutive linear interpolations to smooth out the transition and prevent either axis from changing the velocity suddenly.
-
double autoSmoothRadius[constants::maxPathInterpolateAppendPoints]
The distance along the linear interpolation to replace with a circular interpolation if enableAutoSmooth is set to enabled. If either linear interpolation is shorter than this value, this value will be reduced to equal the shorter of the two linear interpolations.
-
char enableConstProfile
If set to 0, a separate profile will be calculated for each interpolation segment. If set to 1, only one profile will be calculated for the entire path (only the first index of the profile array will be used).
-
char setStartPos
0: The start positions of the axes are set to the command positions of the axes at the time the simulation is started; 1: The start positions of the axes are set to the values in startPos.
-
double startPos[constants::maxPathInterpolateDimensions]
If setStartPos is 1, the start positions of the axes of the simulated path interpolation command are set to these values.
-
SimulatePathIntplCommand()
-
class SplinePoint
This class contains data for a spline point.
Public Functions
-
SplinePoint()
Public Members
-
double pos[constants::maxSplineDimensions]
The positions of the axes at this point.
-
SplinePoint()
-
class TotalTimeSplineCommand
This class contains data for a spline command in which the total time is specified.
Public Functions
-
TotalTimeSplineCommand()
Public Members
-
unsigned int dimensionCount
The number of axes in the spline. This value must be between 1 and maxSplineDimensions.
-
int axis[constants::maxSplineDimensions]
The axes of the spline motion command. The axes are specified in the first dimensionCount indices.
-
double totalTimeMilliseconds
The total time to complete the spline in, in units of milliseconds.
-
unsigned char ignoreDimensionForDistanceCalc[constants::maxSplineDimensions]
This value can be set to 1 to ignore particular axes when calculating the distances between points. The distance between points is used to calculate the time at which that point is traversed, with longer distances receiving a proportionally longer amount of time to traverse. This parameter allows axes which should not be considered for this distance calculation (for example, rotary axes) to be ignored.
-
TotalTimeSplineCommand()
-
class TwoLinkLinearCommand
This class contains data for a two link motion command for a linear axis.
Public Functions
-
TwoLinkLinearCommand()
Public Members
-
int axis
The slave/linear axis to command.
-
double target
The target position to move the slave/linear axis to. If the specifyTargetInRotaryCoordinates parameter is set to 1, this is the target position to move the master/rotary axis to (the slave axis will follow the master axis).
-
Profile masterProfile
The profile of the master/rotary axis. The motion of the master axis will follow these profile parameters.
-
double L1
The length of the first link, in the user units of the slave/linear axis.
-
double L2
The length of the second link, in the user units of slave/linear axis.
-
double Lzero
The position along the linear axis where the rotary axis is located.
-
int Lpolarity
The polarity of the linear axis (0 or 1 for normal, -1 for reverse).
-
double Rspan
The number of units in one rotation of the rotary axis.
-
double Rzero
The position of the rotary axis when the first and second links are outstretched and the linear axis position is farthest away from the rotary axis.
-
unsigned char specifyTargetInRotaryCoordinates
If set to 1, the target position is specified for the master/rotary axis instead of the slave/linear axis.
-
TwoLinkLinearCommand()
-
class TwoLinkRotaryCommand
This class contains data for a two link motion command for a rotary axis.
Public Functions
-
TwoLinkRotaryCommand()
Public Members
-
int axis
The slave/rotary axis to command.
-
double target
The target position to move the slave/rotary axis to. If the specifyTargetInLinearCoordinates parameter is set to 1, this is the target position to move the master/linear axis to (the slave axis will follow the master axis).
-
Profile masterProfile
The profile of master/linear axis. The motion of the master axis will follow these profile parameters.
-
double L1
The length of the first link, in the units of the master/linear axis.
-
double L2
The length of the second link, in the units of the master/linear axis.
-
double Lzero
The position along the linear axis where the rotary axis is located.
-
int Lpolarity
The polarity of the linear axis (0 or 1 for normal, -1 for reverse).
-
double Rzero
The position of the rotary axis when the first and second links are outstretched and the linear axis position is farthest away from the rotary axis.
-
unsigned char specifyTargetInLinearCoordinates
If set to 1, the target position is specified for the master/linear axis instead of the slave/rotary axis.
-
TwoLinkRotaryCommand()
-
class VelAccLimitedSplineCommand
This class contains data for a spline command in which the spline is traversed while staying within the specified velocity and acceleration limits for each axis.
Public Functions
-
VelAccLimitedSplineCommand()
Public Members
-
unsigned int dimensionCount
The number of axes in the spline. This value must be between 1 and maxSplineDimensions.
-
int axis[constants::maxSplineDimensions]
The axes of the spline motion command. The axes are specified in the first dimensionCount indices.
-
double velLimit[constants::maxSplineDimensions]
The velocity limit for the axis specified in the same index. The units are in user units per second. If 0 is specified, that axis is considered to have no velocity limit.
-
double accLimit[constants::maxSplineDimensions]
The acceleration limit for the axis specified in the same index. The units are in user units per second^2. If 0 is specified, that axis is considered to have no acceleration limit.
-
double compositeVel
The velocity to travel along the spline, in user units per second. This velocity will be used to traverse the spline while none of the axes reach the axis velocity and acceleration limits.
-
double compositeAcc
The acceleration to travel along the spline, in user units per second^2. This acceleration will be used to traverse the spline while none of the axes reach the axis velocity and acceleration limits.
-
unsigned char ignoreDimensionForDistanceCalc[constants::maxSplineDimensions]
This value can be set to 1 to ignore particular axes when calculating the distances between points. The distance between points is used to calculate the time at which that point is traversed, with longer distances receiving a proportionally longer amount of time to traverse. This parameter allows axes which should not be considered for this distance calculation (for example, rotary axes) to be ignored.
-
unsigned int sampleMultiplier
If set to 2 or higher, it will increase the number of point samples by that factor. For example, if the number of points is 100 and sampleMultiplier is 5, a total of 500 samples will be taken. This has the effect of reducing fluctuations of the velocity along the spline.
-
unsigned char sampleMultiplierCubicDistribution
If set to 1, the additional samples taken by the SampleMultiplier parameter will follow a cubic distribution, so that more samples are taken near the original points. This option can reduce fluctuations in the velocity while keeping the same number of samples.
-
VelAccLimitedSplineCommand()
-
inline AdvMotion(AdvancedMotion *f)