klampt.model.cartesian_trajectory module

Reliable Cartesian interpolation functions between arbitrary task space points. Also defines a convenient “bump” function that modify joint-space paths to achieve a task-space displacement.

class klampt.model.cartesian_trajectory.BisectNode(a, b, ua, ub, qa, qb)[source]
klampt.model.cartesian_trajectory.cartesian_bump(robot, js_path, constraints, bump_paths, delta=0.01, solver=None, ee_relative=False, maximize=False, closest=False, maxDeviation=None)[source]

Given the robot and a reference joint space trajectory, “bumps” the trajectory in cartesian space using a given relative transform (or transform path). The movement in joint space is approximately minimized to follow the bumped cartesian path.

For example, to translate the motion of an end effector by [dx,dy,dz] in world coordinates, call:

cartesian_bump(robot,traj,ik.fixed_objective(link),se3.from_translation([dx,dy,dz]))
Parameters:
  • robot (RobotModel or SubRobotModel) – the robot for which the bump is applied.
  • js_path – the reference joint space Trajectory of the robot. May be a RobotTrajectory.
  • constraints

    one or more link indices, link names, or IKObjective’s giving the manner in which the Cartesian space is defined. Interpreted as follows:

    • int or str: the specified link’s entire pose is constrained
    • IKObjective: the links, constraint types, local positions, and local axes are used as constraints.
      The world space elements are considered temporary and will change to match the Cartesian trajectory.
    • list of int, list of str, or list of IKObjective: concatenates the specified constraints together
  • bump_paths – one or more transforms or transform paths specifying the world-space relative “bump” of each cartesian goal. One bump per constraint must be given as input. Each bump can either be a static klampt.se3 element or a SE3Trajectory.
  • delta (float, optional) – the maximum configuration space distance between points on the output path
  • method – method used. Can be ‘any’, ‘pointwise’, or ‘roadmap’.
  • solver (IKSolver, optional) – if provided, an IKSolver configured with the desired parameters for IK constraint solving.
  • ee_relative (bool, optional) – if False (default), bumps are given in world coordinates. If True, bumps are given in end-effector local coordinates.
  • maximize (bool, optional) – if true, goes as far as possible along the path.
  • closest (bool, optional) – if not resolved and this is True, the function returns the robot trajectory whose cartesian targets get as close as possible (locally) to the bumped trajectory
  • maxDeviation (list of floats, optional) – if not None, this is a vector giving the max joint space distance by which each active joint is allowed to move from js_path.
Returns:

the bumped trajectory, or None if none can be found

Return type:

RobotTrajectory

klampt.model.cartesian_trajectory.cartesian_interpolate_bisect(robot, a, b, constraints, startConfig='robot', endConfig=None, delta=0.01, solver=None, feasibilityTest=None, growthTol=10)[source]

Resolves a continuous robot trajectory that interpolates between two cartesian points for a single link of a robot. Note that the output path is only a kinematic resolution. It has time domain [0,1].

Parameters:
  • robot – the RobotModel or SubRobotModel.
  • b (a,) – endpoints of the Cartesian trajectory. Assumed derived from config.getConfig(constraints)
  • constraints

    one or more link indices, link names, or IKObjective’s giving the manner in which the Cartesian space is defined. Interpreted as follows:

    • int or str: the specified link’s entire pose is constrained
    • IKObjective: the links, constraint types, local positions, and local axes are used as constraints.
      The world space elements are considered temporary and will change to match the Cartesian trajectory.
    • list of int, list of str, or list of IKObjective: concatenates the specified constraints together
  • startConfig (optional) – either ‘robot’ (configuration taken from the robot), a configuration, or None (any configuration)
  • endConfig (optional) – same type as startConfig.
  • delta (float, optional) – the maximum configuration space distance between points on the output path
  • solver (IKSolver, optional) – if provided, an IKSolver configured with the desired parameters for IK constraint solving.
  • feasibilityTest (function, optional) – a function f(q) that returns false when a configuration q is infeasible
  • growthTol (float, optional) – the end path can be at most growthTol the times length of the length between the start and goal configurations.
Returns:

a configuration space path that interpolates the Cartesian path, or None if no

solution can be found.

Return type:

RobotTrajectory

klampt.model.cartesian_trajectory.cartesian_interpolate_linear(robot, a, b, constraints, startConfig='robot', endConfig=None, delta=0.01, solver=None, feasibilityTest=None, maximize=False)[source]

Resolves a continuous robot trajectory that interpolates between two cartesian points for specified IK constraints. Note that the output path is only a kinematic resolution. It has time domain [0,1].

Parameters:
  • robot – the RobotModel or SubRobotModel.
  • b (a,) – endpoints of the Cartesian trajectory. Assumed derived from config.getConfig(constraints)
  • constraints

    one or more link indices, link names, or IKObjective’s giving the manner in which the Cartesian space is defined. Interpreted as follows:

    • int or str: the specified link’s entire pose is constrained
    • IKObjective: the links, constraint types, local positions, and local axes are used as constraints.
      The world space elements are considered temporary and will change to match the Cartesian trajectory.
    • list of int, list of str, or list of IKObjective: concatenates the specified constraints together
  • startConfig (optional) – either ‘robot’ (configuration taken from the robot), a configuration, or None (any configuration)
  • endConfig (optional) – same type as startConfig.
  • delta (float, optional) – the maximum configuration space distance between points on the output path
  • solver (IKSolver, optional) – if provided, an IKSolver configured with the desired parameters for IK constraint solving.
  • feasibilityTest (function, optional) – a function f(q) that returns false when a configuration q is infeasible
  • maximize (bool, optional) – if true, goes as far as possible along the path.
Returns:

a configuration space path that interpolates the Cartesian path, or None if no

solution can be found.

Return type:

RobotTrajectory

klampt.model.cartesian_trajectory.cartesian_move_to(robot, constraints, delta=0.01, method='any', solver=None, feasibilityTest=None, numSamples=1000, maximize=False)[source]

A convenience function that generates a path that performs a linear cartesian interpolation starting from the robot’s current configuration and ending at the desired IK constraints. This is a bit more convenient than cartesian_interpolate_linear since you only need to pass in the target objective, rather than the start and end Cartesian parameters as well. Typical calling is path = cartesian_move_to(robot,goal).

Other arguments are equivalent to those in cartesian_interpolate_linear.

klampt.model.cartesian_trajectory.cartesian_path_interpolate(robot, path, constraints, startConfig='robot', endConfig=None, delta=0.01, method='any', solver=None, feasibilityTest=None, numSamples=1000, maximize=False)[source]

Resolves a continuous robot trajectory that follows a cartesian path for a single link of a robot. Note that the output path is only a kinematic resolution, and may not respect the robot’s velocity / acceleration limits.

Parameters:
  • robot – the RobotModel or SubRobotModel.
  • path – a list of milestones, or a Trajectory for the parameters of the given constraints. In the former case the milestones are spaced 1s apart in time.
  • constraints

    one or more link indices, link names, or IKObjective’s giving the manner in which the Cartesian space is defined. Interpreted as follows:

    • int or str: the specified link’s entire pose is constrained
    • IKObjective: the links, constraint types, local positions, and local axes are used as constraints.
      The world space elements are considered temporary and will change to match the Cartesian trajectory.
    • list of int, list of str, or list of IKObjective: concatenates the specified constraints together
  • startConfig (optional) – either ‘robot’ (configuration taken from the robot), a configuration, or None (any configuration)
  • endConfig (optional) – same type as startConfig.
  • delta (float, optional) – the maximum configuration space distance between points on the output path
  • method – method used. Can be ‘any’, ‘pointwise’, or ‘roadmap’.
  • solver (IKSolver, optional) – if provided, an IKSolver configured with the desired parameters for IK constraint solving.
  • feasibilityTest (function, optional) – a function f(q) that returns false when a configuration q is infeasible
  • numSamples (int, optional) – if ‘roadmap’ or ‘any’ method is used, the # of configuration space samples that are used.
  • maximize (bool, optional) – if true, goes as far as possible along the path.
Returns:

a configuration space path that interpolates the Cartesian path, or None if no

solution can be found.

Return type:

RobotTrajectory

klampt.model.cartesian_trajectory.set_cartesian_constraints(x, constraints, solver)[source]

For x a workspace parameter setting (achieved via config.getConfig(constraints)), a set of constraints, and a IKSolver object, modifies the constraints and the solver so that the solver is setup to match the workspace parameter setting x.

klampt.model.cartesian_trajectory.solve_cartesian(x, constraints, solver)[source]

For x a workspace parameter setting (achieved via config.getConfig(constraints)), a set of constraints, and a IKSolver object, returns True if the solver can find a solution (from the robot’s current configuration). Returns True if successful.