Lula [omni.isaac.lula]¶
Overview¶
The lula module provides a high-level interface to the Lula library, with classes exposing routines for forward and inverse kinematics, sampling-based global planning, and smooth reactive motion generation via RMPflow and geometric fabrics.
Logging¶
-
class
LogLevel
¶ Logging levels, ordered from least to most verbose.
-
FATAL
¶ Logging level for nonrecoverable errors (minimum level, so always enabled).
-
ERROR
¶ Logging level for recoverable errors.
-
WARNING
¶ Logging level for warnings, indicating possible cause for concern.
-
INFO
¶ Logging level for informational messages.
-
VERBOSE
¶ Logging level for highly verbose informational messages.
-
-
set_log_level
(level: lula.LogLevel = LogLevel.ERROR) → None¶ Suppress output for all log messages with associated verbosity higher than log_level.
Rotations and Poses¶
-
class
Rotation3
¶ Representation of a rotation (i.e. element of SO(3)) in 3D.
-
from_scaled_axis
(scaled_axis: numpy.ndarray[float64[3, 1]]) → lula.Rotation3¶ Construct a rotation from a scaled axis, where the magnitude of scaled_axis represents the rotation angle in radians.
-
identity
() → lula.Rotation3¶ Create identity rotation.
-
inverse
(self: lula.Rotation3) → lula.Rotation3¶ Returns the inverse rotation.
-
matrix
(self: lula.Rotation3) → numpy.ndarray[float64[3, 3]]¶ Return matrix representation of the rotation.
-
scaled_axis
(self: lula.Rotation3) → numpy.ndarray[float64[3, 1]]¶ Return scaled axis represetation of the rotation where magnitude of the returned vector represents the rotation angle in radians.
-
w
(self: lula.Rotation3) → float¶ Return w component of the quaternion represention of the rotation.
-
x
(self: lula.Rotation3) → float¶ Return x component of the quaternion represention of the rotation.
-
y
(self: lula.Rotation3) → float¶ Return y component of the quaternion represention of the rotation.
-
z
(self: lula.Rotation3) → float¶ Return z component of the quaternion represention of the rotation.
-
-
class
Pose3
¶ Representation of a pose (i.e. element of SE(3)) in 3D.
-
from_rotation
(rotation: lula::Rotation3) → lula.Pose3¶ Create a pure rotational pose
-
from_translation
(translation: numpy.ndarray[float64[3, 1]]) → lula.Pose3¶ Create a pure translational pose.
-
identity
() → lula.Pose3¶ Create identity pose.
-
inverse
(self: lula.Pose3) → lula.Pose3¶ Return the inverse pose.
-
matrix
(self: lula.Pose3) → numpy.ndarray[float64[4, 4]]¶ Return matrix representation of the pose.
-
property
rotation
¶ Rotation component of pose.
-
property
translation
¶ Translation component of pose.
-
Robot Specification¶
-
class
RobotDescription
¶ Robot description, consisting of geometric and kinematic properties of a robot.
-
c_space_coord_name
(self: lula.RobotDescription, coord_index: int) → str¶ Return the name of a given joint of the robot.
-
default_c_space_configuration
(self: lula.RobotDescription) → numpy.ndarray[float64[m, 1]]¶ Return default joint positions for the robot.
-
kinematics
(self: lula.RobotDescription) → lula.Kinematics¶ Return the robot kinematics.
-
num_c_space_coords
(self: lula.RobotDescription) → int¶ Return the number of actuated joints for the robot.
-
-
load_robot
(robot_description_file: str, robot_urdf: str) → lula.RobotDescription¶ Load a robot description from a YAML file (robot_description_file) and a URDF (robot_urdf).
-
load_robot_from_memory
(robot_description: str, robot_urdf: str) → lula.RobotDescription¶ Load a robot description from the contents of a YAML file (robot_description_file) and the contents of a URDF (robot_urdf).
World Specification¶
-
class
Obstacle
¶ Geometric primitive.
Note
Currently, the CYLINDER obstacle type is internally represented as a capsule (i.e., a cylinder with two hemispherical end caps) extending beyond the nominal HEIGHT. This will be corrected in a future release.
-
class
Attribute
¶ -
HEIGHT
= Attribute.HEIGHT¶
-
RADIUS
= Attribute.RADIUS¶
-
SIDE_LENGTHS
= Attribute.SIDE_LENGTHS¶
-
-
class
AttributeValue
¶
-
set_attribute
(self: lula.Obstacle, attribute: lula::Obstacle::Attribute, value: lula::Obstacle::AttributeValue) → None¶ Set attribute for obstacle
-
type
(self: lula.Obstacle) → lula::Obstacle::Type¶ Return the type of the obstacle.
-
class
-
create_obstacle
(type: lula.Obstacle.Type) → lula.Obstacle¶ Create an obstacle.
-
class
World
¶ Represents a collection of obstacles.
-
class
ObstacleHandle
¶
-
add_obstacle
(self: lula.World, obstacle: lula.Obstacle, pose: Optional[lula.Pose3] = None) → lula::World::ObstacleHandle¶ Add obstacle to the world.
-
add_world_view
(self: lula.World) → lula::WorldView¶ Create a view into the world that can be used for collision checks and distance evaluations.
-
disable_obstacle
(self: lula.World, obstacle: lula::World::ObstacleHandle) → None¶ Disable an obstacle for the purpose of collision checks and distance evaluations.
-
enable_obstacle
(self: lula.World, obstacle: lula::World::ObstacleHandle) → None¶ Enable an obstacle for the purpose of collision checks and distance evaluations.
-
remove_obstacle
(self: lula.World, obstacle: lula::World::ObstacleHandle) → None¶ Permanently remove obstacle, invalidating its handle.
-
set_pose
(self: lula.World, obstacle: lula::World::ObstacleHandle, pose: lula.Pose3) → None¶ Set the pose of the given obstacle.
-
class
-
create_world
() → lula.World¶ Create a new, empty world.
-
class
WorldView
¶ Represents a view of a lula.World.
-
distance_to
(self: lula.WorldView, obstacle: lula.World.ObstacleHandle, point: numpy.ndarray[float64[3, 1]], gradient: Optional[numpy.ndarray[float64[3, 1], flags.writeable]] = None) → float¶ Calculate the distance from point to the obstacle specified by obstacle.
-
distances_to
(self: lula.WorldView, point: numpy.ndarray[float64[3, 1]], compute_distance_gradients: bool = True) → Tuple[List[float], Optional[List[numpy.ndarray[float64[3, 1]]]]]¶ Calculate distances from point to all enabled obstacles.
-
in_collision
(*args, **kwargs)¶ Overloaded function.
in_collision(self: lula.WorldView, center: numpy.ndarray[float64[3, 1]], radius: float) -> bool
Test whether a sphere defined by center and radius is in collision with any enabled obstacles in the world.
in_collision(self: lula.WorldView, obstacle: lula.World.ObstacleHandle, center: numpy.ndarray[float64[3, 1]], radius: float) -> bool
Test whether a sphere defined by center and radius is in collision with the obstacle specified by obstacle.
-
num_enabled_obstacles
(self: lula.WorldView) → int¶ Return the number of enabled obstacles in the current view of the world.
-
update
(self: lula.WorldView) → None¶ Update WorldView such that any changes to the underlying world are reflected in this view.
-
Kinematics¶
-
class
Kinematics
¶ Kinematics interface class.
-
class
Limits
¶ Simple class consisting of upper and lower limits for a given c-space coordinate.
-
property
lower
¶
-
property
upper
¶
-
property
-
base_frame_name
(self: lula.Kinematics) → str¶ Return the name of the base frame of the kinematic structure.
-
c_space_coord_limits
(self: lula.Kinematics, coord_index: int) → lula.Kinematics.Limits¶ Return the limits of a given configuration space coordinate of the kinematic structure.
-
c_space_coord_name
(self: lula.Kinematics, coord_index: int) → str¶ Return the name of a given configuration space coordinate of the kinematic structure.
-
frame_names
(self: lula.Kinematics) → List[str]¶ Return all of the frame names in the kinematic structure.
-
jacobian
(self: lula.Kinematics, cspace_position: numpy.ndarray[float64[m, 1]], frame: str) → numpy.ndarray[float64[6, n]]¶ Return the Jacobian of the origin of the given frame with respect to the base frame (i.e., base_frame_name()) at the given cspace_position.
The returned Jacobian is a 6 x N matrix where N is the c-space dimension (i.e., num_c_space_coords()). Column i of the returned Jacobian corresponds to the derivative of the origin of frame with respect to the ith c-space coordinate in the coordinates of the base frame. For each column, the first three elements correspond to the translational portion, and the last three elements correspond to the rotational portion.
-
num_c_space_coords
(self: lula.Kinematics) → int¶ Return the number of configuration space coordinates for the kinematic structure.
-
orientation
(*args, **kwargs)¶ Overloaded function.
orientation(self: lula.Kinematics, cspace_position: numpy.ndarray[float64[m, 1]], frame: str, reference_frame: str) -> lula::Rotation3
Return the orientation of the given frame with respect to reference_frame at the given cspace_position.
orientation(self: lula.Kinematics, cspace_position: numpy.ndarray[float64[m, 1]], frame: str) -> lula::Rotation3
Return the orientation of the given frame with respect to the base frame (i.e., base_frame_name()) at the given cspace_position.
-
orientation_jacobian
(self: lula.Kinematics, cspace_position: numpy.ndarray[float64[m, 1]], frame: str) → numpy.ndarray[float64[3, n]]¶ Return the Jacobian of the orientation of the given frame with respect to the base frame (i.e., base_frame_name()) at the given cspace_position.
The returned Jacobian is a 3 x N matrix where N is the c-space dimension (i.e., num_c_space_coords()). Column i of the returned Jacobian corresponds to the derivative of the orientation of frame with respect to the ith c-space coordinate in the coordinates of the base frame.
-
pose
(*args, **kwargs)¶ Overloaded function.
pose(self: lula.Kinematics, cspace_position: numpy.ndarray[float64[m, 1]], frame: str, reference_frame: str) -> lula::Pose3
Return the pose of the given frame with respect to reference_frame at the given cspace_position.
pose(self: lula.Kinematics, cspace_position: numpy.ndarray[float64[m, 1]], frame: str) -> lula::Pose3
Return the pose of the given frame with respect to the base frame (i.e., base_frame_name()) at the given cspace_position.
-
position
(*args, **kwargs)¶ Overloaded function.
position(self: lula.Kinematics, cspace_position: numpy.ndarray[float64[m, 1]], frame: str, reference_frame: str) -> numpy.ndarray[float64[3, 1]]
Return the position of the origin of the given frame with respect to reference_frame at the given cspace_position.
position(self: lula.Kinematics, cspace_position: numpy.ndarray[float64[m, 1]], frame: str) -> numpy.ndarray[float64[3, 1]]
Return the position of the origin of the given frame with respect to the base frame (i.e., base_frame_name()) at the given cspace_position.
-
position_jacobian
(self: lula.Kinematics, cspace_position: numpy.ndarray[float64[m, 1]], frame: str) → numpy.ndarray[float64[3, n]]¶ Return the Jacobian of the position of the origin of the given frame with respect to the base frame (i.e., base_frame_name()) at the given cspace_position.
The returned Jacobian is a 3 x N matrix where N is the c-space dimension (i.e., num_c_space_coords()). Column i of the returned Jacobian corresponds to the derivative of the position of the origin of frame with respect to the ith c-space coordinate in the coordinates of the base frame.
-
within_cspace_limits
(self: lula.Kinematics, cspace_position: numpy.ndarray[float64[m, 1]], log_warnings: bool) → bool¶ Determine whether a specified configuration space position is within limits.
-
class
Inverse Kinematics¶
-
class
CyclicCoordDescentIkConfig
¶ Configuration parameters for CCD inverse kinematics solver.
-
property
cspace_seeds
¶ Optional parameter to set the initial c-space configurations for descent.
-
property
descent_termination_delta
¶ Minimal change in c-space coordinates for early descent termination.
-
property
irwin_hall_sampling_order
¶ Sampling distribution for initial c-space positions.
-
property
max_iterations_per_descent
¶ Number of iterations used for each cyclic coordinate descent.
-
property
max_num_descents
¶ Maximum number of c-space positions that will be used as seeds.
-
property
orientation_tolerance
¶ Maximum orientation error (per-axis L2-norm) for a successful IK solution
-
property
orientation_weight
¶ Weight for the relative importance of position error during CCD
-
property
position_tolerance
¶ Maximum position error (L2-norm) for a successful IK solution
-
property
position_weight
¶ Weight for the relative importance of position error during CCD
-
property
sampling_seed
¶ Seed for Irwin-Hall sampling of initial c-space positions
-
property
-
class
CyclicCoordDescentIkResults
¶ Results returned by CCD inverse kinematics solver.
-
property
cspace_position
¶ If success is true, joint configuration corresponding to target_pose.
-
property
num_descents
¶ Number of unique c-sapce positions used for CCD prior to termination.
-
property
position_error
¶ Position error (L2-norm) of returned c-space position
-
property
success
¶ Indicate whether a cspace_position within the tolerances has been found.
-
property
x_axis_orientation_error
¶ X-axis orientation error (L2-norm) of returned c-space position
-
property
y_axis_orientation_error
¶ Y-axis orientation error (L2-norm) of returned c-space position
-
property
z_axis_orientation_error
¶ Z-axis orientation error (L2-norm) of returned c-space position
-
property
-
compute_ik_ccd
(kinematics: lula::Kinematics, target_pose: lula::Pose3, target_frame: str, config: lula.CyclicCoordDescentIkConfig) → lula.CyclicCoordDescentIkResults¶ Attempt to solve inverse kinematics using cyclic coordinate descent.
Motion Planning¶
-
class
MotionPlanner
¶ Interface for planning collision-free paths for robotic manipulators.
-
class
Limit
¶ Simple class consisting of upper and lower limits for a variable.
-
property
lower
¶
-
property
upper
¶
-
property
-
class
ParamValue
¶ Value for a given parameter.
-
class
Results
¶ Results from a path search.
-
property
interpolated_path
¶
-
property
path
¶
-
property
path_found
¶
-
property
-
plan_to_cspace_target
(self: lula.MotionPlanner, q_initial: numpy.ndarray[float64[m, 1]], q_target: numpy.ndarray[float64[m, 1]], generate_interpolated_path: bool = False) → lula::MotionPlanner::Results¶ Attempt to find path to configuration space target
-
plan_to_task_space_target
(self: lula.MotionPlanner, q_initial: numpy.ndarray[float64[m, 1]], x_target: numpy.ndarray[float64[3, 1]], generate_interpolated_path: bool = False) → lula::MotionPlanner::Results¶ Attempt to find path to task space target
-
set_param
(*args, **kwargs)¶ Overloaded function.
set_param(self: lula.MotionPlanner, param_name: str, value: numpy.ndarray[float64[3, 1]]) -> bool
Set parameter for motion planner.
set_param(self: lula.MotionPlanner, param_name: str, value: List[float]) -> bool
Set parameter for motion planner.
set_param(self: lula.MotionPlanner, param_name: str, value: List[lula::MotionPlanner::Limit]) -> bool
Set parameter for motion planner.
set_param(self: lula.MotionPlanner, param_name: str, value: lula::MotionPlanner::ParamValue) -> bool
Set parameter for motion planner.
-
update_world_view
(self: lula.MotionPlanner) → None¶ Update the internal WorldView to latest state of its underlying World.
-
class
-
create_motion_planner
(*args, **kwargs)¶ Overloaded function.
create_motion_planner(planning_config_file: str, robot_description: lula::RobotDescription, world_view: lula::WorldView) -> lula.MotionPlanner
Create an MotionPlanner interface from configuration parameters, robot description and world view.
create_motion_planner(robot_description: lula::RobotDescription, world_view: lula::WorldView) -> lula.MotionPlanner
Create an MotionPlanner interface from robot description and world view, using default configuration parameters.
RMPflow¶
-
class
RmpFlowConfig
¶ RMPflow configuration, including parameters and robot description.
-
get_all_params
(self: lula.RmpFlowConfig, names: List[str], values: List[float]) → None¶ Get the names and values of all parameters.
The two lists will be overwritten if not empty.
- Parameters
names (List[str]) – List of all parameter names.
values (List[float]) – Values of all parameters, in same order as names.
- Returns
None
-
get_param
(self: lula.RmpFlowConfig, param_name: str) → float¶ Get the value of an RMPflow parameter.
- Parameters
param_name (str) – Fully-qualified parameter name of the form <rmp_name>/<parameter_name>.
- Returns
Current value of the parameter.
- Return type
float
-
set_all_params
(self: lula.RmpFlowConfig, names: List[str], values: List[float]) → None¶ Set all parameters at once.
The lists names and values must have the same size. The parameter corresponding to names[i] will be set to the value given by values[i].
- Parameters
names (List[str]) – List of all parameter names.
values (List[float]) – Desired values for all parameters, in same order as names.
- Returns
None
-
set_param
(self: lula.RmpFlowConfig, param_name: str, value: float) → None¶ Set the value of an RMPflow parameter.
- Parameters
param_name (str) – Fully-qualified parameter name of the form <rmp_name>/<parameter_name>.
value (float) – New value for the parameter.
- Returns
None
-
set_world_view
(self: lula.RmpFlowConfig, world_view: lula::WorldView) → None¶ Set the world view that will be used for obstacle avoidance.
All enabled obstacles in world_view will be avoided by the RMPflow policy.
- Parameters
world_view (lula.WorldView) – Input world view.
- Returns
None
-
-
create_rmpflow_config
(rmpflow_config_file: str, robot_description: lula::RobotDescription, end_effector_frame: str, world_view: lula::WorldView) → lula.RmpFlowConfig¶ Create an RMPflow configuration object.
This function loads a set of RMPflow parameters from a file and combines them with a robot description to create a configuration object for consumption by lula.create_rmpflow().
- Parameters
rmpflow_config_file (str) – Path to RMPflow configuration file.
robot_description (lula.RobotDescription) – RobotDescription object, e.g. created by lula.load_robot().
end_effector_frame (str) – This control frame name must correspond to a link name as specified in the original URDF used to create the robot description.
world_view (lula.WorldView) – World view that will be used for obstacle avoidance.
- Returns
RMPflow motion policy interface object.
- Return type
-
create_rmpflow_config_from_memory
(rmpflow_config: str, robot_description: lula::RobotDescription, end_effector_frame: str, world_view: lula::WorldView) → lula.RmpFlowConfig¶ - Parameters
rmpflow_config (str) – RMPflow configuration as a single string (unparsed YAML).
robot_description (lula.RobotDescription) – RobotDescription object, e.g. created by lula.load_robot().
end_effector_frame (str) – This control frame name must correspond to a link name as specified in the original URDF used to create the robot description.
world_view (lula.WorldView) – World view that will be used for obstacle avoidance.
- Returns
RMPflow motion policy interface object.
- Return type
-
class
RmpFlow
¶ Interface for building and evaluating an RMPflow motion policy.
-
clear_end_effector_orientation_attractor
(self: lula.RmpFlow) → None¶ Clear end-effector orientation attractor.
-
clear_end_effector_position_attractor
(self: lula.RmpFlow) → None¶ Clear end-effector position attractor.
-
collision_sphere_positions
(self: lula.RmpFlow, cspace_position: numpy.ndarray[float64[m, 1]]) → List[numpy.ndarray[float64[3, 1]]]¶ Compute positions of all collision spheres on the robot at the specified cspace_position
-
collision_sphere_radii
(self: lula.RmpFlow) → List[float]¶ Return the radii of each collision sphere on the robot.
-
distance_to_obstacle
(self: lula.RmpFlow, obstacle: lula::World::ObstacleHandle, collision_sphere_index: int, cspace_position: numpy.ndarray[float64[m, 1]]) → float¶ Compute the distance between a given obstacle and collision sphere for the provided position in configuration space.
-
eval_accel
(self: lula.RmpFlow, cspace_position: numpy.ndarray[float64[m, 1]], cspace_velocity: numpy.ndarray[float64[m, 1]], cspace_accel: numpy.ndarray[float64[m, 1], flags.writeable]) → None¶ Compute configuration-space acceleration from motion policy, given input state.
-
in_collision_with_obstacle
(self: lula.RmpFlow, cspace_position: numpy.ndarray[float64[m, 1]]) → bool¶ Determine whether a specified joint configuration puts the robot into collision with an obstacle.
-
num_collision_spheres
(self: lula.RmpFlow) → int¶ Return the number of collision spheres in the robot representation.
-
set_cspace_attractor
(self: lula.RmpFlow, cspace_position: numpy.ndarray[float64[m, 1]]) → None¶ Set an attractor in generalized coordinates (configuration space).
-
set_cspace_target
(self: lula.RmpFlow, cspace_target: numpy.ndarray[float64[m, 1]]) → None¶ Set a target in generalized coordinates (configuration space).
Warning
This function is part of a legacy interface for setting targets that is deprecated and slated for removal in a future release. It is recommended that this function not be used.
-
set_end_effector_orientation_attractor
(self: lula.RmpFlow, orientation: lula::Rotation3) → None¶ Set an end-effector orientation attractor.
-
set_end_effector_position_attractor
(self: lula.RmpFlow, position: numpy.ndarray[float64[3, 1]]) → None¶ Set an end-effector position attractor.
-
set_end_effector_target
(self: lula.RmpFlow, position: Optional[numpy.ndarray[float64[3, 1]]]=None, orientation: Optional[lula::Rotation3]=None, default_cspace_config: Optional[numpy.ndarray[float64[m, 1]]]=None) → None¶ Set an end-effector target pose, along with a default configuration for the robot.
Warning
This function is part of a legacy interface for setting targets that is deprecated and slated for removal in a future release. It is recommended that this function not be used.
-
update_end_effector_target
(self: lula.RmpFlow, position: Optional[numpy.ndarray[float64[3, 1]]]=None, orientation: Optional[lula::Rotation3]=None, default_cspace_config: Optional[numpy.ndarray[float64[m, 1]]]=None) → None¶ Update end-effector target pose and default configuration.
Warning
This function is part of a legacy interface for setting targets that is deprecated and slated for removal in a future release. It is recommended that this function not be used.
-
update_world_view
(self: lula.RmpFlow) → None¶ Update the internal WorldView to latest state of its underlying World.
-
-
create_rmpflow
(config: lula.RmpFlowConfig) → lula.RmpFlow¶ Create an instance of the RmpFlow interface from an RMPflow configuration.
Geometric Fabrics¶
Note
Lula’s support for motion policies based on geometric fabrics is under active development and will be exposed in a future release.