Path Following Motion¶
The PathFollowingMotion
class provides an interface for Cartesian-space paths to be accurately followed by the robot end-effector with a constant velocity. There are four different path types that are supported:
The path-following motion is suitable for use cases such as welding, painting, dispensing and deburring, where constant end-effector velocity is required for successful task execution.
Linear Paths¶
First we construct a LinearPath
path type object with a specified start and goal end-effector poses.
start = Frame.from_translation(0.6, 0.3, 0.1)
goal = Frame.from_translation(0.6, -0.3, 0.1)
path_type = LinearPath(start, goal)
auto start = Frame::from_translation(0.6, 0.3, 0.1);
auto goal = Frame::from_translation(0.6, -0.3, 0.1);
auto path_type = std::make_shared<LinearPath>(start, goal);
Then, we construct a PathFollowingMotion
with a unique name, the robot that should execute the motion, a LinearPath
path type, and a desired end-effector velocity.
name = 'constant-velocity-linear-motion'
velocity = 0.8 # [m/s]
motion = PathFollowingMotion(name, robot, path_type, velocity)
auto name = "constant-velocity-linear-motion";
auto velocity = 0.8; // [m/s]
auto motion = PathFollowingMotion(name, robot, path_type, velocity);
Planning this motion will generate a robot trajectory that moves the robot tool with the specified velocity in a linear motion between start
and goal
. If the start and goal poses have different orientations, the followed path is calculated using spherical linear interpolation (SLERP).
If a desired end-effector velocity is not specified, the robot will follow the path with maximum speed that is feasible considering joint position, velocity and acceleration limits.
motion = PathFollowingMotion(name, robot, path_type)
auto motion = PathFollowingMotion(name, robot, path_type);
Note the difference between using the LinearMotion
class and the PathFollowingMotion
class with LinearPath
: LinearMotion
will generate a jerk-constrained trajectory that may not have constant end-effector velocity throughout the motion, but moves to the goal as fast as possible. In contrast, PathFollowingMotion
will follow the exact path with a desired constant velocity, which is useful for applications where a consistent end-effector speed is required. Moreover, trajectories generated by PathFollowingMotion
with LinearPath
can be directly combined with other PathFollowingMotion
trajectories to create complex motion sequences.
Circular Paths¶
First, we construct a CircularPath
object with a specified start pose, rotation angle, circle center, and normal of the plane in which the circular path lies. You can optionally choose to maintain the tool-to-surface orientation. The calculation of the circle radius is implicit through specifying the start pose and the center of the circle.
start = Frame.from_translation(0.6, 0.3, 0.1)
theta = 1.57 # [rad]
center = [0.6, 0.0, 0.1] # [x, y, z]
normal = [0, 0, 1] # vector in world frame, this one specifies the XY plane
path_type = CircularPath(start, theta, center, normal)
auto start = Frame::from_translation(0.6, 0.3, 0.1);
auto theta = 1.57; // [rad]
std::vector<double> center = {0.6, 0.0, 0.1}; // [x, y, z]
std::vector<double> normal = {0, 0, 1}; // vector in world frame, this one specifies the XY plane
auto path_type = std::make_shared<CircularPath>(start, theta, center, normal);
Alternatively, you can construct a CircularPath
with a specified start pose, goal pose, and circle center. The rotation angle and normal of the plane will be computed internally.
start = Frame.from_translation(0.6, 0.3, 0.1)
goal = Frame.from_translation(0.6, -0.3, 0.1)
center = [0.6, 0.0, 0.1]
path_type = CircularPath(start, goal, center)
auto start = Frame::from_translation(0.6, 0.3, 0.1);
auto goal = Frame::from_translation(0.6, -0.3, 0.1);
std::vector<double> center = {0.6, 0.0, 0.1};
auto path_type = std::make_shared<CircularPath>(start, goal, center);
Then, we construct a PathFollowingMotion
with a unique name, the robot that should execute the motion, a CircularPath
path type, and a desired end-effector velocity.
name = 'constant-velocity-circular-motion'
velocity = 0.6 # [m/s]
motion = PathFollowingMotion(name, robot, path_type, velocity)
auto name = "constant-velocity-circular-motion";
auto velocity = 0.6; // [m/s]
auto motion = PathFollowingMotion(name, robot, path_type, velocity);
Planning this motion will generate a robot trajectory that moves the robot tool with the provided velocity along a circular path in the plane specified by the normal vector. Again, if a desired end-effector velocity is not specified, the robot will follow the path at the maximum feasible speed, considering joint position, velocity, and acceleration limits. If keep_tool_to_surface_orientation
is set to True
, the tool’s orientation will be adjusted to maintain alignment with the surface normal.
Blended Paths¶
Blended paths are a combination of linear and circular segments that are smoothly connected. They are useful in cases where a smooth transition between sequential linear segments is required. In order to follow a sequence of linear paths exactly, the robot would have to come to a complete stop at every waypoint, which would make the robot motion slow and look unnatural. Therefore, we add circular blends between the waypoints, which allows the robot to follow a complex path at a constant velocity.
First, we construct a BlendedPath
object with a specified set of Cartesian waypoints and a blend radius. You can optionally choose to maintain the tool-to-surface orientation. The blend radius controls the size of the circular blends between consecutive linear segments, ensuring smooth transitions and motion continuity. Smaller blend radius values lead to more accurate waypoint following, but may be infeasible for the robot to follow with a specified velocity due to kinematic limits.
waypoints = [
Frame.from_translation(0.5, 0.2, 0.1),
Frame.from_translation(0.6, 0.0, 0.1),
Frame.from_translation(0.5, -0.2, 0.1)
]
blend_radius = 0.05 # [m]
path_type = BlendedPath(waypoints, blend_radius)
std::vector<Frame> waypoints = {
Frame::from_translation(0.5, 0.2, 0.1),
Frame::from_translation(0.6, 0.0, 0.1),
Frame::from_translation(0.5, -0.2, 0.1)
};
auto blend_radius = 0.05; // [m]
auto path_type = std::make_shared<BlendedPath>(waypoints, blend_radius);
Alternatively, you can construct a BlendedPath
with a set of waypoints and use the default blend radius. The blend radius will be automatically set to ensure motion continuity between the waypoints.
waypoints = [
Frame.from_translation(0.5, 0.2, 0.1),
Frame.from_translation(0.6, 0.0, 0.1),
Frame.from_translation(0.5, -0.2, 0.1)
]
path_type = BlendedPath(waypoints)
std::vector<Frame> waypoints = {
Frame::from_translation(0.5, 0.2, 0.1),
Frame::from_translation(0.6, 0.0, 0.1),
Frame::from_translation(0.5, -0.2, 0.1)
};
auto path_type = std::make_shared<BlendedPath>(waypoints);
Then, we construct a PathFollowingMotion
with a unique name, the robot that should execute the motion, a BlendedPath
path type, and a desired end-effector velocity.
name = 'constant-velocity-blended-motion'
velocity = 0.7 # [m/s]
motion = PathFollowingMotion(name, robot, path_type, velocity)
auto name = "constant-velocity-blended-motion";
auto velocity = 0.7; // [m/s]
auto motion = PathFollowingMotion(name, robot, path_type, velocity);
Planning this motion will generate a robot trajectory that moves the robot tool with the provided velocity along the specified waypoints. The trajectory will smoothly transition between the linear segments using the specified blend radius, creating a continuous and smooth path. If keep_tool_to_surface_orientation
is set to True
, the tool’s orientation will be adjusted to maintain alignment with the surface normal throughout the motion.
If a desired end-effector velocity is not specified, the robot will follow the path at the maximum feasible speed, considering joint position, velocity, and acceleration limits.
motion = PathFollowingMotion(name, robot, path_type)
trajectory = planner.plan(motion)
auto motion = PathFollowingMotion(name, robot, path_type);
auto trajectory = planner.plan(motion);
Arbitrary Paths¶
We construct a PathFollowingMotion
with a unique name, the robot that should execute the motion, an ArbitraryPath
path type, and a desired end-effector velocity. The ArbitraryPath
object with a specified set of Cartesian waypoints. This path type allows for arbitrary, user-defined waypoints to create a custom path for the motion of the robot tool.
name = 'custom-arbitrary-motion'
velocity = 0.5 # [m/s]
motion = PathFollowingMotion(name, robot, ArbitraryPath(path_waypoints), velocity)
auto name = "custom-arbitrary-motion";
auto velocity = 0.5; // [m/s]
auto motion = PathFollowingMotion(name, robot, std::make_shared<ArbitraryPath>(path_waypoints), velocity);
Planning this motion will generate a robot trajectory that moves the robot tool with the provided velocity along the user-defined waypoints. The arbitrary path allows complete flexibility in defining the robot’s motion trajectory, making it suitable for custom applications where standard paths do not suffice.
In the next tutorial, we will take a look at the LowLevelMotion
class, which provides an interface for very efficient planning suitable for real-time control.