show
Description
show(
plots the position and
orientation bounds of the workspace goal region. The function also displays the reference
frame and end-effector offset frame.goalRegion
)
show(
specifies
the parent axes on which to plot the workspace goal region.goalRegion
,"Parent",axesHandle)
returns the axes
handle that contains the workspace goal region plot using the input arguments from previous
syntaxes.ax
= show(___)
Examples
Plan Path To Workspace Goal Region
Specify a goal region in your workspace and plan a path within those bounds. The workspaceGoalRegion
object defines the bounds on the xyz-position and zyx Euler orientation of the robot end effector. The manipulatorRRT
object plans a path based on that goal region and samples random poses within the bounds.
Load an existing robot model as a rigidBodyTree
object.
robot = loadrobot("kinovaGen3", "DataFormat", "row"); ax = show(robot);
Create Path Planner
Create a rapidly-exploring random tree (RRT) path planner for the robot. This example uses an empty environment, but this workflow also works well with cluttered environments. You can add collision objects to the environment like the collisionBox
or collisionMesh
object.
planner = manipulatorRRT(robot,{});
planner.SkippedSelfCollisions="parent";
Define Goal Region
Create a workspace goal region using the end-effector body name of the robot.
Define the goal region parameters for your workspace. The goal region includes a reference pose, xyz-position bounds, and orientation limits on the zyx Euler angles. This example specifies bounds on the xy-plane in meters and allows rotation about the z-axis in radians.
goalRegion = workspaceGoalRegion(robot.BodyNames{end}); goalRegion.ReferencePose = trvec2tform([0.5 0.5 0.2]); goalRegion.Bounds(1, :) = [-0.2 0.2]; % X Bounds goalRegion.Bounds(2, :) = [-0.2 0.2]; % Y Bounds goalRegion.Bounds(4, :) = [-pi/2 pi/2]; % Rotation about the Z-axis
You can also apply a fixed offset to all poses sampled within the region. This offset can account for grasping tools or variations in dimensions within your workspace. For this example, apply a fixed transformation that places the end effector 5 cm above the workspace.
goalRegion.EndEffectorOffsetPose = trvec2tform([0 0 0.05]);
hold on
show(goalRegion);
Plan Path To Goal Region
Plan a path to the goal region from the robot's home configuration. Due to the randomness in the RRT algorithm, this example sets the rng
seed to ensure repeatable results.
rng(0) path = plan(planner,homeConfiguration(robot),goalRegion);
Show the robot executing the path. To visualize a more realistic path, interpolate points between path configurations.
interpConfigurations = interpolate(planner,path,5); for i = 1:size(interpConfigurations,1) show(robot,interpConfigurations(i,:),"PreservePlot",false); set(ax,'ZLim',[-0.05 0.75],'YLim',[-0.05 1],'XLim',[-0.05 1],... 'CameraViewAngle',5) drawnow end hold off
Adjust End-Effector Pose
Notice that the robot arm approaches the workspace from the bottom. To flip the orientation of the final position, add a pi
rotation to the Y-axis for the reference pose.
goalRegion.EndEffectorOffsetPose = ... goalRegion.EndEffectorOffsetPose*eul2tform([0 pi 0],"ZYX");
Replan the path and visualize the robot motion again. The robot now approaches from the top.
hold on show(goalRegion); path = plan(planner,homeConfiguration(robot),goalRegion); interpConfigurations = interpolate(planner,path,5); for i = 1 : size(interpConfigurations,1) show(robot, interpConfigurations(i, :),"PreservePlot",false); set(ax,'ZLim',[-0.05 0.75],'YLim',[-0.05 1],'XLim',[-0.05 1]) drawnow; end hold off
Input Arguments
goalRegion
— Workspace goal region
workspaceGoalRegion
object
Workspace goal region, specified as a workspaceGoalRegion
object.
Output Arguments
ax
— Axes that contains the workspace goal region
Axes
object
Axes that contains the workspace goal region, returned as an axes
object.
Version History
Introduced in R2021a
See Also
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)