Class RobotMotionProfile

Class Documentation

class RobotMotionProfile

Structure that defines the motion characteristics and boundary conditions for robot movements.

This class encapsulates all parameters needed to control how the robot moves, including:

  • Motion profile characteristics (velocity, acceleration)

  • Tool motion parameters (linear and rotational)

  • Joint-specific motion limits

  • Motion override factors

The profile parameters are used for both:

  • Continuous Point (CP) Motion: smooth continuous movements following a specified path

  • Point-to-Point (PTP) Motion: joint-space movements from one point to another

Public Members

ProfileType::T profileType

Motion profile type that defines the velocity curve shape.

Currently support motion profile types as below:

  • Trapezoidal: Linear acceleration/deceleration with constant velocity phase

  • S-Curve: Smooth acceleration/deceleration with reduced jerk

double toolLinearVelocity

Linear velocity of the robot’s end effector tool center point (TCP)

Defines the maximum translational speed at which the tool moves through space

Remark

This affects Cartesian motion speed in CP (Continuous Path) movements. An unit of motion speed is millimeters per second [mm/s]

double toolLinearAcceleration

Linear acceleration of the robot’s end effector tool center point (TCP)

Defines how quickly the tool can change its translational velocity

Remark

An unit is millimeters per second squared [mm/s^2]

Note

Higher values mean faster speed changes but may cause more mechanical stress

double toolVelRotRatio

Ratio for calculating the rotational velocity of the end effector.

Used to determine how fast the tool can rotate relative to its linear motion

Remark

Calculation: tool_rotational_velocity[deg/s] = tool_velocity[mm/s] * tool_vel_rot_ratio * (180 / PI)

double jointVelocity[wmx3Api::kinematics::constants::MAX_NUMBER_OF_JOINT]

Array of maximum velocities for each joint motor.

Defines the maximum rotation/translation speed for each robot axis

Remark

An unit is degrees per second [deg/s] for revolute joints, millimeters per second [mm/s] for prismatic joints

double jointAcceleration[wmx3Api::kinematics::constants::MAX_NUMBER_OF_JOINT]

Array of maximum accelerations for each joint motor.

Defines how quickly each joint can change its velocity

Remark

An unit is degrees per second squared [deg/s^2] for revolute joints, millimeters per second squared [mm/s^2] for prismatic joints

Note

Higher accelerations increase mechanical stress and may affect path accuracy

double velOverride

Global velocity override factor.

Scaling factor applied to all velocity parameters to adjust overall motion speed

Remark

A range is 0.0 to 1.0 (0.0% to 100.0% of nominal speed)

double accOverride

Global acceleration override factor.

Scaling factor applied to all acceleration parameters

Remark

A range is 0.0 to 1.0 (0.0% to 100.0% of nominal speed)