randomConfiguration
Generate random configuration of robot
Description
returns a random configuration of the specified robot. Each joint position in this
configuration respects the joint limits set by the configuration
= randomConfiguration(robot
)PositionLimits
property of the corresponding rigidBodyJoint
object in the robot
model.
Examples
Visualize Robot Configurations
Show different configurations of a robot created using a rigidBodyTree
model. Use the homeConfiguration
or randomConfiguration
functions to generate the structure that defines all the joint positions.
Load a FANUC LR Mate 200ib from the Robotics System Toolbox™ loadrobot
. It is returned as a rigidBodyTree
object.
robot = loadrobot("fanucLRMate200ib");
showdetails(robot)
-------------------- Robot: (9 bodies) Idx Body Name Joint Name Joint Type Parent Name(Idx) Children Name(s) --- --------- ---------- ---------- ---------------- ---------------- 1 base base_link-base fixed base_link(0) 2 link_1 joint_1 revolute base_link(0) link_2(3) 3 link_2 joint_2 revolute link_1(2) link_3(4) 4 link_3 joint_3 revolute link_2(3) link_4(5) 5 link_4 joint_4 revolute link_3(4) link_5(6) 6 link_5 joint_5 revolute link_4(5) link_6(7) 7 link_6 joint_6 revolute link_5(6) flange(8) tool0(9) 8 flange joint_6-flange fixed link_6(7) 9 tool0 link_6-tool0 fixed link_6(7) --------------------
Create a structure for the home configuration of the robot. The structure has joint names and positions for each body on the robot model.
config = homeConfiguration(robot)
config=1×6 struct array with fields:
JointName
JointPosition
Show the home configuration using show
. You do not need to specify a configuration input.
show(robot);
Modify the configuration and set the second joint position to pi/2
. Show the resulting change in the robot configuration.
config(2).JointPosition = pi/2; show(robot,config);
Create random configurations and show them.
show(robot,randomConfiguration(robot));
Input Arguments
robot
— Robot model
rigidBodyTree
object
Robot model, specified as a rigidBodyTree
object.
Output Arguments
configuration
— Robot configuration
vector | structure
Robot configuration, returned as a vector of joint positions or a
structure with joint names and positions for all the bodies in the robot
model. You can generate a configuration using
homeConfiguration(robot)
,
randomConfiguration(robot)
, or by specifying your own
joint positions in a structure. To use the vector form of
configuration
, set the
DataFormat
property for the robot
to either
'row'
or 'column'
.
Extended Capabilities
C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.
Usage notes and limitations:
When creating the rigidBodyTree
object, use the syntax that specifies the
MaxNumBodies
as an upper bound for adding bodies to the robot model.
You must also specify the DataFormat
property as a name-value pair. For
example:
robot = rigidBodyTree("MaxNumBodies",15,"DataFormat","row")
To minimize data usage, limit the upper bound to a number close to the expected number of bodies in the model. All data formats are supported for code generation. To use the dynamics functions, the data format must be set to "row"
or "column"
.
The show
and showdetails
functions do not support code generation.
Version History
Introduced in R2016bR2024a: Static memory allocation support
randomConfiguration
now supports code generation with disabled dynamic memory allocation. For more information about disabling dynamic memory allocation, see Set Dynamic Memory Allocation Threshold (MATLAB Coder).
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 (한국어)