moveit.core.planning_scene

Classes

PlanningScene

Representation of the environment as seen by a planning instance.

class moveit.core.planning_scene.PlanningScene

Representation of the environment as seen by a planning instance. The environment geometry, the robot geometry and state are maintained.

property allowed_collision_matrix
apply_collision_object()

Apply a collision object to the planning scene.

Parameters:
  • object (moveit_msgs.msg.CollisionObject) – The collision object to apply to the planning scene.

  • color (moveit_msgs.msg.ObjectColor, optional) – The color of the collision object. Defaults to None if not specified.

check_collision()

Check whether the current state is in collision, and if needed, updates the collision transforms of the current state before the computation.

Parameters:
  • collision_request (moveit_py.core.CollisionRequest) – The collision request to use.

  • collision_result (moveit_py.core.CollisionResult) – The collision result to update

Returns:

bool – true if state is in collision otherwise false.

Check if the robot state is in collision.

Parameters:
  • collision_request ()

  • collision_result ()

  • state ()

Returns:

bool – true if state is in collision otherwise false.

Check if the robot state is in collision.

Parameters:
  • collision_request ()

  • collision_result ()

  • state ()

  • acm ()

Returns:

bool – true if state is in collision otherwise false.

check_collision_unpadded()

Check if the robot state is in collision.

Parameters:
  • collision_request ()

  • collision_result ()

Returns:

bool – true if state is in collision otherwise false.

Check if the robot state is in collision.

Parameters:
  • collision_request ()

  • collision_result ()

  • state ()

Returns:

bool – true if state is in collision otherwise false.

Check if the robot state is in collision.

Parameters:
  • collision_request ()

  • collision_result ()

  • state ()

  • acm ()

Returns:

bool – true if state is in collision otherwise false.

check_self_collision()

Check if the robot state is in collision.

Parameters:
  • collision_request ()

  • collision_result ()

Returns:

bool – true if state is in collision otherwise false.

Check if the robot state is in collision.

Parameters:
  • collision request ()

  • collision_result ()

  • state ()

Returns:

bool – true if state is in self collision otherwise false.

Check if the robot state is in collision.

Parameters:
  • collision request ()

  • collision_result ()

  • state ()

  • acm()

Returns:

bool – true if state is in self collision otherwise false.

property current_state

The current state of the robot.

Type:

moveit_py.core.RobotState

get_frame_transform()

Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available.

Parameters:

frame_id (str) – The frame id to get the transform for.

Returns:

numpy.ndarray – The transform corresponding to the frame id.

is_path_valid()

Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility)

Parameters:
  • trajectory (moveit_py.core.RobotTrajectory) – The trajectory to check.

  • joint_model_group_name (str) – The joint model group to check the path against.

  • verbose (bool)

  • invalid_index (list)

Returns:

bool – true if the path is valid otherwise false.

is_state_colliding()

Check if the robot state is in collision.

Parameters:
  • joint_model_group_name (str) – The name of the group to check collision for.

  • verbose (bool) – If true, print the link names of the links in collision.

Returns:

bool – True if the robot state is in collision, false otherwise.

Check if the robot state is in collision.

Parameters:
  • robot_state (moveit_py.core.RobotState) – The robot state to check collision for.

  • joint_model_group_name (str) – The name of the group to check collision for.

  • verbose (bool) – If true, print the link names of the links in collision.

Returns:

bool – True if the robot state is in collision, false otherwise.

is_state_constrained()

Check if the robot state fulfills the passed constraints

Parameters:
  • state (moveit_py.core.RobotState) – The robot state to check constraints for.

  • constraints (moveit_msgs.msg.Constraints) – The constraints to check.

  • verbose (bool)

Returns:

bool – true if state is constrained otherwise false.

is_state_valid()
knows_frame_transform()

Check if a transform to the frame id is known. This will be known if id is a link name, an attached body id or a collision object.

Parameters:
  • robot_state (moveit_py.core.RobotState) – The robot state to check.

  • frame_id (str) – The frame id to check.

Returns:

bool – True if the transform is known, false otherwise.

Check if a transform to the frame id is known. This will be known if id is a link name, an attached body id or a collision object.

Parameters:

frame_id (str) – The frame id to check.

Returns:

bool – True if the transform is known, false otherwise.

property name

The name of the planning scene.

Type:

str

property planning_frame

The frame in which planning is performed.

Type:

str

property planning_scene_message
process_attached_collision_object()

Apply an attached collision object to the planning scene.

Parameters:

object (moveit_msgs.msg.AttachedCollisionObject) – The attached collision object to apply to the planning scene.

process_octomap()

Apply an octomap to the planning scene.

Parameters:

octomap (moveit_msgs.msg.Octomap) – The octomap to apply to the planning scene.

process_planning_scene_world()

Process a planning scene world message.

Parameters:

msg (moveit_msgs.msg.PlanningSceneWorld) – The planning scene world message.

remove_all_collision_objects()

Removes collision objects from the planning scene. This method will remove all collision object from the scene except for attached collision objects.

property robot_model

The robot model associated to this planning scene.

Type:

moveit_py.core.RobotModel

set_object_color()

Set the color of a collision object.

Parameters:
  • object_id (str) – The id of the collision object to set the color of.

  • color (std_msgs.msg.ObjectColor) – The color of the collision object.

property transforms