movement_primitives.promp.ProMP#
- class movement_primitives.promp.ProMP(n_dims, n_weights_per_dim=10)#
Bases:
object
Probabilistic Movement Primitive (ProMP).
ProMPs have been proposed first in [1] and have been used later in [2], [3]. The learning algorithm is a specialized form of the one presented in [4].
Note that internally we represented trajectories with the task space dimension as the first axis and the time step as the second axis while the exposed trajectory interface is transposed. In addition, we internally only use a 1d array representation to make handling of the covariance simpler.
- Parameters:
- n_dimsint
State space dimensions.
- n_weights_per_dimint, optional (default: 10)
Number of weights of the function approximator per dimension.
Methods
condition_position
(y_mean[, y_cov, t, t_max])Condition ProMP on a specific position.
Get trajectory covariance of ProMP.
Get velocity covariance of ProMP.
from_weight_distribution
(mean, cov)Initialize ProMP from mean and covariance in weight space.
imitate
(Ts, Ys[, n_iter, min_delta, verbose])Learn ProMP from multiple demonstrations.
Get mean trajectory of ProMP.
Get mean velocities of ProMP.
sample_trajectories
(T, n_samples, random_state)Sample trajectories from ProMP.
trajectory_from_weights
(T, weights)Generate trajectory from ProMP weights.
Get trajectory variance of ProMP.
Get velocity variance of ProMP.
weights
(T, Y[, lmbda])Obtain ProMP weights by linear regression.
References
[1]Paraschos, A., Daniel, C., Peters, J., Neumann, G. (2013). Probabilistic movement primitives, In C.J. Burges and L. Bottou and M. Welling and Z. Ghahramani and K.Q. Weinberger (Eds.), Advances in Neural Information Processing Systems, 26, https://papers.nips.cc/paper/2013/file/e53a0a2978c28872a4505bdb51db06dc-Paper.pdf
[3]Maeda, G. J., Neumann, G., Ewerton, M., Lioutikov, R., Kroemer, O., Peters, J. (2017). Probabilistic movement primitives for coordination of multiple human–robot collaborative tasks. Autonomous Robots, 41, 593-612. DOI: 10.1007/s10514-016-9556-2, https://link.springer.com/article/10.1007/s10514-016-9556-2
[2]Paraschos, A., Daniel, C., Peters, J., Neumann, G. (2018). Using probabilistic movement primitives in robotics. Autonomous Robots, 42, 529-551. DOI: 10.1007/s10514-017-9648-7, https://www.ias.informatik.tu-darmstadt.de/uploads/Team/AlexandrosParaschos/promps_auro.pdf
[4]Lazaric, A., Ghavamzadeh, M. (2010). Bayesian Multi-Task Reinforcement Learning. In Proceedings of the 27th International Conference on International Conference on Machine Learning (ICML’10) (pp. 599-606). https://hal.inria.fr/inria-00475214/document
- condition_position(y_mean, y_cov=None, t=0, t_max=1.0)#
Condition ProMP on a specific position.
For details, see page 4 of [1]
- Parameters:
- y_meanarray, shape (n_dims,)
Position mean.
- y_covarray, shape (n_dims, n_dims), optional (default: 0)
Covariance of position.
- tfloat, optional (default: 0)
Time at which the activations of RBFs will be queried. Note that we internally normalize the time so that t_max == 1.
- t_maxfloat, optional (default: 1)
Duration of the ProMP
- Returns:
- conditional_prompProMP
New conditional ProMP
References
[1]Paraschos, A., Daniel, C., Peters, J., Neumann, G. (2013). Probabilistic movement primitives, In C.J. Burges and L. Bottou and M. Welling and Z. Ghahramani and K.Q. Weinberger (Eds.), Advances in Neural Information Processing Systems, 26, https://papers.nips.cc/paper/2013/file/e53a0a2978c28872a4505bdb51db06dc-Paper.pdf
- cov_trajectory(T)#
Get trajectory covariance of ProMP.
- Parameters:
- Tarray-like, shape (n_steps,)
Time steps
- Returns:
- covarray, shape (n_dims * n_steps, n_dims * n_steps)
Covariance
- cov_velocities(T)#
Get velocity covariance of ProMP.
- Parameters:
- Tarray-like, shape (n_steps,)
Time steps
- Returns:
- covarray, shape (n_dims * n_steps, n_dims * n_steps)
Covariance
- from_weight_distribution(mean, cov)#
Initialize ProMP from mean and covariance in weight space.
- Parameters:
- meanarray, shape (n_dims * n_weights_per_dim)
Mean of weight distribution
- covarray, shape (n_dims * n_weights_per_dim, n_dims * n_weights_per_dim)
Covariance of weight distribution
- Returns:
- selfProMP
This object
- imitate(Ts, Ys, n_iter=1000, min_delta=1e-05, verbose=0)#
Learn ProMP from multiple demonstrations.
For details, see Section 3.2 of [1]. We use the parameters \(P = I\) (identity matrix), \(\mu_0 = 0, k_0 = 0, \nu_0 = 0, \Sigma_0 = 0,\alpha_0 = 0,\beta_0 = 0\).
- Parameters:
- Tsarray, shape (n_demos, n_steps)
Time steps of demonstrations
- Ysarray, shape (n_demos, n_steps, n_dims)
Demonstrations
- n_iterint, optional (default: 1000)
Maximum number of iterations
- min_deltafloat, optional (default: 1e-5)
Minimum delta between means to continue iteration
- verboseint, optional (default: 0)
Verbosity level
References
[1]Lazaric, A., Ghavamzadeh, M. (2010). Bayesian Multi-Task Reinforcement Learning. In Proceedings of the 27th International Conference on International Conference on Machine Learning (ICML’10) (pp. 599-606). https://hal.inria.fr/inria-00475214/document
- mean_trajectory(T)#
Get mean trajectory of ProMP.
- Parameters:
- Tarray-like, shape (n_steps,)
Time steps
- Returns:
- Yarray, shape (n_steps, n_dims)
Mean trajectory
- mean_velocities(T)#
Get mean velocities of ProMP.
- Parameters:
- Tarray-like, shape (n_steps,)
Time steps
- Returns:
- Ydarray, shape (n_steps, n_dims)
Mean velocities
- sample_trajectories(T, n_samples, random_state)#
Sample trajectories from ProMP.
- Parameters:
- Tarray-like, shape (n_steps,)
Time steps
- n_samplesint
Number of trajectories that will be sampled
- random_statenp.random.RandomState
State of random number generator
- Returns:
- samplesarray, shape (n_samples, n_steps, n_dims)
Sampled trajectories
- trajectory_from_weights(T, weights)#
Generate trajectory from ProMP weights.
- Parameters:
- Tarray-like, shape (n_steps,)
Time steps
- weightsarray-like, shape (n_steps * n_weights_per_dim)
ProMP weights
- Returns:
- Yarray, shape (n_steps, n_dims)
Trajectory
- var_trajectory(T)#
Get trajectory variance of ProMP.
- Parameters:
- Tarray-like, shape (n_steps,)
Time steps
- Returns:
- vararray, shape (n_steps, n_dims)
Variance
- var_velocities(T)#
Get velocity variance of ProMP.
- Parameters:
- Tarray-like, shape (n_steps,)
Time steps
- Returns:
- vararray, shape (n_steps, n_dims)
Variance
- weights(T, Y, lmbda=1e-12)#
Obtain ProMP weights by linear regression.
- Parameters:
- Tarray-like, shape (n_steps,)
Time steps
- Yarray-like, shape (n_steps, n_dims)
Demonstrated trajectory
- lmbdafloat, optional (default: 1e-12)
Regularization coefficient
- Returns:
- weightsarray, shape (n_steps * n_weights_per_dim)
ProMP weights