Public Member Functions | Public Attributes | Private Member Functions
NeighborhoodGraph Class Reference

#include <NeighborhoodGraph.h>

List of all members.

Public Member Functions

void buildAdjacencyMatrixUsingVoronoi ()
void computeConnectedComponents ()
void computeEndEffectorPose (const SurfacePatch p1, const SurfacePatch p2, const double dist_above_surface, tf::Pose &pose) const
void computeEndEffectorPose (const SurfacePatch p1, const double dist_above_surface, std::vector< tf::Pose > &poses, bool single_pose=false) const
void constructGraphMarker (const std::vector< pcl::PointXYZ > &surface_samples, const Eigen::MatrixXi &adjacency, const std::string frame_id, visualization_msgs::Marker &marker_list) const
void constructGraphMarker (const std::vector< SurfacePatch > &surface, const Eigen::MatrixXi &adjacency, const std::string frame_id, visualization_msgs::Marker &marker_list) const
void getGraph (std::vector< SurfacePatch > &patches, std::vector< pcl::PointXYZ > &surface_points, Eigen::MatrixXi &adjacency, std::vector< std::vector< tf::Pose > > &coll_free_poses, std::vector< std::vector< std::vector< std::vector< double > > > > &coll_free_ik)
void getReachableVector (std::vector< bool > &reachable)
 NeighborhoodGraph (ros::NodeHandle &nh)
 NeighborhoodGraph (ros::NodeHandle &nh, bool coll_check)
 NeighborhoodGraph (ros::NodeHandle &nh, std::vector< SurfacePatch > patches, octomap::OctomapROS< octomap::OcTree > *octomap)
 NeighborhoodGraph (ros::NodeHandle &nh, std::vector< SurfacePatch > patches, octomap::OctomapROS< octomap::OcTree > *octomap, double dist_above_surface, int max_neigborhood, double max_neigborhood_radius, int n_ik_samples, bool coll_check)
void sampleSurfacePoints (const std::vector< SurfacePatch > &surface, std::vector< pcl::PointXYZ > &samples) const
void setOctomap (octomap::OctomapROS< octomap::OcTree > *octomap)
void setPatches (std::vector< SurfacePatch > patches)
void setSurfaceDist (double dist)
 ~NeighborhoodGraph ()

Public Attributes

Eigen::MatrixXi adjacency_
bool coll_check_
CollisionCheckcoll_checker_
double dist_above_surface_
std::vector< SurfacePatchgraph_
int max_neigborhood_
double max_neigborhood_radius_
int n_ik_samples_
ros::NodeHandle nh_
octomap::OctomapROS
< octomap::OcTree > * 
octomap_
std::vector< boolreachable_surface_
std::vector< std::set< int > > subgraphs_
std::vector< SurfacePatchsurface_

Private Member Functions

void buildAdjacencyMatrixUsingOctomap ()
void depthFirstConnectedComponentSearch (const int node, Eigen::MatrixXi &adjacency, std::set< int > &graph)
void getIKSolutions (const tf::Pose p, std::vector< std::vector< double > > &ik_solutions) const
void getSubgraphAdjacency (const std::set< int > &subgraph, std::map< int, int > &index_map, Eigen::MatrixXi &subgraph_adj, const std::vector< SurfacePatch > &patches, std::vector< SurfacePatch > &subgraph_patches)
void getValidIKSolutions (const std::vector< tf::Pose > &poses, const bool check_collision, std::vector< bool > &valid, std::vector< std::vector< std::vector< double > > > &ik_solutions)
bool isPoseValid (const tf::Pose pose, const bool check_collision, std::vector< std::vector< double > > &ik_solutions)
void sampleSurfacePoints (const std::vector< SurfacePatch > &surface, pcl::PointCloud< pcl::PointXYZ > &samples) const

Detailed Description

Definition at line 14 of file NeighborhoodGraph.h.


Constructor & Destructor Documentation

Author:
Juergen Hess

Definition at line 12 of file NeigborhoodGraph.cpp.

Definition at line 19 of file NeigborhoodGraph.cpp.

NeighborhoodGraph::NeighborhoodGraph ( ros::NodeHandle nh,
std::vector< SurfacePatch patches,
octomap::OctomapROS< octomap::OcTree > *  octomap 
)

Definition at line 27 of file NeigborhoodGraph.cpp.

NeighborhoodGraph::NeighborhoodGraph ( ros::NodeHandle nh,
std::vector< SurfacePatch patches,
octomap::OctomapROS< octomap::OcTree > *  octomap,
double  dist_above_surface,
int  max_neigborhood,
double  max_neigborhood_radius,
int  n_ik_samples,
bool  coll_check 
)

Definition at line 38 of file NeigborhoodGraph.cpp.

Definition at line 51 of file NeigborhoodGraph.cpp.


Member Function Documentation

Definition at line 99 of file NeigborhoodGraph.cpp.

Definition at line 149 of file NeigborhoodGraph.cpp.

Definition at line 281 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::computeEndEffectorPose ( const SurfacePatch  p1,
const SurfacePatch  p2,
const double  dist_above_surface,
tf::Pose pose 
) const

Definition at line 496 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::computeEndEffectorPose ( const SurfacePatch  p1,
const double  dist_above_surface,
std::vector< tf::Pose > &  poses,
bool  single_pose = false 
) const

Definition at line 438 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::constructGraphMarker ( const std::vector< pcl::PointXYZ > &  surface_samples,
const Eigen::MatrixXi &  adjacency,
const std::string  frame_id,
visualization_msgs::Marker &  marker_list 
) const

Definition at line 698 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::constructGraphMarker ( const std::vector< SurfacePatch > &  surface,
const Eigen::MatrixXi &  adjacency,
const std::string  frame_id,
visualization_msgs::Marker &  marker_list 
) const

Definition at line 748 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::depthFirstConnectedComponentSearch ( const int  node,
Eigen::MatrixXi &  adjacency,
std::set< int > &  graph 
) [private]

Definition at line 270 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::getGraph ( std::vector< SurfacePatch > &  patches,
std::vector< pcl::PointXYZ > &  surface_points,
Eigen::MatrixXi &  adjacency,
std::vector< std::vector< tf::Pose > > &  coll_free_poses,
std::vector< std::vector< std::vector< std::vector< double > > > > &  coll_free_ik 
)

Definition at line 569 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::getIKSolutions ( const tf::Pose  p,
std::vector< std::vector< double > > &  ik_solutions 
) const [private]

Definition at line 337 of file NeigborhoodGraph.cpp.

Definition at line 68 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::getSubgraphAdjacency ( const std::set< int > &  subgraph,
std::map< int, int > &  index_map,
Eigen::MatrixXi &  subgraph_adj,
const std::vector< SurfacePatch > &  patches,
std::vector< SurfacePatch > &  subgraph_patches 
) [private]

Definition at line 314 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::getValidIKSolutions ( const std::vector< tf::Pose > &  poses,
const bool  check_collision,
std::vector< bool > &  valid,
std::vector< std::vector< std::vector< double > > > &  ik_solutions 
) [private]

Definition at line 255 of file NeigborhoodGraph.cpp.

bool NeighborhoodGraph::isPoseValid ( const tf::Pose  pose,
const bool  check_collision,
std::vector< std::vector< double > > &  ik_solutions 
) [private]

Definition at line 227 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::sampleSurfacePoints ( const std::vector< SurfacePatch > &  surface,
std::vector< pcl::PointXYZ > &  samples 
) const

Definition at line 71 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::sampleSurfacePoints ( const std::vector< SurfacePatch > &  surface,
pcl::PointCloud< pcl::PointXYZ > &  samples 
) const [private]

Definition at line 85 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::setOctomap ( octomap::OctomapROS< octomap::OcTree > *  octomap)

Definition at line 64 of file NeigborhoodGraph.cpp.

Definition at line 57 of file NeigborhoodGraph.cpp.

void NeighborhoodGraph::setSurfaceDist ( double  dist)

Definition at line 60 of file NeigborhoodGraph.cpp.


Member Data Documentation

Definition at line 58 of file NeighborhoodGraph.h.

Definition at line 59 of file NeighborhoodGraph.h.

Definition at line 51 of file NeighborhoodGraph.h.

Definition at line 46 of file NeighborhoodGraph.h.

Definition at line 56 of file NeighborhoodGraph.h.

Definition at line 48 of file NeighborhoodGraph.h.

Definition at line 49 of file NeighborhoodGraph.h.

Definition at line 58 of file NeighborhoodGraph.h.

Definition at line 45 of file NeighborhoodGraph.h.

Definition at line 50 of file NeighborhoodGraph.h.

Definition at line 54 of file NeighborhoodGraph.h.

Definition at line 57 of file NeighborhoodGraph.h.

Definition at line 53 of file NeighborhoodGraph.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


coverage_3d_planning
Author(s): Juergen Hess
autogenerated on Wed Dec 26 2012 15:26:11