Namespaces | Functions | Variables
construct_planning_scene.cpp File Reference
#include "construct_planning_scene.h"
#include <choreo_geometry_conversion_helpers/choreo_geometry_conversion_helpers.h>
#include <eigen_conversions/eigen_msg.h>
#include <shape_msgs/Mesh.h>
#include <moveit_msgs/PlanningSceneComponents.h>
#include <moveit_msgs/ApplyPlanningScene.h>
#include <moveit_msgs/GetPlanningScene.h>
#include <moveit_msgs/AttachedCollisionObject.h>
#include <geometry_msgs/Point.h>
Include dependency graph for construct_planning_scene.cpp:

Go to the source code of this file.

Namespaces

 choreo_process_planning
 

Functions

void choreo_process_planning::constructPlanningScene (const planning_scene::PlanningScenePtr base_scene, const std::vector< moveit_msgs::CollisionObject > &add_cos, const std::vector< moveit_msgs::CollisionObject > &remove_cos, const std::vector< moveit_msgs::AttachedCollisionObject > &attach_objs, const std::vector< moveit_msgs::AttachedCollisionObject > &detach_objs, planning_scene::PlanningScenePtr s)
 
planning_scene::PlanningScenePtr choreo_process_planning::constructPlanningScene (const planning_scene::PlanningScenePtr base_scene, const std::vector< moveit_msgs::CollisionObject > &add_cos, const std::vector< moveit_msgs::CollisionObject > &remove_cos, const std::vector< moveit_msgs::AttachedCollisionObject > &attach_objs, const std::vector< moveit_msgs::AttachedCollisionObject > &detach_objs)
 
void choreo_process_planning::constructPlanningScenes (moveit::core::RobotModelConstPtr moveit_model, const std::string &world_frame, const choreo_msgs::AssemblySequencePickNPlace &as_pnp, std::vector< std::vector< planning_scene::PlanningScenePtr >> &planning_scenes_transition, std::vector< std::vector< planning_scene::PlanningScenePtr >> &planning_scenes_subprocess)
 
void choreo_process_planning::constructPlanningScenes (moveit::core::RobotModelConstPtr moveit_model, const std::vector< choreo_msgs::WireFrameCollisionObject > &wf_collision_objs, std::vector< planning_scene::PlanningScenePtr > &planning_scenes_shrinked_approach, std::vector< planning_scene::PlanningScenePtr > &planning_scenes_shrinked_depart, std::vector< planning_scene::PlanningScenePtr > &planning_scenes_full)
 

Variables

static const std::string GET_PLANNING_SCENE_SERVICE = "get_planning_scene"
 
static const Eigen::Vector3d MESH_SCALE_VECTOR = Eigen::Vector3d(0.001, 0.001, 0.001)
 
static const std::string PICKNPLACE_EEF_NAME = "mit_arch_suction_gripper"
 

Variable Documentation

const std::string GET_PLANNING_SCENE_SERVICE = "get_planning_scene"
static

Definition at line 23 of file construct_planning_scene.cpp.

const Eigen::Vector3d MESH_SCALE_VECTOR = Eigen::Vector3d(0.001, 0.001, 0.001)
static

Definition at line 26 of file construct_planning_scene.cpp.

const std::string PICKNPLACE_EEF_NAME = "mit_arch_suction_gripper"
static

Definition at line 21 of file construct_planning_scene.cpp.



choreo_process_planning
Author(s): Yijiang Huang
autogenerated on Thu Jul 18 2019 03:59:02