Python API#

Logging#

class cumotion.LogLevel#

Logging levels, ordered from least to most verbose.

Members:

FATAL

ERROR

WARNING

INFO

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.

cumotion.set_log_level(level: cumotion.LogLevel = <LogLevel.ERROR: 1>) None#

Suppress output for all log messages with associated verbosity higher than log_level.

cumotion.set_default_logger_text_style(
log_level: cumotion.LogLevel,
style: str,
) None#

Set color/style used by the default logger for messages of a given log_level. The style string may contain one or more ANSI control sequences (e.g., enabling fatal error messages to be rendered in bold with a red foreground color).

cumotion.set_default_logger_prefix(prefix: str) None#

Set prefix used by the default logger for all messages. The prefix string is logged after the style string set for each log_level by set_default_logger_text_style() and prior to the content of the logged message. The default prefix is an empty string.

Rotations and Poses#

class cumotion.Rotation3#

Representation of a rotation (i.e. element of SO(3)) in 3D.

static distance(
rotation0: cumotion.Rotation3,
rotation1: cumotion.Rotation3,
) float#

Compute the minimum angular distance (in radians) between two rotations.

static from_axis_angle(
axis: numpy.ndarray[numpy.float64[3, 1]],
angle: float,
skip_normalization: bool = False,
) cumotion.Rotation3#

Return a rotation that rotates by an angle (in radians) around a given axis.

static from_matrix(
rotation_matrix: numpy.ndarray[numpy.float64[3, 3]],
skip_normalization: bool = False,
) cumotion.Rotation3#

Return a rotation converted from a 3 x 3 rotation matrix.

static from_scaled_axis(
scaled_axis: numpy.ndarray[numpy.float64[3, 1]],
) cumotion.Rotation3#

Return a rotation converted from a scaled axis.

static identity() cumotion.Rotation3#

Create identity rotation.

inverse(self: cumotion.Rotation3) cumotion.Rotation3#

Returns the inverse rotation.

matrix(
self: cumotion.Rotation3,
) numpy.ndarray[numpy.float64[3, 3]]#

Return matrix representation of the rotation.

scaled_axis(
self: cumotion.Rotation3,
) numpy.ndarray[numpy.float64[3, 1]]#

Return scaled axis representation of the rotation where magnitude of the returned vector represents the rotation angle in radians.

static slerp(
rotation0: cumotion.Rotation3,
rotation1: cumotion.Rotation3,
t: float,
) cumotion.Rotation3#

Smoothly interpolate between two rotations using spherical linear interpolation (“slerp”).

w(self: cumotion.Rotation3) float#

Return w component of the quaternion representation of the rotation.

x(self: cumotion.Rotation3) float#

Return x component of the quaternion representation of the rotation.

y(self: cumotion.Rotation3) float#

Return y component of the quaternion representation of the rotation.

z(self: cumotion.Rotation3) float#

Return z component of the quaternion representation of the rotation.

class cumotion.Pose3#

Representation of a pose (i.e. element of SE(3)) in 3D.

static from_rotation(rotation: cumotion::Rotation3) cumotion.Pose3#

Create a pure rotational pose

static from_translation(
translation: numpy.ndarray[numpy.float64[3, 1]],
) cumotion.Pose3#

Create a pure translational pose.

static identity() cumotion.Pose3#

Create identity pose.

inverse(self: cumotion.Pose3) cumotion.Pose3#

Return the inverse pose.

matrix(
self: cumotion.Pose3,
) numpy.ndarray[numpy.float64[4, 4]]#

Return matrix representation of the pose.

property rotation#

Rotation component of pose.

property translation#

Translation component of pose.

Robot Specification#

class cumotion.RobotDescription#

Robot description, consisting of geometric and kinematic properties of a robot.

cspace_coord_name(
self: cumotion.RobotDescription,
coord_index: int,
) str#

Return the name of a given joint of the robot.

default_cspace_configuration(
self: cumotion.RobotDescription,
) numpy.ndarray[numpy.float64[m, 1]]#

Return default joint positions for the robot.

kinematics(
self: cumotion.RobotDescription,
) cumotion.Kinematics#

Return the robot kinematics.

num_cspace_coords(
self: cumotion.RobotDescription,
) int#

Return the number of actuated joints for the robot.

tool_frame_names(
self: cumotion.RobotDescription,
) List[str]#

Return the names of all tool frames (if any) specified in the robot description.

cumotion.load_robot_from_file(
robot_xrdf: os.PathLike,
robot_urdf: os.PathLike,
) cumotion.RobotDescription#

Load a robot description from an XRDF (robot_xrdf) and a URDF (robot_urdf).

cumotion.load_robot_from_memory(
robot_xrdf: str,
robot_urdf: str,
) cumotion.RobotDescription#

Load a robot description from the contents of an XRDF (robot_xrdf) and the contents of a URDF (robot_urdf).

World Specification#

class cumotion.Obstacle#

Geometric primitive.

class Attribute#

Members:

HEIGHT

RADIUS

SIDE_LENGTHS

GRID

GRID = <Attribute.GRID: 3>#
HEIGHT = <Attribute.HEIGHT: 0>#
RADIUS = <Attribute.RADIUS: 1>#
SIDE_LENGTHS = <Attribute.SIDE_LENGTHS: 2>#
property name#
property value#
class AttributeValue#
class Grid#
class GridPrecision#

Members:

HALF

FLOAT

DOUBLE

DOUBLE = <GridPrecision.DOUBLE: 8>#
FLOAT = <GridPrecision.FLOAT: 4>#
HALF = <GridPrecision.HALF: 2>#
property name#
property value#
class Type#

Members:

CUBOID

CAPSULE

SPHERE

SDF

CAPSULE = <Type.CAPSULE: 0>#
CUBOID = <Type.CUBOID: 1>#
SDF = <Type.SDF: 3>#
SPHERE = <Type.SPHERE: 2>#
property name#
property value#
set_attribute(
self: cumotion.Obstacle,
attribute: cumotion::Obstacle::Attribute,
value: cumotion::Obstacle::AttributeValue,
) None#

Set attribute for obstacle

type(self: cumotion.Obstacle) cumotion::Obstacle::Type#

Return the type of the obstacle.

cumotion.create_obstacle(type: cumotion.Obstacle.Type) cumotion.Obstacle#

Create an obstacle.

class cumotion.World#

Represents a collection of obstacles.

class ObstacleHandle#
add_obstacle(
self: cumotion.World,
obstacle: cumotion.Obstacle,
pose: cumotion.Pose3 | None = None,
) cumotion::World::ObstacleHandle#

Add obstacle to the world.

add_world_view(
self: cumotion.World,
) cumotion::WorldViewHandle#

Create a view into the world that can be used for collision checks and distance evaluations.

disable_obstacle(
self: cumotion.World,
obstacle: cumotion::World::ObstacleHandle,
) None#

Disable an obstacle for the purpose of collision checks and distance evaluations.

enable_obstacle(
self: cumotion.World,
obstacle: cumotion::World::ObstacleHandle,
) None#

Enable an obstacle for the purpose of collision checks and distance evaluations.

remove_obstacle(
self: cumotion.World,
obstacle: cumotion::World::ObstacleHandle,
) None#

Permanently remove obstacle, invalidating its handle.

set_pose(
self: cumotion.World,
obstacle: cumotion::World::ObstacleHandle,
pose: cumotion.Pose3,
) None#

Set the pose of the given obstacle.

set_sdf_grid_values_from_host(*args, **kwargs)#

Overloaded function.

  1. set_sdf_grid_values_from_host(self: cumotion.World, obstacle: cumotion::World::ObstacleHandle, values: numpy.ndarray[numpy.float64]) -> None

Set the grid values for an obstacle of type SDF using a 3-dimensional host-resident values buffer of type double, stored with the z coordinate varying fastest (numpy default).

  1. set_sdf_grid_values_from_host(self: cumotion.World, obstacle: cumotion::World::ObstacleHandle, values: numpy.ndarray[numpy.float32]) -> None

Set the grid values for an obstacle of type SDF using a 3-dimensional host-resident values buffer of type float, stored with the z coordinate varying fastest (numpy default).

cumotion.create_world() cumotion.World#

Create a new, empty world.

class cumotion.WorldViewHandle#

Handle to a view (snapshot) of a cumotion.World.

update(self: cumotion.WorldViewHandle) None#

Update world view such that any changes to the underlying world are reflected in this view.

class cumotion.WorldInspector#

Interface for querying properties and spatial relationships within a world.

distance_to(
self: cumotion.WorldInspector,
obstacle: cumotion.World.ObstacleHandle,
point: numpy.ndarray[numpy.float64[3, 1]],
gradient: numpy.ndarray[numpy.float64[3, 1], flags.writeable] | None = None,
) float#

Compute the distance from point to the obstacle specified by obstacle.

distances_to(
self: cumotion.WorldInspector,
point: numpy.ndarray[numpy.float64[3, 1]],
compute_distance_gradients: bool = True,
) Tuple[List[float], List[numpy.ndarray[numpy.float64[3, 1]]] | None]#

Compute distances from point to all enabled obstacles.

in_collision(*args, **kwargs)#

Overloaded function.

  1. in_collision(self: cumotion.WorldInspector, center: numpy.ndarray[numpy.float64[3, 1]], radius: float) -> bool

Test whether a sphere defined by center and radius is in collision with any enabled obstacle in the world.

  1. in_collision(self: cumotion.WorldInspector, obstacle: cumotion.World.ObstacleHandle, center: numpy.ndarray[numpy.float64[3, 1]], radius: float) -> bool

Test whether a sphere defined by center and radius is in collision with the obstacle specified by obstacle.

min_distance(
self: cumotion.WorldInspector,
point: numpy.ndarray[numpy.float64[3, 1]],
gradient: numpy.ndarray[numpy.float64[3, 1], flags.writeable] | None = None,
) float#

Compute the minimum distance from point to ANY enabled obstacles in the current view of the world.

num_enabled_obstacles(
self: cumotion.WorldInspector,
) int#

Return the number of enabled obstacles in the current view of the world.

cumotion.create_world_inspector(
world_view: cumotion.WorldViewHandle,
) cumotion.WorldInspector#

Create a WorldInspector for a given world_view.

class cumotion.RobotWorldInspector#

Interface for querying spatial relationships between a robot and a world.

clear_world_view(
self: cumotion.RobotWorldInspector,
) None#

Clear the existing world view from RobotWorldInspector.

distance_to_obstacle(self: cumotion.RobotWorldInspector, obstacle: cumotion::World::ObstacleHandle, world_collision_sphere_index: int, cspace_position: numpy.ndarray[numpy.float64[m, 1]]) float#

Compute the distance between a given obstacle and collision sphere for the provided position in configuration space. If the collision sphere intersects the obstacle, a distance of zero is returned.

frames_in_self_collision(
self: cumotion.RobotWorldInspector,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
) List[Tuple[str, str]]#

Return pairs of frames for which self-collision occurs at the given cspace_position. Each pair of self-collision frames will be returned once in arbitrary order (e.g., the pair {“linkA”, “linkB”} may be returned OR the pair {“linkB”, “linkA”} may be returned, but not both.

in_collision_with_obstacle(
self: cumotion.RobotWorldInspector,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
) bool#

Determine whether a specified joint configuration puts the robot into collision with an obstacle.

in_self_collision(
self: cumotion.RobotWorldInspector,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
) bool#

Indicate whether the robot is in self-collision at the given cspace_position. The robot is considered to be in self-collision if any collision sphere on any frame intersects a collision sphere from another frame for which collisions have not been masked.

min_distance_to_obstacle(
self: cumotion.RobotWorldInspector,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
) float#

Compute the minimum pair-wise signed distance between the set of robot spheres and the set of obstacles for the provided position in configuration space. A positive distance implies that the obstacle and the robot are NOT in collision. NOTE: A distance of zero implies that the closest robot sphere to any obstacle intersects the obstacle at a point.

num_self_collision_spheres(
self: cumotion.RobotWorldInspector,
) int#

Return the number of self-collision spheres in the robot representation.

num_world_collision_spheres(
self: cumotion.RobotWorldInspector,
) int#

Return the number of world-collision spheres in the robot representation.

self_collision_sphere_frame_name(
self: cumotion.RobotWorldInspector,
self_collision_sphere_index: int,
) str#

Return the name of the frame associated with the self-collision sphere corresponding to self_collision_sphere_index

self_collision_sphere_positions(
self: cumotion.RobotWorldInspector,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
) List[numpy.ndarray[numpy.float64[3, 1]]]#

Compute positions of all self-collision spheres on the robot at the specified cspace_position

self_collision_sphere_radii(
self: cumotion.RobotWorldInspector,
) List[float]#

Return the radii of each self-collision sphere on the robot.

set_world_view(
self: cumotion.RobotWorldInspector,
world_view: cumotion::WorldViewHandle,
) None#

Set the internal world view used by RobotWorldInspector.

world_collision_sphere_frame_name(
self: cumotion.RobotWorldInspector,
world_collision_sphere_index: int,
) str#

Return the name of the frame associated with the world-collision sphere corresponding to world_collision_sphere_index

world_collision_sphere_positions(
self: cumotion.RobotWorldInspector,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
) List[numpy.ndarray[numpy.float64[3, 1]]]#

Compute positions of all world-collision spheres on the robot at the specified cspace_position

world_collision_sphere_radii(
self: cumotion.RobotWorldInspector,
) List[float]#

Return the radii of each world-collision sphere on the robot.

cumotion.create_robot_world_inspector(
robot_description: cumotion.RobotDescription,
world_view: Optional[cumotion::WorldViewHandle] = None,
) cumotion.RobotWorldInspector#

Create a RobotWorldInspector for a given robot_description and world_view.

Kinematics#

class cumotion.Kinematics#

Kinematics interface class.

class Limits#

Simple class consisting of upper and lower limits for a given c-space coordinate.

property lower#
property upper#
base_frame_name(self: cumotion.Kinematics) str#

Return the name of the base frame of the kinematic structure.

cspace_coord_acceleration_limit(
self: cumotion.Kinematics,
coord_index: int,
) float#

Return the acceleration limit of a given configuration space coordinate of the kinematic structure.

cspace_coord_jerk_limit(
self: cumotion.Kinematics,
coord_index: int,
) float#

Return the jerk limit of a given configuration space coordinate of the kinematic structure.

cspace_coord_limits(
self: cumotion.Kinematics,
coord_index: int,
) cumotion.Kinematics.Limits#

Return the limits of a given configuration space coordinate of the kinematic structure.

cspace_coord_name(
self: cumotion.Kinematics,
coord_index: int,
) str#

Return the name of a given configuration space coordinate of the kinematic structure.

cspace_coord_velocity_limit(
self: cumotion.Kinematics,
coord_index: int,
) float#

Return the velocity limit of a given configuration space coordinate of the kinematic structure.

frame_names(self: cumotion.Kinematics) List[str]#

Return all of the frame names in the kinematic structure.

jacobian(
self: cumotion.Kinematics,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
frame: str,
) numpy.ndarray[numpy.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_cspace_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_cspace_coords(self: cumotion.Kinematics) int#

Return the number of configuration space coordinates for the kinematic structure.

orientation(*args, **kwargs)#

Overloaded function.

  1. orientation(self: cumotion.Kinematics, cspace_position: numpy.ndarray[numpy.float64[m, 1]], frame: str, reference_frame: str) -> cumotion::Rotation3

Return the orientation of the given frame with respect to reference_frame at the given cspace_position.

  1. orientation(self: cumotion.Kinematics, cspace_position: numpy.ndarray[numpy.float64[m, 1]], frame: str) -> cumotion::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: cumotion.Kinematics,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
frame: str,
) numpy.ndarray[numpy.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_cspace_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.

  1. pose(self: cumotion.Kinematics, cspace_position: numpy.ndarray[numpy.float64[m, 1]], frame: str, reference_frame: str) -> cumotion::Pose3

Return the pose of the given frame with respect to reference_frame at the given cspace_position.

  1. pose(self: cumotion.Kinematics, cspace_position: numpy.ndarray[numpy.float64[m, 1]], frame: str) -> cumotion::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.

  1. position(self: cumotion.Kinematics, cspace_position: numpy.ndarray[numpy.float64[m, 1]], frame: str, reference_frame: str) -> numpy.ndarray[numpy.float64[3, 1]]

Return the position of the origin of the given frame with respect to reference_frame at the given cspace_position.

  1. position(self: cumotion.Kinematics, cspace_position: numpy.ndarray[numpy.float64[m, 1]], frame: str) -> numpy.ndarray[numpy.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: cumotion.Kinematics,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
frame: str,
) numpy.ndarray[numpy.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_cspace_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: cumotion.Kinematics,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
log_warnings: bool,
) bool#

Determine whether a specified configuration space position is within limits.

Inverse Kinematics (Collision-Unaware)#

class cumotion.IkConfig#

Configuration parameters for inverse kinematics solver.

class CSpaceLimitBiasing#

Members:

AUTO

ENABLE

DISABLE

AUTO = <CSpaceLimitBiasing.AUTO: 0>#
DISABLE = <CSpaceLimitBiasing.DISABLE: 2>#
ENABLE = <CSpaceLimitBiasing.ENABLE: 1>#
property name#
property value#
property bfgs_cspace_limit_biasing#

Indicate whether c-space limit avoidance is active for BFGS descent

property bfgs_cspace_limit_biasing_weight#

Relative weight applied to c-space limit error (if active).

property bfgs_cspace_limit_penalty_region#

Region near c-space limits which will induce penalties when c-space limit biasing is active.

property bfgs_gradient_norm_termination#

Minimal change in L2-norm of the error function gradient for early descent termination from BFGS descent.

property bfgs_gradient_norm_termination_coarse_scale_factor#

Ratio between bfgs_gradient_norm_termination for coarse and fine stagesof BFGS descent.

property bfgs_max_iterations#

Number of iterations used for each BFGS descent.

property bfgs_orientation_weight#

Weight for the relative importance of orientation error during BFGS descent.

property bfgs_position_weight#

Weight for the relative importance of position error during BFGS descent.

property ccd_bracket_search_num_uniform_samples#

Number of samples used to identify valid three-point bracket for numerical optimization of c-space updates.

property ccd_descent_termination_delta#

Minimal change in c-space coordinates for early descent termination.

property ccd_max_iterations#

Number of iterations used for each cyclic coordinate descent.

property ccd_orientation_weight#

Weight for the relative importance of orientation error during CCD.

property ccd_position_weight#

Weight for the relative importance of position error during CCD.

property cspace_seeds#

Optional parameter to set the initial c-space configurations for descent.

property irwin_hall_sampling_order#

Sampling distribution for initial c-space positions.

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 position_tolerance#

Maximum position error (L2-norm) for a successful IK solution

property sampling_seed#

Seed for Irwin-Hall sampling of initial c-space positions

class cumotion.IkResults#

Results returned by inverse kinematics solver.

property cspace_position#

If success is true, joint configuration corresponding to target_pose.

property num_descents#

Number of unique c-space 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

cumotion.solve_ik(
kinematics: cumotion::Kinematics,
target_pose: cumotion::Pose3,
target_frame: str,
config: cumotion.IkConfig,
) cumotion.IkResults#

Attempt to solve inverse kinematics.

Collision-Aware Inverse Kinematics#

class cumotion.CollisionFreeIkSolverConfig#

Configuration parameters for a CollisionFreeIkSolver.

class ParamValue#

Specify the value for a given parameter.

set_param(
self: cumotion.CollisionFreeIkSolverConfig,
param_name: str,
value: cumotion.CollisionFreeIkSolverConfig.ParamValue,
) bool#

Set the value of the parameter. Returns True if the param has been successfully updated and False if an error has occurred (e.g., invalid parameter).

class cumotion.CollisionFreeIkSolver#

Interface for using numerical optimization to generate collision-free c-space positions for task-space targets

class OrientationConstraint#

Orientation constraints restrict the orientation of a tool frame.

static axis(
tool_frame_axis: numpy.ndarray[numpy.float64[3, 1]],
world_target_axis: numpy.ndarray[numpy.float64[3, 1]],
axis_deviation_limit: float | None = None,
) cumotion.CollisionFreeIkSolver.OrientationConstraint#

Create an OrientationConstraint such that the tool frame orientation is constrained to rotate about a “free axis”.

static none() cumotion.CollisionFreeIkSolver.OrientationConstraint#

Create an OrientationConstraint such that no tool frame orientation constraints are active.

static target(
orientation_target: cumotion.Rotation3,
deviation_limit: float | None = None,
) cumotion.CollisionFreeIkSolver.OrientationConstraint#

Create an OrientationConstraint such that a tool frame orientation_target is fully specified.

class OrientationConstraintGoalset#

Variant of OrientationConstraint for “goalset” planning.

static axis(
tool_frame_axes: List[numpy.ndarray[numpy.float64[3, 1]]],
world_target_axes: List[numpy.ndarray[numpy.float64[3, 1]]],
axis_deviation_limit: float | None = None,
) cumotion.CollisionFreeIkSolver.OrientationConstraintGoalset#

Create an OrientationConstraintGoalset such that the tool frame orientation is constrained to rotate about a “free axis”.

static none() cumotion.CollisionFreeIkSolver.OrientationConstraintGoalset#

Create an OrientationConstraintGoalset such that no tool frame orientation constraints are active.

static target(
orientation_targets: List[cumotion.Rotation3],
deviation_limit: float | None = None,
) cumotion.CollisionFreeIkSolver.OrientationConstraintGoalset#

Create an OrientationConstraintGoalset such that tool frame orientation_targets are fully specified.

class Results#

Results from an inverse kinematics solve.

class Status#

Members:

SUCCESS

INVERSE_KINEMATICS_FAILURE

INVERSE_KINEMATICS_FAILURE = <Status.INVERSE_KINEMATICS_FAILURE: 1>#
SUCCESS = <Status.SUCCESS: 0>#
property name#
property value#
cspace_positions(
self: cumotion.CollisionFreeIkSolver.Results,
) List[numpy.ndarray[numpy.float64[m, 1]]]#

If status() returns SUCCESS, then cspace_positions() returns unique IK solutions.

status(
self: cumotion.CollisionFreeIkSolver.Results,
) cumotion.CollisionFreeIkSolver.Results.Status#

Return the Status from the inverse kinematics solve.

target_indices(
self: cumotion.CollisionFreeIkSolver.Results,
) List[int]#

Return the indices of the targets selected for each valid c-space position.

class TaskSpaceTarget#

Task-space targets restrict the position and (optionally) orientation of the tool frame.

class TaskSpaceTargetGoalset#

Variant of TaskSpaceTarget for “goalset” planning.

class TranslationConstraint#

Translation constraints restrict the position of the origin of a tool frame.

static target(
translation_target: numpy.ndarray[numpy.float64[3, 1]],
deviation_limit: float | None = None,
) cumotion.CollisionFreeIkSolver.TranslationConstraint#

Create a TranslationConstraint such that the desired position is fully specified as translation_target.

class TranslationConstraintGoalset#

Variant of TranslationConstraint for “goalset” planning.

static target(
translation_targets: List[numpy.ndarray[numpy.float64[3, 1]]],
deviation_limit: float | None = None,
) cumotion.CollisionFreeIkSolver.TranslationConstraintGoalset#

Create a TranslationConstraintGoalset such that translation_targets are fully specified.

solve(
self: cumotion.CollisionFreeIkSolver,
task_space_target: cumotion.CollisionFreeIkSolver.TaskSpaceTarget,
cspace_seeds: List[numpy.ndarray[numpy.float64[m, 1]]] = [],
) cumotion.CollisionFreeIkSolver.Results#

Attempt to find c-space solutions that satisfy the constraints specified in task_space_target.

solve_goalset(
self: cumotion.CollisionFreeIkSolver,
task_space_target_goalset: cumotion.CollisionFreeIkSolver.TaskSpaceTargetGoalset,
cspace_seeds: List[numpy.ndarray[numpy.float64[m, 1]]] = [],
) cumotion.CollisionFreeIkSolver.Results#

Attempt to find c-space solutions that satisfy the constraints specified in task_space_target_goalset.

cumotion.create_collision_free_ik_solver(
config: cumotion.CollisionFreeIkSolverConfig,
) cumotion.CollisionFreeIkSolver#

Create a CollisionFreeIkSolver with the given config.

Trajectory Representation#

class cumotion.Trajectory#

Represent a path through configuration space (i.e., “c-space”) parameterized by time.

class Domain#

Indicates the continuous range of time values, t, for which the trajectory and its derivatives are defined.

property lower#
span(self: cumotion.Trajectory.Domain) float#

Convenience function to return the span of time values included in domain.

property upper#
domain(
self: cumotion.Trajectory,
) cumotion.Trajectory.Domain#

Return the domain for the trajectory.

eval(
self: cumotion.Trajectory,
time: float,
derivative_order: int = 0,
) numpy.ndarray[numpy.float64[m, 1]]#

Evaluate specified trajectory derivative at the given time and return value.

eval_all(
self: cumotion.Trajectory,
arg0: float,
) Tuple[numpy.ndarray[numpy.float64[m, 1]], numpy.ndarray[numpy.float64[m, 1]], numpy.ndarray[numpy.float64[m, 1]], numpy.ndarray[numpy.float64[m, 1]]]#

Evaluate the trajectory at the given time, returning position, velocity, acceleration, and jerk.

max_acceleration_magnitude(
self: cumotion.Trajectory,
) numpy.ndarray[numpy.float64[m, 1]]#

Return the maximum magnitude of acceleration for each c-space coordinate within the defined domain().

max_jerk_magnitude(
self: cumotion.Trajectory,
) numpy.ndarray[numpy.float64[m, 1]]#

Return the maximum magnitude of jerk for each c-space coordinate within the defined domain().

max_position(
self: cumotion.Trajectory,
) numpy.ndarray[numpy.float64[m, 1]]#

Return the maximum position for each c-space coordinate within the defined domain().

max_velocity_magnitude(
self: cumotion.Trajectory,
) numpy.ndarray[numpy.float64[m, 1]]#

Return the maximum magnitude of velocity for each c-space coordinate within the defined domain().

min_position(
self: cumotion.Trajectory,
) numpy.ndarray[numpy.float64[m, 1]]#

Return the minimum position for each c-space coordinate within the defined domain().

num_cspace_coords(self: cumotion.Trajectory) int#

Return the number of configuration space coordinates for the trajectory.

Trajectory Optimization#

class cumotion.TrajectoryOptimizerConfig#

Configuration parameters for a TrajectoryOptimizer.

class ParamValue#

Value for a given parameter.

set_param(
self: cumotion.TrajectoryOptimizerConfig,
param_name: str,
value: cumotion.TrajectoryOptimizerConfig.ParamValue,
) bool#

Set parameter for the trajectory optimizer config.

cumotion.create_trajectory_optimizer_config_from_file(
trajectory_optimizer_config_file: os.PathLike,
robot_description: cumotion.RobotDescription,
tool_frame_name: str,
world_view: cumotion::WorldViewHandle,
) cumotion.TrajectoryOptimizerConfig#

Load a set of TrajectoryOptimizer configuration parameters from file.

cumotion.create_default_trajectory_optimizer_config(
robot_description: cumotion.RobotDescription,
tool_frame_name: str,
world_view: cumotion::WorldViewHandle,
) cumotion.TrajectoryOptimizerConfig#

Use default parameters to create a configuration for trajectory optimization.

class cumotion.TrajectoryOptimizer#

Interface for using numerical optimization to generate collision-free trajectories for a ” robot.

See documentation for corresponding C++ Class.

class CSpaceTarget#

C-space targets fully restrict the c-space configuration at the termination of the trajectory while allowing (optional) task-space constraints along the path.

class OrientationPathConstraint#

Orientation path constraints restrict the orientation of a tool frame along the path.

static axis(
tool_frame_axis: numpy.ndarray[numpy.float64[3, 1]],
world_target_axis: numpy.ndarray[numpy.float64[3, 1]],
path_axis_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.CSpaceTarget.OrientationPathConstraint#

Create an OrientationPathConstraint such that the tool frame orientation is constrained to rotate about a “free axis” along the path.

static constant(
path_deviation_limit: float | None = None,
use_terminal_orientation: bool = True,
) cumotion.TrajectoryOptimizer.CSpaceTarget.OrientationPathConstraint#

Create an OrientationPathConstraint such that the tool frame orientation along the path is constant.

static none() cumotion.TrajectoryOptimizer.CSpaceTarget.OrientationPathConstraint#

Create a OrientationPathConstraint such that the orientation of the tool frame is not restricted along the path.

class TranslationPathConstraint#

Translation path constraints restrict the position of the origin of a tool frame along the path.

static linear(
path_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.CSpaceTarget.TranslationPathConstraint#

Create a TranslationPathConstraint such that a linear translation constraint is active along the path.

static none() cumotion.TrajectoryOptimizer.CSpaceTarget.TranslationPathConstraint#

Create a TranslationPathConstraint such that the position of the tool frame is not restricted along the path.

class OrientationConstraint#

Orientation constraints restrict the orientation of a tool frame.

static constant(
path_deviation_limit: float | None = None,
terminal_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraint#

Create an OrientationConstraint such that the tool frame orientation along the path AND at termination are constrained to the tool frame orientation at the initial c-space position.

static none() cumotion.TrajectoryOptimizer.OrientationConstraint#

Create an OrientationConstraint such that no tool frame orientation constraints are active along the path OR at termination.

static terminal_and_path_axis(
tool_frame_axis: numpy.ndarray[numpy.float64[3, 1]],
world_target_axis: numpy.ndarray[numpy.float64[3, 1]],
path_axis_deviation_limit: float | None = None,
terminal_axis_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraint#

Create an OrientationConstraint such that the tool frame orientation is constrained to rotate about a “free axis” along the path AND at termination.

static terminal_and_path_target(
orientation_target: cumotion.Rotation3,
path_deviation_limit: float | None = None,
terminal_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraint#

Create an OrientationConstraint such that a tool frame orientation_target is specified along the path AND at termination.

static terminal_axis(
tool_frame_axis: numpy.ndarray[numpy.float64[3, 1]],
world_target_axis: numpy.ndarray[numpy.float64[3, 1]],
terminal_axis_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraint#

Create an OrientationConstraint such that the terminal tool frame orientation is constrained to rotate about a “free axis”, but no orientation constraints are active along the path.

static terminal_target(
orientation_target: cumotion.Rotation3,
terminal_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraint#

Create an OrientationConstraint such that a tool frame orientation_target is specified at termination, but no orientation constraints are active along the path.

static terminal_target_and_path_axis(
terminal_orientation_target: cumotion.Rotation3,
tool_frame_axis: numpy.ndarray[numpy.float64[3, 1]],
world_target_axis: numpy.ndarray[numpy.float64[3, 1]],
terminal_deviation_limit: float | None = None,
path_axis_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraint#

Create an OrientationConstraint such that a tool frame terminal_orientation_target is specified at termination, AND the tool frame orientation is constrained to rotate about a “free axis” along the path.

class OrientationConstraintGoalset#

Variant of OrientationConstraint for “goalset” planning.

static constant(
path_deviation_limit: float | None = None,
terminal_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraintGoalset#

Create an OrientationConstraintGoalset such that the tool frame orientation along the path AND at termination are constrained to the tool frame orientation at the initial c-space position.

static none() cumotion.TrajectoryOptimizer.OrientationConstraintGoalset#

Create an OrientationConstraintGoalset such that no tool frame orientation constraints are active along the path OR at termination.

static terminal_and_path_axis(
tool_frame_axes: List[numpy.ndarray[numpy.float64[3, 1]]],
world_target_axes: List[numpy.ndarray[numpy.float64[3, 1]]],
path_axis_deviation_limit: float | None = None,
terminal_axis_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraintGoalset#

Create an OrientationConstraintGoalset such that the tool frame orientation is constrained to rotate about a “free axis” along the path AND at termination.

static terminal_and_path_target(
orientation_targets: List[cumotion.Rotation3],
path_deviation_limit: float | None = None,
terminal_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraintGoalset#

Create an OrientationConstraintGoalset such that tool frame orientation_targets are specified along the path AND at termination.

static terminal_axis(
tool_frame_axes: List[numpy.ndarray[numpy.float64[3, 1]]],
world_target_axes: List[numpy.ndarray[numpy.float64[3, 1]]],
terminal_axis_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraintGoalset#

Create an OrientationConstraintGoalset such that the terminal tool frame orientation is constrained to rotate about a “free axis”, but no orientation constraints are active along the path.

static terminal_target(
orientation_targets: List[cumotion.Rotation3],
terminal_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraintGoalset#

Create an OrientationConstraintGoalset such that tool frame orientation_targets are specified at termination, but no orientation constraints are active along the path.

static terminal_target_and_path_axis(
terminal_orientation_targets: List[cumotion.Rotation3],
tool_frame_axes: List[numpy.ndarray[numpy.float64[3, 1]]],
world_target_axes: List[numpy.ndarray[numpy.float64[3, 1]]],
terminal_deviation_limit: float | None = None,
path_axis_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.OrientationConstraintGoalset#

Create an OrientationConstraintGoalset such that tool frame terminal_orientation_targets are specified at termination, AND the tool frame orientation is constrained to rotate about a “free axis” along the path.

class Results#

Results from a trajectory optimization.

class Status#

Members:

SUCCESS

INVALID_INITIAL_CSPACE_POSITION

INVALID_TARGET_SPECIFICATION

INVERSE_KINEMATICS_FAILURE

GEOMETRIC_PLANNING_FAILURE

TRAJECTORY_OPTIMIZATION_FAILURE

GEOMETRIC_PLANNING_FAILURE = <Status.GEOMETRIC_PLANNING_FAILURE: 4>#
INVALID_INITIAL_CSPACE_POSITION = <Status.INVALID_INITIAL_CSPACE_POSITION: 1>#
INVALID_TARGET_SPECIFICATION = <Status.INVALID_TARGET_SPECIFICATION: 2>#
INVERSE_KINEMATICS_FAILURE = <Status.INVERSE_KINEMATICS_FAILURE: 3>#
SUCCESS = <Status.SUCCESS: 0>#
TRAJECTORY_OPTIMIZATION_FAILURE = <Status.TRAJECTORY_OPTIMIZATION_FAILURE: 5>#
property name#
property value#
status(
self: cumotion.TrajectoryOptimizer.Results,
) cumotion.TrajectoryOptimizer.Results.Status#

Return the Status from the trajectory optimization.

target_index(
self: cumotion.TrajectoryOptimizer.Results,
) int#

Return the index of the target selected for the terminal knot point.

trajectory(
self: cumotion.TrajectoryOptimizer.Results,
) cumotion.Trajectory#

If status() returns SUCCESS, then trajectory() returns a valid Trajectory.

class TaskSpaceTarget#

Task-space targets restrict the position and (optionally) orientation of the tool frame at the termination of a trajectory and (optionally) along the path.

class TaskSpaceTargetGoalset#

Variant of TaskSpaceTarget for “goalset” planning.

class TranslationConstraint#

Translation constraints restrict the position of the origin of a tool frame.

static linear_path_constraint(
translation_target: numpy.ndarray[numpy.float64[3, 1]],
path_deviation_limit: float | None = None,
terminal_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.TranslationConstraint#

Create a TranslationConstraint such that a translation_target is specified at termination AND a linear translation constraint is active along the path.

static target(
translation_target: numpy.ndarray[numpy.float64[3, 1]],
terminal_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.TranslationConstraint#

Create a TranslationConstraint such that a translation_target is specified at termination, but no translation constraints are active along the path.

class TranslationConstraintGoalset#

Variant of TranslationConstraint for “goalset” planning.

static linear_path_constraint(
translation_targets: List[numpy.ndarray[numpy.float64[3, 1]]],
path_deviation_limit: float | None = None,
terminal_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.TranslationConstraintGoalset#

Create a TranslationConstraintGoalset such that translation_targets are specified at termination AND linear translation constraints are active along the path.

static target(
translation_targets: List[numpy.ndarray[numpy.float64[3, 1]]],
terminal_deviation_limit: float | None = None,
) cumotion.TrajectoryOptimizer.TranslationConstraintGoalset#

Create a TranslationConstraintGoalset such that translation_targets are specified at termination, but no translation constraints are active along the path.

plan_to_cspace_target(
self: cumotion.TrajectoryOptimizer,
initial_cspace_position: numpy.ndarray[numpy.float64[m, 1]],
cspace_target: cumotion.TrajectoryOptimizer.CSpaceTarget,
) cumotion.TrajectoryOptimizer.Results#

Attempt to find a trajectory from initial_cspace_position to cspace_target.

plan_to_task_space_goalset(
self: cumotion.TrajectoryOptimizer,
initial_cspace_position: numpy.ndarray[numpy.float64[m, 1]],
task_space_target_goalset: cumotion.TrajectoryOptimizer.TaskSpaceTargetGoalset,
) cumotion.TrajectoryOptimizer.Results#

Attempt to find a trajectory from initial_cspace_position to task_space_target_goalset.

plan_to_task_space_target(
self: cumotion.TrajectoryOptimizer,
initial_cspace_position: numpy.ndarray[numpy.float64[m, 1]],
task_space_target: cumotion.TrajectoryOptimizer.TaskSpaceTarget,
) cumotion.TrajectoryOptimizer.Results#

Attempt to find a trajectory from initial_cspace_position to task_space_target.

cumotion.create_trajectory_optimizer(
config: cumotion.TrajectoryOptimizerConfig,
) cumotion.TrajectoryOptimizer#

Create a TrajectoryOptimizer with the given config.

Path Specification#

class cumotion.CSpacePathSpec#

Procedurally specify a CSpacePathSpec from a series of configuration space waypoints

add_cspace_waypoint(
self: cumotion.CSpacePathSpec,
waypoint: numpy.ndarray[numpy.float64[m, 1]],
) bool#

Add a path to connect the previous configuration to the waypoint.

num_cspace_coords(self: cumotion.CSpacePathSpec) int#

Return the number of configuration space coordinates for the path specification.

cumotion.create_cspace_path_spec(
initial_cspace_position: numpy.ndarray[numpy.float64[m, 1]],
) cumotion.CSpacePathSpec#

Create a CSpacePathSpec with the specified initial_cspace_position.

class cumotion.TaskSpacePathSpec#

Procedurally compose a TaskSpacePathSpec from a series of continuous task space segments

add_linear_path(
self: cumotion.TaskSpacePathSpec,
target_pose: cumotion.Pose3,
blend_radius: float = 0.0,
) bool#

Add a path to linearly connect the previous pose to the target_pose.

add_rotation(
self: cumotion.TaskSpacePathSpec,
target_rotation: cumotion.Rotation3,
) bool#

Add a rotation-only path connecting the previous pose to the target_rotation.

add_tangent_arc(
self: cumotion.TaskSpacePathSpec,
target_position: numpy.ndarray[numpy.float64[3, 1]],
constant_orientation: bool = True,
) bool#

Add a path to connect the previous pose to the target_position along a circular arc that is tangent to the previous segment.

add_tangent_arc_with_orientation_target(
self: cumotion.TaskSpacePathSpec,
target_pose: cumotion.Pose3,
) bool#

Add a path to connect the previous pose to the target_pose along a circular arc that is tangent to the previous segment.

add_three_point_arc(
self: cumotion.TaskSpacePathSpec,
target_position: numpy.ndarray[numpy.float64[3, 1]],
intermediate_position: numpy.ndarray[numpy.float64[3, 1]],
constant_orientation: bool = True,
) bool#

Add a path to connect the previous pose to the target_position along a circular arc that passes through intermediate_position.

add_three_point_arc_with_orientation_target(
self: cumotion.TaskSpacePathSpec,
target_pose: cumotion.Pose3,
intermediate_position: numpy.ndarray[numpy.float64[3, 1]],
) bool#

Add a path to connect the previous pose to the target_pose along a circular arc that passes through intermediate_position.

add_translation(
self: cumotion.TaskSpacePathSpec,
target_position: numpy.ndarray[numpy.float64[3, 1]],
blend_radius: float = 0.0,
) bool#

Add a translation-only path to linearly connect the previous pose to the target_position

generate_path(
self: cumotion.TaskSpacePathSpec,
) cumotion.TaskSpacePath#

Generate a continuous path between all of the procedurally added task space path segments.

cumotion.create_task_space_path_spec(
initial_pose: cumotion.Pose3,
) cumotion.TaskSpacePathSpec#

Create a TaskSpacePathSpec with the specified initial_pose.

class cumotion.CompositePathSpec#

Procedurally compose CSpacePathSpec and TaskSpacePathSpec segments into a single path specification.

class PathSpecType#

Members:

TASK_SPACE

CSPACE

CSPACE = <PathSpecType.CSPACE: 1>#
TASK_SPACE = <PathSpecType.TASK_SPACE: 0>#
property name#
property value#
class TransitionMode#

Members:

SKIP

FREE

LINEAR_TASK_SPACE

FREE = <TransitionMode.FREE: 1>#
LINEAR_TASK_SPACE = <TransitionMode.LINEAR_TASK_SPACE: 2>#
SKIP = <TransitionMode.SKIP: 0>#
property name#
property value#
add_cspace_path_spec(
self: cumotion.CompositePathSpec,
path_spec: cumotion.CSpacePathSpec,
transition_mode: cumotion.CompositePathSpec.TransitionMode,
) bool#

Add a c-space path_spec to the CompositePathSpec with the specified transition_mode.

add_task_space_path_spec(
self: cumotion.CompositePathSpec,
path_spec: cumotion::TaskSpacePathSpec,
transition_mode: cumotion.CompositePathSpec.TransitionMode,
) bool#

Add a task space path_spec to the CompositePathSpec with the specified transition_mode.

cspace_path_spec(
self: cumotion.CompositePathSpec,
path_spec_index: int,
) cumotion.CSpacePathSpec#

Return the CSpacePathSpec at the given path_spec_index.

num_cspace_coords(
self: cumotion.CompositePathSpec,
) int#

Return the number of configuration space coordinates for the path specification.

num_path_specs(
self: cumotion.CompositePathSpec,
) int#

Return the number of path specifications contained in the CompositePathSpec.

path_spec_type(
self: cumotion.CompositePathSpec,
path_spec_index: int,
) cumotion.CompositePathSpec.PathSpecType#

Given a path_spec_index in range [0, num_path_specs()), return the type of the corresponding path specification.

task_space_path_spec(
self: cumotion.CompositePathSpec,
path_spec_index: int,
) cumotion::TaskSpacePathSpec#

Return the TaskSpacePathSpec at the given path_spec_index.

cumotion.create_composite_path_spec(
initial_cspace_position: numpy.ndarray[numpy.float64[m, 1]],
) cumotion.CompositePathSpec#

Create a CompositePathSpec with the specified initial_cspace_position.

cumotion.load_cspace_path_spec_from_file(
cspace_path_spec_file: os.PathLike,
) cumotion.CSpacePathSpec#

Load a CSpacePathSpec from file with absolute path cspace_path_spec_file.

cumotion.load_cspace_path_spec_from_memory(
cspace_path_spec_yaml: str,
) cumotion.CSpacePathSpec#

Load a CSpacePathSpec from the contents of a YAML file (cspace_path_spec_yaml).

cumotion.export_cspace_path_spec_to_memory(
cspace_path_spec: cumotion.CSpacePathSpec,
) str#

Export cspace_path_spec as a string.

cumotion.load_task_space_path_spec_from_file(
task_space_path_spec_file: os.PathLike,
) cumotion::TaskSpacePathSpec#

Load a TaskSpacePathSpec from file with absolute path task_space_path_spec_file.

cumotion.load_task_space_path_spec_from_memory(
task_space_path_spec_yaml: str,
) cumotion::TaskSpacePathSpec#

Load a TaskSpacePathSpec from the contents of a YAML file (task_space_path_spec_yaml).

cumotion.export_task_space_path_spec_to_memory(
task_space_path_spec: cumotion::TaskSpacePathSpec,
) str#

Export task_space_path_spec as a string.

cumotion.load_composite_path_spec_from_file(
composite_path_spec_file: os.PathLike,
) cumotion.CompositePathSpec#

Load a CompositePathSpec from file with absolute path composite_path_spec_file.

cumotion.load_composite_path_spec_from_memory(
composite_path_spec_yaml: str,
) cumotion.CompositePathSpec#

Load a CompositePathSpec from the contents of a YAML file (composite_path_spec_yaml).

cumotion.export_composite_path_spec_to_memory(
composite_path_spec: cumotion.CompositePathSpec,
) str#

Export composite_path_spec as a string.

Path Generation (Collision-Unaware)#

class cumotion.CSpacePath#

Represent a path through configuration space (i.e., c-space or “joint space”).

class Domain#

Indicates the continuous range of independent values, s, for which the path is defined.

property lower#
span(self: cumotion.CSpacePath.Domain) float#

Convenience function to return the span of s values included in domain.

property upper#
domain(
self: cumotion.CSpacePath,
) cumotion.CSpacePath.Domain#

Return the domain for the path.

eval(
self: cumotion.CSpacePath,
s: float,
) numpy.ndarray[numpy.float64[m, 1]]#

Evaluate the path at the given s.

max_position(
self: cumotion.CSpacePath,
) numpy.ndarray[numpy.float64[m, 1]]#

Return the maximum x, y, and z positions reached by the path (not necessarily simultaneously) within the defined domain().

min_position(
self: cumotion.CSpacePath,
) numpy.ndarray[numpy.float64[m, 1]]#

Return the minimum x, y, and z positions reached by the path (not necessarily simultaneously) within the defined domain().

num_cspace_coords(self: cumotion.CSpacePath) int#

Return the number of configuration space coordinates for the path.

path_length(self: cumotion.CSpacePath) float#

Return the total translation distance accumulated along the path, where distance is computed using the L2-norm.

class cumotion.LinearCSpacePath#

Represent a path linearly interpolated through configuration space (i.e., c-space) waypoints.

domain(
self: cumotion.LinearCSpacePath,
) cumotion.CSpacePath.Domain#

Return the domain for the path.

eval(
self: cumotion.LinearCSpacePath,
s: float,
) numpy.ndarray[numpy.float64[m, 1]]#

Evaluate the path at the given s.

max_position(
self: cumotion.LinearCSpacePath,
) numpy.ndarray[numpy.float64[m, 1]]#

Return the maximum x, y, and z positions reached by the path (not necessarily simultaneously) within the defined domain().

min_position(
self: cumotion.LinearCSpacePath,
) numpy.ndarray[numpy.float64[m, 1]]#

Return the minimum x, y, and z positions reached by the path (not necessarily simultaneously) within the defined domain().

num_cspace_coords(
self: cumotion.LinearCSpacePath,
) int#

Return the number of configuration space coordinates for the path.

path_length(self: cumotion.LinearCSpacePath) float#

Return the total translation distance accumulated along the path, where distance is computed using the L2-norm.

waypoints(
self: cumotion.LinearCSpacePath,
) List[numpy.ndarray[numpy.float64[m, 1]]]#

Return all of the waypoints through which the path is linearly interpolated (including the initial and final c-space configurations).

cumotion.create_linear_cspace_path(
cspace_path_spec: cumotion.CSpacePathSpec,
) cumotion.LinearCSpacePath#

Create a LinearCSpacePath from a c-space path specification.

class cumotion.TaskSpacePath#

Represent a path through task space (i.e., SE(3) group representing 6-dof poses).

class Domain#

Indicates the continuous range of independent values, s, for which the path is defined.

property lower#
span(
self: cumotion.TaskSpacePath.Domain,
) float#

Convenience function to return the span of s values included in domain.

property upper#
accumulated_rotation(
self: cumotion.TaskSpacePath,
) float#

Return the total angular distance (in radians) accumulated throughout the path.

domain(
self: cumotion.TaskSpacePath,
) cumotion.TaskSpacePath.Domain#

Return the domain for the path.

eval(
self: cumotion.TaskSpacePath,
s: float,
) cumotion.Pose3#

Evaluate the path at the given s.

max_position(
self: cumotion.TaskSpacePath,
) numpy.ndarray[numpy.float64[3, 1]]#

Return the maximum x, y, and z positions reached by the path (not necessarily simultaneously) within the defined domain().

min_position(
self: cumotion.TaskSpacePath,
) numpy.ndarray[numpy.float64[3, 1]]#

Return the minimum x, y, and z positions reached by the path (not necessarily simultaneously) within the defined domain().

path_length(self: cumotion.TaskSpacePath) float#

Return the total translation distance accumulated along the path.

class cumotion.TaskSpacePathConversionConfig#

Configuration parameters for converting a TaskSpacePathSpec into a series of c-space configurations.

property alpha#

“alpha” is used to exponentially scale the s step size “delta” to speed convergence when the s step size is being successively increased or successively decreased. When an increase is followed by a decrease, or vice versa, “alpha” is used to decrease the s step size “delta” to reduce overshoot. The default value is generally recommended. alpha must be greater than 1. Default value is 1.4.

property initial_s_step_size#

Initial step size in the domain value s used to sample poses from the task space path to be converted to c-space waypoints. The s step size will be adaptively updated throughout the path conversion and the default value for initialization is generally recommended. initial_s_step_size must be positive. Default value is 0.05.

property initial_s_step_size_delta#

Initial step size “delta” that is used to adaptively adjust the s step size; s is the domain value s used to sample poses from the task space path to be converted to c-space waypoints. The s step size “delta” will be adaptively updated throughout the path conversion and the default value for initialization is generally recommended. initial_s_step_size_delta must be positive. Default value is 0.005.

property max_iterations#

Maximum number of iterations to search for each c-space waypoint. If max_iterations is reached for any c-space waypoint, then path conversion will fail. max_iterations must be positive. Default value is 50.

property max_position_deviation#

For each c-space waypoint that is generated, the position deviation between the desired task space path and a task space mapping of a straight-line interpolation in c-space is approximated. The maximum position deviation places an upper bound of deviation allowed to add a c-space waypoint. max_position_deviation must be positive and greater than min_position_deviation. Default value is 0.003.

property min_position_deviation#

For each c-space waypoint that is generated, the position deviation between the desired task space path and a task space mapping of a straight-line interpolation in c-space is approximated. The minimum position deviation places a lower bound of deviation required to add a c-space waypoint. While it is somewhat unintuitive that the deviation could be too small, this minimum deviation is used to control the minimum spacing between c-space configurations along the task space path domain. A (relatively) sparse series of c-space waypoints is desirable for trajectory generation; if the minimum deviation is arbitrarily small then the c-space points will be (in general) too close together to generate a time-optimal trajectory. Generation of excessive c-space waypoints will also be computationally expensive and is, in general, best avoided. min_position_deviation must be positive and less than max_position_deviation. Default value is 0.001.

property min_s_step_size#

Minimum allowable interval in domain value s that can separate poses from the task space path to be converted to c-space waypoints. The minimum s step size serves to limit the number of c-space configurations that can be returned in the converted path. Specifically, the upper bound for the number of returned c-space configurations is (“span of the task space path domain” / min_s_step_size) + 1. min_s_step_size must be positive. Default value is 1e-5.

property min_s_step_size_delta#

Minimum allowable s step size “delta” used to adaptively update the s step size. The min_s_step_size_delta serves to limit wasted iterations when (minimal) progress is being made towards path conversion. If min_s_step_size_delta is reached during the search for any c-space waypoint, then path conversion will fail. The default value is generally recommended. min_s_step_size_delta must be positive`. Default value is 1e-5.

cumotion.convert_composite_path_spec_to_cspace(
composite_path_spec: cumotion.CompositePathSpec,
kinematics: cumotion.Kinematics,
control_frame: str,
task_space_path_conversion_config: cumotion.TaskSpacePathConversionConfig = <cumotion.TaskSpacePathConversionConfig object at 0x7515ac338db0>,
ik_config: cumotion.IkConfig = <cumotion.IkConfig object at 0x7515ac7901b0>,
) cumotion.LinearCSpacePath#

Convert a composite_path_spec into a linear c-space path.

cumotion.convert_task_space_path_spec_to_cspace(
task_space_path_spec: cumotion::TaskSpacePathSpec,
kinematics: cumotion.Kinematics,
control_frame: str,
task_space_path_conversion_config: cumotion.TaskSpacePathConversionConfig = <cumotion.TaskSpacePathConversionConfig object at 0x7515ac760f70>,
ik_config: cumotion.IkConfig = <cumotion.IkConfig object at 0x7515ac3de0f0>,
) cumotion.LinearCSpacePath#

Convert a task_space_path_spec into a linear c-space path.

Trajectory Generation (Collision-Unaware)#

class cumotion.CSpaceTrajectoryGenerator#

Configure a trajectory generator that can compute smooth trajectories.

class InterpolationMode#

Members:

LINEAR

CUBIC_SPLINE

CUBIC_SPLINE = <InterpolationMode.CUBIC_SPLINE: 1>#
LINEAR = <InterpolationMode.LINEAR: 0>#
property name#
property value#
class SolverParamValue#

Value for a given parameter.

generate_time_stamped_trajectory(self: cumotion.CSpaceTrajectoryGenerator, waypoints: List[numpy.ndarray[numpy.float64[m, 1]]], times: List[float], interpolation_mode: cumotion.CSpaceTrajectoryGenerator.InterpolationMode = <InterpolationMode.CUBIC_SPLINE: 1>) cumotion.Trajectory#

Attempt to interpolate a trajectory passing through the specified ‘waypoints’ at the specified ‘times’

generate_trajectory(
self: cumotion.CSpaceTrajectoryGenerator,
waypoints: List[numpy.ndarray[numpy.float64[m, 1]]],
) cumotion.Trajectory#

Attempt to generate a time-optimal trajectory with the specified constraints.

num_cspace_coords(
self: cumotion.CSpaceTrajectoryGenerator,
) int#

Return the number of configuration space coordinates for the trajectory generator

set_acceleration_limits(
self: cumotion.CSpaceTrajectoryGenerator,
max_acceleration: numpy.ndarray[numpy.float64[m, 1]],
) None#

Set acceleration limits.

set_jerk_limits(
self: cumotion.CSpaceTrajectoryGenerator,
max_jerk: numpy.ndarray[numpy.float64[m, 1]],
) None#

Set jerk limits.

set_position_limits(
self: cumotion.CSpaceTrajectoryGenerator,
min_position: numpy.ndarray[numpy.float64[m, 1]],
max_position: numpy.ndarray[numpy.float64[m, 1]],
) None#

Set position limits.

set_solver_param(
self: cumotion.CSpaceTrajectoryGenerator,
param_name: str,
value: cumotion.CSpaceTrajectoryGenerator.SolverParamValue,
) bool#

Set the value of the solver parameter.

set_velocity_limits(
self: cumotion.CSpaceTrajectoryGenerator,
max_velocity: numpy.ndarray[numpy.float64[m, 1]],
) None#

Set velocity limits.

cumotion.create_cspace_trajectory_generator(*args, **kwargs)#

Overloaded function.

  1. create_cspace_trajectory_generator(num_cspace_coords: int) -> cumotion.CSpaceTrajectoryGenerator

Create a CreateCSpaceTrajectoryGenerator with the specified number of configuration space coordinates.

  1. create_cspace_trajectory_generator(kinematics: cumotion.Kinematics) -> cumotion.CSpaceTrajectoryGenerator

Create a CreateCSpaceTrajectoryGenerator with the specified ‘kinematics’.

Graph-Based Path Planning#

class cumotion.MotionPlannerConfig#

Configuration parameters for MotionPlanner.

class Limit#

Simple class consisting of upper and lower limits for a variable.

property lower#
property upper#
class ParamValue#

Value for a given parameter.

set_param(*args, **kwargs)#

Overloaded function.

  1. set_param(self: cumotion.MotionPlannerConfig, param_name: str, value: numpy.ndarray[numpy.float64[3, 1]]) -> bool

Set parameter for motion planner.

  1. set_param(self: cumotion.MotionPlannerConfig, param_name: str, value: List[float]) -> bool

Set parameter for motion planner.

  1. set_param(self: cumotion.MotionPlannerConfig, param_name: str, value: List[cumotion::MotionPlannerConfig::Limit]) -> bool

Set parameter for motion planner.

  1. set_param(self: cumotion.MotionPlannerConfig, param_name: str, value: cumotion::MotionPlannerConfig::ParamValue) -> bool

Set parameter for motion planner.

cumotion.create_motion_planner_config_from_file(
motion_planner_config_file: os.PathLike,
robot_description: cumotion::RobotDescription,
tool_frame_name: str,
world_view: cumotion::WorldViewHandle,
) cumotion.MotionPlannerConfig#

Load a set of motion planning parameters from file and construct a MotionPlannerConfig.

cumotion.create_default_motion_planner_config(
robot_description: cumotion::RobotDescription,
tool_frame_name: str,
world_view: cumotion::WorldViewHandle,
) cumotion.MotionPlannerConfig#

Use default motion planning parameters to construct a MotionPlannerConfig.

class cumotion.MotionPlanner#

Interface for planning collision-free paths for robotic manipulators.

class Results#

Results from a path search.

property interpolated_path#
property path#
property path_found#
plan_to_cspace_target(
self: cumotion.MotionPlanner,
q_initial: numpy.ndarray[numpy.float64[m, 1]],
q_target: numpy.ndarray[numpy.float64[m, 1]],
generate_interpolated_path: bool = False,
) cumotion::MotionPlanner::Results#

Attempt to find path to configuration space target

plan_to_pose_target(self: cumotion.MotionPlanner, q_initial: numpy.ndarray[numpy.float64[m, 1]], pose_target: cumotion::Pose3, generate_interpolated_path: bool = False) cumotion::MotionPlanner::Results#

Attempt to find path to task space pose target using JtRRT.

plan_to_translation_target(
self: cumotion.MotionPlanner,
q_initial: numpy.ndarray[numpy.float64[m, 1]],
translation_target: numpy.ndarray[numpy.float64[3, 1]],
generate_interpolated_path: bool = False,
) cumotion::MotionPlanner::Results#

Attempt to find path to task space translation target using JtRRT.

cumotion.create_motion_planner(
config: cumotion.MotionPlannerConfig,
) cumotion.MotionPlanner#

Create a MotionPlanner with the given config.

RMPflow#

class cumotion.RmpFlowConfig#

RMPflow configuration, including parameters and robot description.

get_all_params(
self: cumotion.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: cumotion.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: cumotion.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: cumotion.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: cumotion.RmpFlowConfig,
world_view: cumotion::WorldViewHandle,
) 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 (cumotion.WorldViewHandle) – Input world view.

Returns:

None

cumotion.create_rmpflow_config_from_file(
rmpflow_config_file: os.PathLike,
robot_description: cumotion::RobotDescription,
end_effector_frame: str,
world_view: cumotion::WorldViewHandle,
) cumotion.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 cumotion.create_rmpflow().

Parameters:
  • rmpflow_config_file (str) – Path to RMPflow configuration file.

  • robot_description (cumotion.RobotDescription) – RobotDescription object, e.g. created by cumotion.load_robot_from_file().

  • 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 (cumotion.WorldViewHandle) – World view that will be used for obstacle avoidance.

Returns:

RMPflow motion policy interface object.

Return type:

cumotion.RmpFlow

cumotion.create_rmpflow_config_from_memory(
rmpflow_config: str,
robot_description: cumotion::RobotDescription,
end_effector_frame: str,
world_view: cumotion::WorldViewHandle,
) cumotion.RmpFlowConfig#
Parameters:
  • rmpflow_config (str) – RMPflow configuration as a single string (unparsed YAML).

  • robot_description (cumotion.RobotDescription) – RobotDescription object, e.g. created by cumotion.load_robot_from_file().

  • 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 (cumotion.WorldViewHandle) – World view that will be used for obstacle avoidance.

Returns:

RMPflow motion policy interface object.

Return type:

cumotion.RmpFlow

class cumotion.RmpFlow#

Interface for building and evaluating an RMPflow motion policy.

clear_end_effector_orientation_attractor(
self: cumotion.RmpFlow,
) None#

Clear end-effector orientation attractor.

clear_end_effector_position_attractor(
self: cumotion.RmpFlow,
) None#

Clear end-effector position attractor.

eval_accel(
self: cumotion.RmpFlow,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
cspace_velocity: numpy.ndarray[numpy.float64[m, 1]],
cspace_accel: numpy.ndarray[numpy.float64[m, 1], flags.writeable],
) None#

Compute configuration-space acceleration from motion policy, given input state.

eval_force_and_metric(
self: cumotion.RmpFlow,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
cspace_velocity: numpy.ndarray[numpy.float64[m, 1]],
) Tuple[numpy.ndarray[numpy.float64[m, 1]], numpy.ndarray[numpy.float64[m, n]]]#

Compute configuration-space force and metric from motion policy, given input state.

set_cspace_attractor(
self: cumotion.RmpFlow,
cspace_position: numpy.ndarray[numpy.float64[m, 1]],
) None#

Set an attractor in generalized coordinates (configuration space).

set_end_effector_orientation_attractor(
self: cumotion.RmpFlow,
orientation: cumotion::Rotation3,
) None#

Set an end-effector orientation attractor.

set_end_effector_position_attractor(
self: cumotion.RmpFlow,
position: numpy.ndarray[numpy.float64[3, 1]],
) None#

Set an end-effector position attractor.

cumotion.create_rmpflow(config: cumotion.RmpFlowConfig) cumotion.RmpFlow#

Create an instance of the RmpFlow interface from an RMPflow configuration.

Collision Sphere Generation#

class cumotion.CollisionSphereGenerator#

Configure a generator that can generate spheres to approximate mesh volumes.

class ParamValue#

Value for a given parameter.

class Sphere#

Simple representation of a sphere.

property center#
property radius#
generate_spheres(
self: cumotion.CollisionSphereGenerator,
num_spheres: int,
radius_offset: float,
) List[cumotion.CollisionSphereGenerator.Sphere]#

Generate a set of num_spheres that approximate the volume of the specified mesh

get_sampled_spheres(
self: cumotion.CollisionSphereGenerator,
) List[cumotion.CollisionSphereGenerator.Sphere]#

Return all of the medial axis spheres used to approximate the volume of the mesh. The spheres returned by generateSpheres() are selected from this set.

num_triangles(
self: cumotion.CollisionSphereGenerator,
) int#

Return the number of validated triangles that have been included in the mesh used for sampling spheres to approximate volume.

set_param(
self: cumotion.CollisionSphereGenerator,
param_name: str,
value: cumotion.CollisionSphereGenerator.ParamValue,
) bool#

Set the value of the parameter.

cumotion.create_collision_sphere_generator(
vertices: List[numpy.ndarray[numpy.float64[3, 1]]],
triangles: List[numpy.ndarray[numpy.int32[3, 1]]],
) cumotion.CollisionSphereGenerator#

Create a CollisionSphereGenerator to generate spheres that approximate the volume of a mesh represented by vertices and triangles.

cumotion.generate_collision_spheres(
vertices: List[numpy.ndarray[numpy.float64[3, 1]]],
triangles: List[numpy.ndarray[numpy.int32[3, 1]]],
max_overshoot: float = 0.05,
max_num_spheres: int = 3000,
surface_point_density: float = 30000.0,
surface_point_sampling_seed: int = 123,
flip_normals: bool = False,
min_triangle_area: float = 1e-08,
) List[cumotion.CollisionSphereGenerator.Sphere]#

Generate a selection of collision spheres from a grid of points filling a triangle mesh.