Classes | Typedefs | Functions | Variables
planning_scene Namespace Reference

This namespace includes the central class for representing planning scenes. More...

Classes

class  PlanningScene
 This class maintains the representation of the environment as seen by a planning instance. The environment geometry, the robot geometry and state are maintained. More...
 
class  SceneTransforms
 

Typedefs

using MotionFeasibilityFn = boost::function< bool(const moveit::core::RobotState &, const moveit::core::RobotState &, bool)>
 This is the function signature for additional feasibility checks to be imposed on motions segments between states (in addition to respecting constraints and collision avoidance). The order of the arguments matters: the notion of feasibility is to be checked for motion segments that start at the first state and end at the second state. The third argument indicates whether the check should be verbose or not. More...
 
using ObjectColorMap = std::map< std::string, std_msgs::ColorRGBA >
 A map from object names (e.g., attached bodies, collision objects) to their colors. More...
 
using ObjectTypeMap = std::map< std::string, object_recognition_msgs::ObjectType >
 A map from object names (e.g., attached bodies, collision objects) to their types. More...
 
typedef boost::function< bool(const moveit::core::RobotState &, bool)> StateFeasibilityFn
 This is the function signature for additional feasibility checks to be imposed on states (in addition to respecting constraints and collision avoidance). The first argument is the state to check the feasibility for, the second one is whether the check should be verbose or not. More...
 

Functions

collision_detection::OccMapTreePtr createOctomap (const octomap_msgs::Octomap &map)
 
 MOVEIT_CLASS_FORWARD (PlanningScene)
 

Variables

const std::string LOGNAME = "planning_scene"
 

Detailed Description

This namespace includes the central class for representing planning scenes.

Format of .scene files

It is possible to read/write a PlanningScene's collision objects from a simple text file (.scene). The file format is defined as follows:

  <FILE>:
      <ID>  # scene id
      <OBJECT_DESCRIPTION>*
      . # single dot indicates end of file

  <OBJECT_DESCRIPTION>:
      * <ID>  # object id
      <POSE>   # object pose
      <NUMBER> # number of shapes in object
      <SHAPE_DESCRIPTION>*
      <NUMBER> # number of sub frames
      <SUBFRAME_DESCRIPTION>*

  <SHAPE_DESCRIPTION>:
      <BOX> | <CONE> | <CYLINDER> | <SPHERE> | <PLANE> | <MESH>
      <POSE>   # shape pose w.r.t. object's pose
      <COLOR>  # common color for all shapes

  <SUBFRAME_DESCRIPTION>:
      <ID>  # sub frame id
      <POSE>

  <BOX>:
      box
      <FLOAT> <FLOAT> <FLOAT>  # box dimensions: x y z

  <CONE>:
      cone
      <FLOAT> <FLOAT>  # radius height

  <CYLINDER>:
      cylinder
      <FLOAT> <FLOAT>  # radius height

  <SPHERE>:
      sphere
      <FLOAT>  # radius

  <PLANE>:
      plane
      <FLOAT> <FLOAT> <FLOAT> <FLOAT>  # plane parameters: a b c d for a*x + b*y +c*z = d

  <ID>: any text

  <POSE>:
      <FLOAT> <FLOAT> <FLOAT>  # position: x y z
      <FLOAT> <FLOAT> <FLOAT> <FLOAT>  # quaternion: x y z w

  <COLOR>:
      <FLOAT> <FLOAT> <FLOAT> <FLOAT>  # R G B A

Here is an example:

My PlanningScene
* object
0 1.0 0
0 0 0 1
2
box
0.1 0.2 0.3
0 1.0 0
0 0 0 1
1 0 0 0.5
cylinder
0.1 0.5
0.5 0 0
0 0 0 1
0 0 1 0.5
0
.

Typedef Documentation

◆ MotionFeasibilityFn

using planning_scene::MotionFeasibilityFn = typedef boost::function<bool(const moveit::core::RobotState&, const moveit::core::RobotState&, bool)>

This is the function signature for additional feasibility checks to be imposed on motions segments between states (in addition to respecting constraints and collision avoidance). The order of the arguments matters: the notion of feasibility is to be checked for motion segments that start at the first state and end at the second state. The third argument indicates whether the check should be verbose or not.

Definition at line 191 of file planning_scene.h.

◆ ObjectColorMap

using planning_scene::ObjectColorMap = typedef std::map<std::string, std_msgs::ColorRGBA>

A map from object names (e.g., attached bodies, collision objects) to their colors.

Definition at line 194 of file planning_scene.h.

◆ ObjectTypeMap

using planning_scene::ObjectTypeMap = typedef std::map<std::string, object_recognition_msgs::ObjectType>

A map from object names (e.g., attached bodies, collision objects) to their types.

Definition at line 197 of file planning_scene.h.

◆ StateFeasibilityFn

typedef boost::function<bool(const moveit::core::RobotState&, bool)> planning_scene::StateFeasibilityFn

This is the function signature for additional feasibility checks to be imposed on states (in addition to respecting constraints and collision avoidance). The first argument is the state to check the feasibility for, the second one is whether the check should be verbose or not.

Definition at line 183 of file planning_scene.h.

Function Documentation

◆ createOctomap()

collision_detection::OccMapTreePtr planning_scene::createOctomap ( const octomap_msgs::Octomap &  map)

Definition at line 1396 of file planning_scene.cpp.

◆ MOVEIT_CLASS_FORWARD()

planning_scene::MOVEIT_CLASS_FORWARD ( PlanningScene  )

Variable Documentation

◆ LOGNAME

const std::string planning_scene::LOGNAME = "planning_scene"

Definition at line 90 of file planning_scene.cpp.



moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:41