addCapsule
Description
addCapsule(
adds a collision capsule at the next index of the rigid body capapprox
,bodyname
,parameters
,pose
)bodyname
with the specified pose and geometry parameters.
Examples
Create and Modify Capsule Approximation
Load a robot into the workspace and visualize it.
robotIRB = loadrobot("abbIrb120");
show(robotIRB);
Create a capsule approximation of the robot, and visualize the capsule-approximated robot model.
capsIRB = capsuleApproximation(robotIRB); figure show(capsIRB,homeConfiguration(capsIRB.RigidBodyTree));
Use the getCapsules
function to see if the end effector, "tool0"
, has any collision capsules. Because tool0
is just a frame, it has no collision mesh to approximate as a collision capsule.
capsulesTool = getCapsules(capsIRB,"tool0")
capsulesTool = 1x0 empty cell array
Add a capsule to tool0
, at a position 0.15
meters along the x-axis, with a radius of 0.15
and a length of 0
.
addCapsule(capsIRB,"tool0",[0.15 0],trvec2tform([0.15 0 0]))
show(capsIRB,homeConfiguration(capsIRB.RigidBodyTree));
Again check tool0 for a collision capsule, and verify the properties of the detected capsule.
capsulesTool = getCapsules(capsIRB,"tool0")
capsulesTool = 1x1 cell array
{1x1 collisionCapsule}
capsulesTool{1}
ans = collisionCapsule with properties: Radius: 0.1500 Length: 0 Pose: [4x4 double]
Remove the capsule from the base link. Then, reduce the collision capsule size of tool0
, and move it -0.05
meters from the previous position along the x-axis.
removeCapsule(capsIRB,"base_link",1) updatePose(capsIRB,"tool0",trvec2tform([-0.05 0 0]),1) updateGeometry(capsIRB,"tool0",[.1 0.01],1) show(capsIRB,homeConfiguration(capsIRB.RigidBodyTree));
Input Arguments
capapprox
— Capsule approximation of rigid body tree
capsuleApproximation
object
Capsule approximation of a rigid body tree, specified as a
capsuleApproximation
object.
bodyname
— Name of rigid body to add capsule to
string scalar | character vector
Name of the rigid body to add the capsule to, specified as a string scalar or
character vector. The rigid body must exist in the rigidBodyTree
object
of the RigidBodyTree
property of capapprox
.
Example: "EndEffectorTool"
Data Types: char
| string
parameters
— Radius and length of added collision capsule
two-element row vector
Radius and length of the added collision capsule, specified as a two-element row vector of the form [radius length], in meters. The radius is the radius of the spherical ends of the capsule, and the length is the length of the central line segment of the capsule.
Example: [1 2]
pose
— Pose for added collision capsule
4-by-4 matrix
Pose for the added collision capsule, specified as a 4-by-4 homogeneous
transformation matrix defined with respect to the frame of the rigid body
bodyname
.
Example: eye(4)
Extended Capabilities
C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.
Version History
Introduced in R2022b
See Also
Objects
Functions
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 (한국어)