Class TrajectoryMotionParam¶
Defined in File RobotMotionApi.h
Nested Relationships¶
Nested Types¶
Class Documentation¶
-
class TrajectoryMotionParam¶
An extended class that makes it easier to use the coordinate::Trajectory class that defines continuous point (CP) motion.
-
class TrajectoryArcMotionParam : public wmx3Api::TrajectoryMotionParam::TrajectoryBaseMotionParam<TrajectoryArcMotionParam>¶
Motion parameter class for circular and arc Continuous Path (CP) movements.
Defines parameters for generating circular and arc trajectories in Cartesian space. This class provides functionality for:
Circular arc motion generation
Three-point arc definition (start, intermediate, end)
Center point and angle-based arc definition
Tool orientation control during arc motion
Key features:
Multiple arc definition methods (3-point or center-angle)
Constant velocity along the arc
Optional tool orientation interpolation
Support for partial and full circles
Automatic radius calculation and validation
Remark
Arc motions are essential for operations requiring curved paths such as welding curved seams or following contoured surfaces
See also
See also
See also
Warning
Arc motion requires careful definition of points to ensure a valid circular path can be generated
Public Functions
-
TrajectoryArcMotionParam(const RobotMotionProfile &profile, const coordinate::CartesianPose &circularArcTarget)¶
Generate CP arc motion parameter which starts from current position to given target position.
Generate CP arc motion parameter which starts from current position, past the intermediate position, and to the target position.
Remark
Intermediate position is stored in ‘PoseArray’ class.
- Parameters:
profile – [in] Motion profile parameter of the robot
circularArcTarget – [in] Target cartesian position
-
TrajectoryArcMotionParam(const RobotMotionProfile &profile, const coordinate::CartesianPose &circularArcEnd, const double targetRotateAngle, const bool executeRotationMotion = false)¶
Generate CP arc motion parameter with given positions and rotation angle.
Generate CP arc motion parameter which create circular path using current position, and end position, and which determine arc using given rotation angle.
Remark
Intermediate position is stored in ‘PoseArray’ class.
- Parameters:
profile – [in] Motion profile parameter of the robot
circularArcEnd – [in] Virtual target cartesian position to determine the circle
targetRotateAngle – [in] The rotation angle [degree unit]
executeRotationMotion – [in] If true, the end-effector will rotate to the targetRotateAngle at the end of the arc motion.
-
class TrajectoryBSplineMotionParam : public wmx3Api::TrajectoryMotionParam::TrajectoryBaseMotionParam<TrajectoryBSplineMotionParam>¶
Motion parameter class for B-spline Continuous Path (CP) movements.
Defines parameters for generating smooth paths using B-spline interpolation. This class specializes in:
Local control of path shape
Path approximation through control points
Efficient curve computation
Flexible path modification
Key features:
Local path control (changes affect only nearby segments)
Path approximation (may not pass exactly through control points)
Automatic knot vector generation
Efficient computation even with many control points
Distance-based control point filtering
Advantages over C-spline:
Better local control of path shape
More numerically stable
Generally smoother paths
More efficient computation
Remark
B-spline paths are particularly useful for:
Complex path planning
Smooth motion with many control points
Applications requiring local path modification
See also
See also
See also
Public Functions
-
TrajectoryBSplineMotionParam(const RobotMotionProfile &profile)¶
Generate B-Spline motion parameter.
Generate B-Spline motion parameter based on ‘PoseArray’ class.
Remark
The number of points and the array of the points to path through are stored in ‘PoseArray’ class.
- Parameters:
profile – [in] Motion profile parameter of the robot
-
TrajectoryBSplineMotionParam(const RobotMotionProfile &profile, double ignoreDistanceLessThan)¶
Generate B-Spline motion parameter.
Generate B-Spline motion parameter based on ‘PoseArray’ class.
Remark
The number of points and the array of the points to path through are stored in ‘PoseArray’ class.
- Parameters:
profile – [in] Motion profile parameter of the robot
ignoreDistanceLessThan – [in] If the distace between a control point and the next is less than this value, the next is skipped. If the value is less than or equal to 0, the value is not used
-
class TrajectoryCSplineMotionParam : public wmx3Api::TrajectoryMotionParam::TrajectoryBaseMotionParam<TrajectoryCSplineMotionParam>¶
Motion parameter class for C-spline Continuous Path (CP) movements.
Defines parameters for generating smooth curved paths using C-spline interpolation. This class specializes in:
Smooth curve generation through multiple points
Continuous first and second derivatives
Automatic control point handling
Path optimization and smoothing
Key features:
Smooth path interpolation through control points
Automatic tangent calculation at control points
Path simplification with distance-based point filtering
Velocity and acceleration continuity
Support for arbitrary number of control points
Remark
C-spline paths provide smoother motion than linear or circular segments and are ideal for continuous, flowing movements
See also
See also
See also
Warning
The smoothness of the path depends on the spacing and arrangement of control points
Public Functions
-
TrajectoryCSplineMotionParam(const RobotMotionProfile &profile)¶
Generate C-Spline motion parameter.
Generate C-Spline motion parameter based on ‘PoseArray’ class.
Remark
The number of points and the array of the points to path through are stored in ‘PoseArray’ class.
- Parameters:
profile – [in] Motion profile parameter of the robot
-
TrajectoryCSplineMotionParam(const RobotMotionProfile &profile, double ignoreDistanceLessThan)¶
Generate C-Spline motion parameter.
Generate C-Spline motion parameter based on ‘PoseArray’ class.
Remark
The number of points and the array of the points to path through are stored in ‘PoseArray’ class.
- Parameters:
profile – [in] Motion profile parameter of the robot
ignoreDistanceLessThan – [in] If the distace between a control point and the next is less than this value, the next is skipped. If the value is less than or equal to 0, the value is not used
-
class TrajectoryLineMotionParam : public wmx3Api::TrajectoryMotionParam::TrajectoryBaseMotionParam<TrajectoryLineMotionParam>¶
Motion parameter class for linear Continuous Path (CP) movements.
Defines parameters for generating straight-line trajectories in Cartesian space. This class handles:
Linear interpolation between points
Constant velocity motion along straight paths
Tool orientation interpolation
Cartesian space constraints
Key features:
Direct point-to-point linear movements
Constant tool orientation or smooth orientation changes
Support for tool and world coordinate systems
Automatic velocity and acceleration profiling
Path accuracy monitoring and control
Remark
Linear motion provides the most predictable tool path and is commonly used for precise operations like welding or cutting
See also
See also
Public Functions
-
TrajectoryLineMotionParam(const RobotMotionProfile &profile, const coordinate::CartesianPose &destination, const bool isToolCoordinate = false)¶
Generate CP line motion.
Generate CP line motion parameter which starts from current position to given target position.
- Parameters:
profile – [in] Motion profile parameter of the robot
destination – [in] Target cartesian position
isToolCoordinate – [in] If true, the destination is represented by tool coordination
-
class TrajectoryToolJogMotionParam : public wmx3Api::TrajectoryMotionParam::TrajectoryBaseMotionParam<TrajectoryToolJogMotionParam>¶
Motion parameter class for tool jogging in Continuous Path (CP) mode.
Defines parameters for incremental tool movement in Cartesian space. This class provides functionality for:
Manual tool positioning
Incremental Cartesian movements
Tool-centric or world-centric motion
Single-axis movement control
Key features:
Six degrees of freedom control (Tx, Ty, Tz, Rx, Ry, Rz)
Direction control (positive/negative)
Coordinate system selection (tool/world)
Safe incremental movement
Automatic velocity scaling
Common applications:
Fine positioning of end effector
Teaching robot positions
Process path verification
Maintenance and calibration
Remark
Tool jog motion is primarily used in manual operation and teaching modes for precise tool positioning
See also
See also
Public Functions
-
TrajectoryToolJogMotionParam(const RobotMotionProfile &profile, int axisId, char direction, bool isToolCoordinate = false)¶
Generate cartesian jog motion parameter.
Generate cartesian jog motion parameter given directions.
- Parameters:
profile – [in] Motion profile parameter of the robot
axisId – [in] ID of the axis. Tx:0, Ty:1, Tz:2, Rx:3, Ry:4, Rz:5
direction – [in] Direction of the jog motion [ positive(1) or negative(-1)]
isToolCoordinate – [in] if true, the tool coordinate is used
-
class TrajectoryArcMotionParam : public wmx3Api::TrajectoryMotionParam::TrajectoryBaseMotionParam<TrajectoryArcMotionParam>¶