primp package

Subpackages

Submodules

primp.gora module

class primp.gora.GORA(g_init, n_step=50)

Bases: object

Globally Optimal Reparameterization Algorithm (GORA) for SE(3) trajectory data

  1. Recovering a finite difference approximation of the change between adjacent frames of an SE(3) trajectory

  2. globally minimizing the functional of the form J = int_0^1 g( au) dot{ au} dt

  3. reparameterizing the sequence with the optimal time steps

@authors: Sipu Ruan, Thomas Mitchel

get_cost_functional(tau, g_tau)

Compute cost functional

Parameters:
  • tau – Parameterization of the trajectory

  • g_tau – SE(3) trajectory parameterized by tau

Returns:

Cost functional value

get_optimal_time()

Retrieve the optimal temporal reparameterization

get_optimal_trajectory()

Retrieve the optimal trajectory

run()

Run the main routines

primp.primp module

class primp.primp.PrIMP(g_demos=None, mean_init=None, cov_init=None, group_name='SE')

Bases: object

PRIMP class for PRobabilistically-Informed Motion Primitives. It encodes demonstrated trajectories in Lie groups, adapts to novel via-point poses.

@author: Sipu Ruan

condition_via_pose(g_via=array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]), cov_via=array([[1., 0., 0., 0., 0., 0.], [0., 1., 0., 0., 0., 0.], [0., 0., 1., 0., 0., 0.], [0., 0., 0., 1., 0., 0.], [0., 0., 0., 0., 1., 0.], [0., 0., 0., 0., 0., 1.]]), t_via=1.0)

Compute conditional distribution based on via pose

Parameters:
  • g_via – Mean of the via pose

  • cov_via – Covariance of the via pose

  • t_via – Time parameter of the desired pose

get_covariance_step()

Retrieve covariance of each step

Returns:

cov_step: Covariance matrix of each step

get_joint_pdf()

Retrieve joint distribution

Returns:

self._mean_joint: Mean value of the joint distribution

Returns:

self._cov_joint: Covariance matrix of the joint distribution

get_samples(n_sample=5)

Generate random samples from Gaussian based on joint distribution

Param:

n_sample: Number of samples

Returns:

Array of SE(3) trajectory samples

primp.promp_interface module

Interface for ProMP in learning trajectory distribution from demonstration

@author: Sipu Ruan, 2022

primp.promp_interface.promp_condition(promp, T, xi, cov=None, t_c=1.0)

Compute conditioning on via points

Parameters:
  • promp – Class object of ProMP

  • T – Time sequence that parameterizes the trajectory

  • xi – Via point coordinate

  • cov – Covariance of the via point

  • t_c – The time step of the via point

Returns:

cpromp: Class object for ProMP after conditioning

Returns:

mean: Mean trajectory after conditioning

Returns:

std: An array of standard deviation after conditioning

Returns:

cov: An array of covariance after conditioning

primp.promp_interface.promp_learn(T, X, n_weights_per_dim=30)

Learning process from ProMP

Parameters:
  • T – Time sequence

  • X – Data points in Euclidean space

  • n_weights_per_dim – Number of weights per dimension

Returns:

promp: Class object for ProMP

Returns:

mean: Mean trajectory

Returns:

std: An array of standard deviation

Returns:

cov: An array of covariance

primp.promp_interface.to_workspace_start(T, X, g_start)

Convert trajectory to start from a given workspace pose (only changes positions)

Parameters:
  • T – Time sequence for the trajectory

  • X – Data point

  • g_start – SE(3) element for the starting pose

Return X2:

Positional trajectory after moving to the starting position

Module contents