POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs package

class POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.ContinuousPushVectorizedUpdater(obs_dist, state_transition_dist, grid_size, push_threshold, friction_coefficient, max_push, obstacles, robot_radius, action_to_vector=None)[source]

Bases: VectorizedParticleBeliefUpdater

Vectorized particle belief updater for the Continuous Push POMDP.

Performs all-particle transitions and observation log-likelihood evaluations using vectorized NumPy operations, replacing per-particle Python loops with batched array operations.

Parameters:
obs_dist

2-D observation noise distribution for object position.

grid_size

Size of the square grid.

push_threshold

Maximum robot-object distance for a push to occur.

friction_coefficient

Friction reducing push force (0-1).

max_push

Maximum push magnitude.

obstacles

Shape (M, 4) AABB array.

robot_radius

Robot body radius.

Example

>>> import numpy as np
>>> np.random.seed(42)
>>> from POMDPPlanners.environments.push_pomdp import ContinuousPushPOMDP
>>> env = ContinuousPushPOMDP(discount_factor=0.99)
>>> updater = ContinuousPushVectorizedUpdater.from_environment(env)
>>> particles = np.tile(env.initial_state_dist().sample()[0], (50, 1))
>>> action = np.array([1.0, 0.0])
>>> next_p = updater.batch_transition(particles, action)
>>> next_p.shape[1]
6
>>> obs = particles[0].copy()
>>> ll = updater.batch_observation_log_likelihood(next_p, action, obs)
>>> ll.shape[0]
50
batch_observation_log_likelihood(next_particles, action, observation)[source]

Compute observation log-likelihoods for all particles at once.

Parameters:
  • next_particles (ndarray) – Transitioned particle states of shape (N, d).

  • action (ndarray) – Action vector.

  • observation (ndarray) – Observed value.

Return type:

ndarray

Returns:

Log-likelihoods of shape (N,).

batch_transition(particles, action)[source]

Transition all particles in a single batched operation.

Parameters:
  • particles (ndarray) – Current particle states of shape (N, d).

  • action (ndarray) – Action vector.

Return type:

ndarray

Returns:

Next-state particles of shape (N, d).

property config_id: str

Return a deterministic identifier for this updater configuration.

classmethod from_environment(env)[source]

Construct an updater from a ContinuousPushPOMDP instance.

Parameters:

env (ContinuousPushPOMDP) – Environment to extract parameters from.

Return type:

ContinuousPushVectorizedUpdater

Returns:

A new ContinuousPushVectorizedUpdater instance.

class POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.PushVectorizedUpdater(obs_dist, grid_size, push_threshold, friction_coefficient, obstacles, obstacle_radius, transition_error_prob)[source]

Bases: VectorizedParticleBeliefUpdater

Vectorized particle belief updater for the Push POMDP.

Performs all-particle transitions and observation log-likelihood evaluations using vectorized NumPy operations, replacing per-particle Python loops with batched array operations.

The Push transition is deterministic when transition_error_prob is zero. When nonzero, each particle independently samples which action actually executes. Observations follow a 2-D Gaussian centred on the true object position (only indices 2:4 of the state carry noise).

Parameters:
obs_dist

2-D observation noise distribution for object position.

grid_size

Size of the square grid.

push_threshold

Maximum robot-object distance for a push to occur.

friction_coefficient

Friction reducing push force (0-1).

obstacles

Array of obstacle centres, shape (M, 2) or (0, 2).

obstacle_radius

Collision radius for each obstacle.

transition_error_prob

Probability of executing a random other action.

Example

>>> import numpy as np
>>> np.random.seed(42)
>>> from POMDPPlanners.environments.push_pomdp import PushPOMDP
>>> env = PushPOMDP(discount_factor=0.99)
>>> updater = PushVectorizedUpdater.from_environment(env)
>>> particles = np.tile(env.initial_state_dist().sample()[0], (50, 1))
>>> action = 0  # "up"
>>> next_p = updater.batch_transition(particles, action)
>>> next_p.shape[1]
6
>>> obs = particles[0].copy()
>>> ll = updater.batch_observation_log_likelihood(next_p, action, obs)
>>> ll.shape[0]
50
ACTION_NAME_TO_INDEX = {'down': 1, 'left': 3, 'right': 2, 'up': 0}
ACTION_VECTORS = array([[ 0.,  1.],        [ 0., -1.],        [ 1.,  0.],        [-1.,  0.]])
batch_observation_log_likelihood(next_particles, action, observation)[source]

Compute observation log-likelihoods for all particles at once.

Parameters:
  • next_particles (ndarray) – Transitioned particle states of shape (N, d).

  • action (ndarray) – Action vector.

  • observation (ndarray) – Observed value.

Return type:

ndarray

Returns:

Log-likelihoods of shape (N,).

batch_transition(particles, action)[source]

Transition all particles in a single batched operation.

Parameters:
  • particles (ndarray) – Current particle states of shape (N, d).

  • action (ndarray) – Action vector.

Return type:

ndarray

Returns:

Next-state particles of shape (N, d).

property config_id: str

Return a deterministic identifier for this updater configuration.

classmethod from_environment(env)[source]

Construct an updater from a PushPOMDP instance.

Parameters:

env (PushPOMDP) – Environment to extract parameters from.

Return type:

PushVectorizedUpdater

Returns:

A new PushVectorizedUpdater instance.

POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.create_continuous_push_belief(env, belief_type=BeliefType.VECTORIZED_PARTICLE, n_particles=200)[source]

Create a ready-to-use belief for the Continuous Push POMDP.

Parameters:
  • env (ContinuousPushPOMDP) – ContinuousPushPOMDP environment instance.

  • belief_type (BeliefType) – Desired belief representation. Defaults to BeliefType.VECTORIZED_PARTICLE.

  • n_particles (int) – Number of particles. Defaults to 200.

Return type:

Belief

Returns:

A configured Belief object.

Raises:

ValueError – If belief_type is not supported.

POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.create_push_belief(env, belief_type=BeliefType.VECTORIZED_PARTICLE, n_particles=200)[source]

Create a ready-to-use belief for the Push POMDP.

Parameters:
  • env (PushPOMDP) – PushPOMDP environment instance.

  • belief_type (BeliefType) – Desired belief representation. Defaults to BeliefType.VECTORIZED_PARTICLE.

  • n_particles (int) – Number of particles. Defaults to 200.

Return type:

Belief

Returns:

A configured Belief object.

Raises:

ValueError – If belief_type is not supported.

Submodules

POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.continuous_push_belief_factory module

Belief factory for the Continuous Push POMDP.

Functions:
create_continuous_push_belief: Factory producing a configured belief

for ContinuousPushPOMDP.

POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.continuous_push_belief_factory.create_continuous_push_belief(env, belief_type=BeliefType.VECTORIZED_PARTICLE, n_particles=200)[source]

Create a ready-to-use belief for the Continuous Push POMDP.

Parameters:
  • env (ContinuousPushPOMDP) – ContinuousPushPOMDP environment instance.

  • belief_type (BeliefType) – Desired belief representation. Defaults to BeliefType.VECTORIZED_PARTICLE.

  • n_particles (int) – Number of particles. Defaults to 200.

Return type:

Belief

Returns:

A configured Belief object.

Raises:

ValueError – If belief_type is not supported.

POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.continuous_push_vectorized_updater module

Vectorized particle belief updater for the Continuous Push POMDP.

This module implements a concrete VectorizedParticleBeliefUpdater that performs batched state transitions and observation log-likelihood evaluations for the Continuous Push environment, replacing per-particle Python loops with NumPy array operations.

Classes:
ContinuousPushVectorizedUpdater: Batched updater for the Continuous

Push POMDP.

class POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.continuous_push_vectorized_updater.ContinuousPushVectorizedUpdater(obs_dist, state_transition_dist, grid_size, push_threshold, friction_coefficient, max_push, obstacles, robot_radius, action_to_vector=None)[source]

Bases: VectorizedParticleBeliefUpdater

Vectorized particle belief updater for the Continuous Push POMDP.

Performs all-particle transitions and observation log-likelihood evaluations using vectorized NumPy operations, replacing per-particle Python loops with batched array operations.

Parameters:
obs_dist

2-D observation noise distribution for object position.

grid_size

Size of the square grid.

push_threshold

Maximum robot-object distance for a push to occur.

friction_coefficient

Friction reducing push force (0-1).

max_push

Maximum push magnitude.

obstacles

Shape (M, 4) AABB array.

robot_radius

Robot body radius.

Example

>>> import numpy as np
>>> np.random.seed(42)
>>> from POMDPPlanners.environments.push_pomdp import ContinuousPushPOMDP
>>> env = ContinuousPushPOMDP(discount_factor=0.99)
>>> updater = ContinuousPushVectorizedUpdater.from_environment(env)
>>> particles = np.tile(env.initial_state_dist().sample()[0], (50, 1))
>>> action = np.array([1.0, 0.0])
>>> next_p = updater.batch_transition(particles, action)
>>> next_p.shape[1]
6
>>> obs = particles[0].copy()
>>> ll = updater.batch_observation_log_likelihood(next_p, action, obs)
>>> ll.shape[0]
50
batch_observation_log_likelihood(next_particles, action, observation)[source]

Compute observation log-likelihoods for all particles at once.

Parameters:
  • next_particles (ndarray) – Transitioned particle states of shape (N, d).

  • action (ndarray) – Action vector.

  • observation (ndarray) – Observed value.

Return type:

ndarray

Returns:

Log-likelihoods of shape (N,).

batch_transition(particles, action)[source]

Transition all particles in a single batched operation.

Parameters:
  • particles (ndarray) – Current particle states of shape (N, d).

  • action (ndarray) – Action vector.

Return type:

ndarray

Returns:

Next-state particles of shape (N, d).

property config_id: str

Return a deterministic identifier for this updater configuration.

classmethod from_environment(env)[source]

Construct an updater from a ContinuousPushPOMDP instance.

Parameters:

env (ContinuousPushPOMDP) – Environment to extract parameters from.

Return type:

ContinuousPushVectorizedUpdater

Returns:

A new ContinuousPushVectorizedUpdater instance.

POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.push_belief_factory module

Belief factory for the Push POMDP.

Functions:

create_push_belief: Factory producing a configured belief for PushPOMDP.

POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.push_belief_factory.create_push_belief(env, belief_type=BeliefType.VECTORIZED_PARTICLE, n_particles=200)[source]

Create a ready-to-use belief for the Push POMDP.

Parameters:
  • env (PushPOMDP) – PushPOMDP environment instance.

  • belief_type (BeliefType) – Desired belief representation. Defaults to BeliefType.VECTORIZED_PARTICLE.

  • n_particles (int) – Number of particles. Defaults to 200.

Return type:

Belief

Returns:

A configured Belief object.

Raises:

ValueError – If belief_type is not supported.

POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.push_vectorized_updater module

Vectorized particle belief updater for the Push POMDP.

This module implements a concrete VectorizedParticleBeliefUpdater that performs batched state transitions and observation log-likelihood evaluations for the Push environment, replacing per-particle Python loops with NumPy array operations.

Classes:

PushVectorizedUpdater: Batched updater for the Push POMDP.

class POMDPPlanners.environments.push_pomdp.push_pomdp_beliefs.push_vectorized_updater.PushVectorizedUpdater(obs_dist, grid_size, push_threshold, friction_coefficient, obstacles, obstacle_radius, transition_error_prob)[source]

Bases: VectorizedParticleBeliefUpdater

Vectorized particle belief updater for the Push POMDP.

Performs all-particle transitions and observation log-likelihood evaluations using vectorized NumPy operations, replacing per-particle Python loops with batched array operations.

The Push transition is deterministic when transition_error_prob is zero. When nonzero, each particle independently samples which action actually executes. Observations follow a 2-D Gaussian centred on the true object position (only indices 2:4 of the state carry noise).

Parameters:
obs_dist

2-D observation noise distribution for object position.

grid_size

Size of the square grid.

push_threshold

Maximum robot-object distance for a push to occur.

friction_coefficient

Friction reducing push force (0-1).

obstacles

Array of obstacle centres, shape (M, 2) or (0, 2).

obstacle_radius

Collision radius for each obstacle.

transition_error_prob

Probability of executing a random other action.

Example

>>> import numpy as np
>>> np.random.seed(42)
>>> from POMDPPlanners.environments.push_pomdp import PushPOMDP
>>> env = PushPOMDP(discount_factor=0.99)
>>> updater = PushVectorizedUpdater.from_environment(env)
>>> particles = np.tile(env.initial_state_dist().sample()[0], (50, 1))
>>> action = 0  # "up"
>>> next_p = updater.batch_transition(particles, action)
>>> next_p.shape[1]
6
>>> obs = particles[0].copy()
>>> ll = updater.batch_observation_log_likelihood(next_p, action, obs)
>>> ll.shape[0]
50
ACTION_NAME_TO_INDEX = {'down': 1, 'left': 3, 'right': 2, 'up': 0}
ACTION_VECTORS = array([[ 0.,  1.],        [ 0., -1.],        [ 1.,  0.],        [-1.,  0.]])
batch_observation_log_likelihood(next_particles, action, observation)[source]

Compute observation log-likelihoods for all particles at once.

Parameters:
  • next_particles (ndarray) – Transitioned particle states of shape (N, d).

  • action (ndarray) – Action vector.

  • observation (ndarray) – Observed value.

Return type:

ndarray

Returns:

Log-likelihoods of shape (N,).

batch_transition(particles, action)[source]

Transition all particles in a single batched operation.

Parameters:
  • particles (ndarray) – Current particle states of shape (N, d).

  • action (ndarray) – Action vector.

Return type:

ndarray

Returns:

Next-state particles of shape (N, d).

property config_id: str

Return a deterministic identifier for this updater configuration.

classmethod from_environment(env)[source]

Construct an updater from a PushPOMDP instance.

Parameters:

env (PushPOMDP) – Environment to extract parameters from.

Return type:

PushVectorizedUpdater

Returns:

A new PushVectorizedUpdater instance.