00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <ros/ros.h>
00037 #include "jsk_footstep_planner/ann_grid.h"
00038
00039 using namespace jsk_footstep_planner;
00040
00041 int main(int argc, char** argv)
00042 {
00043 ros::init(argc, argv, "ann_grid_demo");
00044 pcl::PointCloud<pcl::PointNormal> cloud;
00045 for (double x = -2; x < 2; x += 0.01) {
00046 for (double y = -2; y < 2; y += 0.01) {
00047 pcl::PointNormal p;
00048 p.x = x;
00049 p.y = y;
00050 p.z = cos(x) * cos(y);
00051 cloud.points.push_back(p);
00052 }
00053 }
00054 ANNGrid::Ptr ann_grid(new ANNGrid(0.1));
00055 ann_grid->build(cloud);
00056 cv::Mat grid_image;
00057 ann_grid->toImage(grid_image);
00058 std::cout << "ann grid size is "
00059 << grid_image.rows << "x" << grid_image.cols << std::endl;
00060 cv::imshow("ann_grid", grid_image);
00061
00062 cv::Mat grid_image2;
00063 ANNGrid::IndexArray pixels = ann_grid->bresenham(Eigen::Vector3f(1, 1, 0), Eigen::Vector3f(-1, -1, 0));
00064 ann_grid->toImage(grid_image2, pixels);
00065 cv::imshow("ann_grid2", grid_image2);
00066
00067 cv::Mat grid_image3;
00068 ANNGrid::IndexArray box_pixels = ann_grid->box(Eigen::Vector3f(1, 1, 0),
00069 Eigen::Vector3f(-1, 1, 0),
00070 Eigen::Vector3f(-1, -1, 0),
00071 Eigen::Vector3f(1, -1, 0));
00072 ann_grid->toImage(grid_image3, box_pixels);
00073 cv::imshow("ann_grid3", grid_image3);
00074
00075 cv::Mat grid_image4;
00076 ANNGrid::IndexArray filled_pixels = ann_grid->fillByBox(Eigen::Vector3f(1, 1, 0),
00077 Eigen::Vector3f(-1, 1, 0),
00078 Eigen::Vector3f(-1, -1, 0),
00079 Eigen::Vector3f(1, -1, 0));
00080 std::cout << "filled pixels: " << filled_pixels.size() << std::endl;
00081 ann_grid->toImage(grid_image4, filled_pixels);
00082 cv::imshow("ann_grid4", grid_image4);
00083
00084 pcl::PointIndices near_indices;
00085 ann_grid->approximateSearchInBox(Eigen::Vector3f(1, 1, 0),
00086 Eigen::Vector3f(-1, 1, 0),
00087 Eigen::Vector3f(-1, -1, 0),
00088 Eigen::Vector3f(1, -1, 0),
00089 near_indices);
00090 for (size_t i = 0; i < near_indices.indices.size(); i++) {
00091 std::cout << cloud.points[near_indices.indices[i]] << std::endl;
00092 }
00093
00094 while(1) {
00095 cv::waitKey(0);
00096 }
00097 return 0;
00098 }