1 #include <console_bridge/console.h> 
    3 #include <octomap/OcTree.h> 
    8 int main(
int , 
char** )
 
   11   auto box = std::make_shared<tesseract_geometry::Box>(1, 1, 1);
 
   13   auto cone = std::make_shared<tesseract_geometry::Cone>(1, 1);
 
   15   auto capsule = std::make_shared<tesseract_geometry::Capsule>(1, 1);
 
   17   auto cylinder = std::make_shared<tesseract_geometry::Cylinder>(1, 1);
 
   19   auto plane = std::make_shared<tesseract_geometry::Plane>(1, 1, 1, 1);
 
   21   auto sphere = std::make_shared<tesseract_geometry::Sphere>(1);
 
   24   std::shared_ptr<const tesseract_common::VectorVector3d> mesh_vertices =
 
   25       std::make_shared<const tesseract_common::VectorVector3d>();
 
   26   std::shared_ptr<const Eigen::VectorXi> mesh_faces = std::make_shared<const Eigen::VectorXi>();
 
   28   auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
 
   31   std::shared_ptr<const tesseract_common::VectorVector3d> sdf_vertices =
 
   32       std::make_shared<const tesseract_common::VectorVector3d>();
 
   33   std::shared_ptr<const Eigen::VectorXi> sdf_faces = std::make_shared<const Eigen::VectorXi>();
 
   35   auto sdf_mesh = std::make_shared<tesseract_geometry::SDFMesh>(sdf_vertices, sdf_faces);
 
   38   std::shared_ptr<const tesseract_common::VectorVector3d> convex_vertices =
 
   39       std::make_shared<const tesseract_common::VectorVector3d>();
 
   40   std::shared_ptr<const Eigen::VectorXi> convex_faces = std::make_shared<const Eigen::VectorXi>();
 
   42   auto convex_mesh = std::make_shared<tesseract_geometry::ConvexMesh>(convex_vertices, convex_faces);
 
   45   std::shared_ptr<const octomap::OcTree> octree;