35 #define BOOST_PARAMETER_MAX_ARITY 7 42 Cube::Cube(
const Eigen::Vector3f& pos,
const Eigen::Quaternionf& rot):
48 Cube::Cube(
const Eigen::Vector3f& pos,
const Eigen::Quaternionf& rot,
49 const std::vector<double>& dimensions):
54 Cube::Cube(
const Eigen::Vector3f& pos,
const Eigen::Quaternionf& rot,
55 const Eigen::Vector3f& dimensions):
65 const Line& line_a,
const Line& line_b,
const Line& line_c)
67 double distance_a_b = line_a.
distance(line_b);
68 double distance_a_c = line_a.
distance(line_c);
69 double distance_b_c = line_b.
distance(line_c);
72 Eigen::Vector3f ex, ey, ez;
73 if (distance_a_b >= distance_a_c &&
74 distance_a_b >= distance_b_c) {
80 else if (distance_a_c >= distance_a_b &&
81 distance_a_c >= distance_b_c) {
95 axis->getDirection(ez);
99 if (ex.cross(ey).dot(ez) < 0) {
103 axis->foot(pos,
pos_);
112 Eigen::Affine3f
pose;
114 pos_ = Eigen::Vector3f(pose.translation());
115 rot_ = Eigen::Quaternionf(pose.rotation());
125 std::vector<Segment::Ptr> ret;
126 Eigen::Vector3f A =
pos_ 129 (+
dimensions_[2] * Eigen::Vector3f::UnitZ())) / 2.0;
130 Eigen::Vector3f B =
pos_ 133 (+
dimensions_[2] * Eigen::Vector3f::UnitZ())) / 2.0;
134 Eigen::Vector3f C =
pos_ 137 (+
dimensions_[2] * Eigen::Vector3f::UnitZ())) / 2.0;
138 Eigen::Vector3f D =
pos_ 141 (+
dimensions_[2] * Eigen::Vector3f::UnitZ())) / 2.0;
142 Eigen::Vector3f E =
pos_ 145 (-
dimensions_[2] * Eigen::Vector3f::UnitZ())) / 2.0;
146 Eigen::Vector3f F =
pos_ 149 (-
dimensions_[2] * Eigen::Vector3f::UnitZ())) / 2.0;
150 Eigen::Vector3f G =
pos_ 153 (-
dimensions_[2] * Eigen::Vector3f::UnitZ())) / 2.0;
154 Eigen::Vector3f H =
pos_ 157 (-
dimensions_[2] * Eigen::Vector3f::UnitZ())) / 2.0;
176 std::vector<Segment::Ptr> candidate_edges =
edges();
178 for (
size_t i = 0; i < candidate_edges.size(); i++) {
181 if (edge->intersect(plane, p)) {
182 intersects.push_back(p);
187 pcl::ConvexHull<pcl::PointXYZ> chull;
188 pcl::PointCloud<pcl::PointXYZ>::Ptr chull_input
189 = verticesToPointCloud<pcl::PointXYZ>(intersects);
190 pcl::PointCloud<pcl::PointXYZ>::Ptr chull_cloud
191 (
new pcl::PointCloud<pcl::PointXYZ>);
192 chull.setDimension(2);
193 chull.setInputCloud(chull_input);
196 chull.reconstruct(*chull_cloud);
205 jsk_recognition_msgs::BoundingBox ret;
206 ret.pose.position.x =
pos_[0];
207 ret.pose.position.y =
pos_[1];
208 ret.pose.position.z =
pos_[2];
209 ret.pose.orientation.x =
rot_.x();
210 ret.pose.orientation.y =
rot_.y();
211 ret.pose.orientation.z =
rot_.z();
212 ret.pose.orientation.w =
rot_.w();
237 for (
size_t i = 0; i < vs.size(); i++) {
238 transformed_vertices.push_back(pose_offset * vs[i]);
240 return transformed_vertices;
244 const Eigen::Vector3f v1,
245 const Eigen::Vector3f v2,
246 const Eigen::Vector3f v3)
258 std::vector<Polygon::Ptr> fs(6);
260 Eigen::Vector3f A = vs[0];
261 Eigen::Vector3f B = vs[1];
262 Eigen::Vector3f C = vs[2];
263 Eigen::Vector3f D = vs[3];
264 Eigen::Vector3f E = vs[4];
265 Eigen::Vector3f F = vs[5];
266 Eigen::Vector3f G = vs[6];
267 Eigen::Vector3f H = vs[7];
268 Vertices vs0, vs1, vs2, vs3, vs4, vs5, vs6;
269 vs0.push_back(A); vs0.push_back(E); vs0.push_back(F); vs0.push_back(B);
270 vs1.push_back(B); vs1.push_back(F); vs1.push_back(G); vs1.push_back(C);
271 vs2.push_back(C); vs2.push_back(G); vs2.push_back(H); vs2.push_back(D);
272 vs3.push_back(D); vs3.push_back(H); vs3.push_back(E); vs3.push_back(A);
273 vs4.push_back(A); vs4.push_back(B); vs4.push_back(C); vs4.push_back(D);
274 vs5.push_back(E); vs5.push_back(H); vs5.push_back(G); vs5.push_back(F);
286 Eigen::Vector3f local = (Eigen::Vector3f::UnitX() * i *
dimensions_[0] +
289 return Eigen::Translation3f(
pos_) *
rot_ * local;
295 std::vector<Polygon::Ptr> current_faces =
faces();
296 double min_distance = DBL_MAX;
297 Eigen::Vector3f min_point;
298 for (
size_t i = 0; i < current_faces.size(); i++) {
301 Eigen::Vector3f
q = f->nearestPoint(p, d);
302 if (min_distance > d) {
307 distance = min_distance;
Vertices vertices()
returns vertices as an array of Eigen::Vectro3f. The order of the vertices is: [1, 1, 1], [-1, 1, 1], [-1, -1, 1], [1, -1, 1], [1, 1, -1], [-1, 1, -1], [-1, -1, -1], [1, -1, -1].
std::vector< Segment::Ptr > edges()
virtual double distance(const Line &other) const
compute a distance to line.
Vertices transformVertices(const Eigen::Affine3f &pose_offset)
returns vertices transformed by pose_offset.
boost::mutex global_chull_mutex
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
boost::shared_ptr< ConvexPolygon > Ptr
boost::shared_ptr< Polygon > Ptr
ConvexPolygon::Ptr intersectConvexPolygon(Plane &plane)
Class to represent 3-D straight line which has finite length.
virtual Polygon::Ptr buildFace(const Eigen::Vector3f v0, const Eigen::Vector3f v1, const Eigen::Vector3f v2, const Eigen::Vector3f v3)
A helper method to build polygon from 4 vertices.
Cube(const Eigen::Vector3f &pos, const Eigen::Quaternionf &rot)
Eigen::Quaternionf rotFrom3Axis(const Eigen::Vector3f &ex, const Eigen::Vector3f &ey, const Eigen::Vector3f &ez)
virtual Ptr midLine(const Line &other) const
compute a middle line between given line.
std::vector< double > dimensions_
virtual Eigen::Vector3f buildVertex(double i, double j, double k)
A helper method to build vertex from x-y-z relatiev coordinates.
virtual Eigen::Vector3f nearestPoint(const Eigen::Vector3f &p, double &distance)
compute minimum distance from point p to cube surface.
jsk_recognition_msgs::BoundingBox toROSMsg()
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
std::vector< Polygon::Ptr > faces()
returns all the 6 faces as Polygon::Ptr. TODO: is it should be ConvexPolygon?
Vertices pointCloudToVertices(const pcl::PointCloud< PointT > &cloud)
Compute Vertices from PointCloud.
Class to represent 3-D straight line.
virtual void parallelLineNormal(const Line &other, Eigen::Vector3f &output) const
compute a perpendicular line of two lines from origin_