35 #define BOOST_PARAMETER_MAX_ARITY 7
37 #include <boost/make_shared.hpp>
43 #include <pcl/surface/convex_hull.h>
44 #include <jsk_topic_tools/log_utils.h>
50 resolution_(resolution), vote_(0)
55 d_ = -coefficients[3];
62 Eigen::Vector3f u(1, 0, 0);
64 u[0] = 0; u[1] = 1; u[2] = 0;
78 if (it !=
data_.end()) {
79 (it->second).insert(y);
104 const pcl::PointXYZRGB& to)
106 #ifdef DEBUG_GRID_MAP
107 std::cout <<
"newline" << std::endl;
109 std::vector<GridIndex::Ptr> added_indices;
122 #ifdef DEBUG_GRID_MAP
123 std::cout <<
"registering (" << (int)from_x <<
", " << (
int)from_y <<
")" << std::endl;
124 std::cout <<
"registering (" << (int)to_x <<
", " << (
int)to_y <<
")" << std::endl;
128 if (from_x != to_x) {
129 double a = (to_y - from_y) / (to_x - from_x);
130 double b = - a * from_x + from_y;
131 #ifdef DEBUG_GRID_MAP
132 std::cout <<
"a: " << a << std::endl;
135 #ifdef DEBUG_GRID_MAP
136 std::cout <<
"parallel to x" << std::endl;
138 int from_int_x = (int)from_x;
139 int to_int_x = (int)to_x;
140 int int_y = (int)from_y;
141 if (from_int_x > to_int_x) {
142 std::swap(from_int_x, to_int_x);
144 for (
int ix = from_int_x; ix < to_int_x; ++ix) {
146 #ifdef DEBUG_GRID_MAP
147 std::cout <<
"registering (" << ix <<
", " << int_y <<
")" << std::endl;
151 else if (fabs(a) < 1.0) {
152 #ifdef DEBUG_GRID_MAP
153 std::cout <<
"based on x" << std::endl;
155 int from_int_x = (int)from_x;
156 int to_int_x = (int)to_x;
157 if (from_int_x > to_int_x) {
158 std::swap(from_int_x, to_int_x);
161 for (
int ix = from_int_x; ix < to_int_x; ++ix) {
162 double y = a * ix + b;
164 #ifdef DEBUG_GRID_MAP
165 std::cout <<
"registering (" << ix <<
", " << (int)y <<
")" << std::endl;
170 #ifdef DEBUG_GRID_MAP
171 std::cout <<
"based on y" << std::endl;
173 int from_int_y = (int)from_y;
174 int to_int_y = (int)to_y;
175 if (from_int_y > to_int_y) {
176 std::swap(from_int_y, to_int_y);
179 for (
int iy = from_int_y; iy < to_int_y; ++iy) {
180 double x = iy / a - b / a;
182 #ifdef DEBUG_GRID_MAP
183 std::cout <<
"registering (" << (int)x <<
", " << iy <<
")" << std::endl;
190 #ifdef DEBUG_GRID_MAP
191 std::cout <<
"parallel to y" << std::endl;
194 int from_int_y = (int)from_y;
195 int to_int_y = (int)to_y;
196 int int_x = (int)from_x;
197 if (from_int_y > to_int_y) {
198 std::swap(from_int_y, to_int_y);
200 for (
int iy = from_int_y; iy < to_int_y; ++iy) {
202 #ifdef DEBUG_GRID_MAP
203 std::cout <<
"registering (" << int_x <<
", " << (int)iy <<
")" << std::endl;
207 return added_indices;
212 for (
size_t i = 0;
i < cloud->points.size();
i++) {
269 if (it ==
data_.end()) {
274 if (c.find(y) == c.end()) {
295 #ifdef DEBUG_GRID_MAP
296 std::cout <<
"filling " <<
start->x <<
", " <<
start->y << std::endl;
298 output.push_back(
start);
300 #ifdef DEBUG_GRID_MAP
301 if (abs(
start->x) > 100 || abs(
start->y) > 100) {
303 std::cout <<
"force to quit" << std::endl;
304 for (
size_t i = 0;
i <
lines_.size();
i++) {
306 Eigen::Vector3f from = line->from;
307 Eigen::Vector3f to = line->to;
308 #ifdef DEBUG_GRID_MAP
309 std::cout <<
"line[" <<
i <<
"]: "
310 <<
"[" << from[0] <<
", " << from[1] <<
", " << from[2] <<
"] -- "
311 <<
"[" << to[0] <<
", " << to[1] <<
", " << to[2] << std::endl;
323 fillRegion(boost::make_shared<GridIndex>(U), output);
326 fillRegion(boost::make_shared<GridIndex>(L), output);
329 fillRegion(boost::make_shared<GridIndex>(R), output);
332 fillRegion(boost::make_shared<GridIndex>(D), output);
345 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud)
347 for (
size_t i = 0;
i < indices.size();
i++) {
349 Eigen::Vector3f point;
350 pcl::PointXYZRGB new_point;
352 new_point.x = point[0];
353 new_point.y = point[1];
354 new_point.z = point[2];
355 cloud->points.push_back(new_point);
361 Eigen::Matrix3f rot_mat;
362 rot_mat.col(0) = Eigen::Vector3f(
ex_[0],
ex_[1],
ex_[2]);
363 rot_mat.col(1) = Eigen::Vector3f(
ey_[0],
ey_[1],
ey_[2]);
369 output = Eigen::Translation3f(
O_) * Eigen::Quaternionf(rot_mat);
374 Eigen::Affine3f float_affine;
383 Eigen::Affine3d plane_pose;
389 int column_index = it->first;
391 jsk_recognition_msgs::SparseOccupancyGridColumn ros_column;
392 ros_column.column_index = column_index;
394 rit != row_indices.end();
396 jsk_recognition_msgs::SparseOccupancyGridCell cell;
397 cell.row_index = *rit;
399 ros_column.cells.push_back(cell);
401 grid.columns.push_back(ros_column);
419 std::vector<float> output;
423 output.push_back(
d_);
451 if (it !=
data_.end()) {
453 if (rit != it->second.end()) {
454 it->second.erase(rit);
469 int max_x = - INT_MAX;
481 return boost::make_tuple<int, int>(min_x, max_x);
487 int max_y = - INT_MAX;
493 rit != row_indices.end();
504 return boost::make_tuple<int, int>(min_y, max_y);
509 boost::tuple<int, int> min_max_x =
minMaxX();
510 return min_max_x.get<1>() - min_max_x.get<0>();
515 boost::tuple<int, int> min_max_y =
minMaxY();
516 return min_max_y.get<1>() - min_max_y.get<0>();
521 boost::tuple<int, int> min_max_x =
minMaxX();
522 int min_x = min_max_x.get<0>();
528 boost::tuple<int, int> min_max_y =
minMaxY();
529 int min_y = min_max_y.get<0>();
536 int original_x,
int original_y)
538 int x = original_x + width_offset;
539 int y = original_y + height_offset;
540 return y *
step + x * elem_size;
557 rit != it->second.end();
560 m.step, m.elemSize(),
561 it->first, *rit)] = 255;
590 rit != row_indices.end();
594 new_map->registerIndex(x, y);
598 data_ = new_map->data_;
603 for (
int ii = 0; ii <
i; ii++) {
611 it != other.
data_.end();
616 rit != row_indices.end();
623 pointFromVectorToXYZ<Eigen::Vector3f, pcl::PointXYZRGB>(pos,
p);
631 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (
new pcl::PointCloud<pcl::PointXYZ>);
638 rit != row_indices.end();
645 pointFromVectorToXYZ<Eigen::Vector3f, pcl::PointXYZ>(pos,
p);
646 cloud->points.push_back(
p);
657 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud =
toPointCloud();
658 pcl::ConvexHull<pcl::PointXYZ> chull;
659 chull.setInputCloud(cloud);
660 chull.setDimension(2);
661 pcl::PointCloud<pcl::PointXYZ> chull_output;
662 chull.reconstruct(chull_output);
665 for (
size_t i = 0;
i < chull_output.points.size();
i++) {
666 Eigen::Vector3f v = chull_output.points[
i].getVector3fMap();