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
00037 #ifndef JSK_PCL_ROS_PARTICLE_CUBOID_H_
00038 #define JSK_PCL_ROS_PARTICLE_CUBOID_H_
00039
00040 #include <pcl/point_cloud.h>
00041 #include "jsk_pcl_ros/geo_util.h"
00042
00043 namespace pcl
00044 {
00045 namespace tracking
00046 {
00047 struct _ParticleCuboid
00048 {
00049 PCL_ADD_POINT4D;
00050 union
00051 {
00052 struct
00053 {
00054 float roll;
00055 float pitch;
00056 float yaw;
00057 float dx;
00058 float dy;
00059 float dz;
00060 float weight;
00061
00062 };
00063 float data_c[8];
00064 };
00065
00066
00067 int plane_index;
00068 };
00069
00070 struct EIGEN_ALIGN16 ParticleCuboid : public _ParticleCuboid
00071 {
00072
00073
00074 inline ParticleCuboid(const ParticleCuboid& obj)
00075 {
00076 x = obj.x;
00077 y = obj.y;
00078 z = obj.z;
00079 roll = obj.roll;
00080 pitch = obj.pitch;
00081 yaw = obj.yaw;
00082 dx = obj.dx;
00083 dy = obj.dy;
00084 dz = obj.dz;
00085 weight = obj.weight;
00086 plane_index = obj.plane_index;
00087 }
00088
00089 inline ParticleCuboid()
00090 {
00091 x = y = z = roll = pitch = yaw = dx = dy = dz = weight = 0.0;
00092 data[3] = 1.0f;
00093 plane_index = -1;
00094 }
00095 inline ParticleCuboid (float _x, float _y, float _z, float _roll, float _pitch, float _yaw)
00096 {
00097 x = _x; y = _y; z = _z;
00098 roll = _roll; pitch = _pitch; yaw = _yaw;
00099 dx = dy = dz = 0.0;
00100 data[3] = 1.0f;
00101 }
00102
00103 inline Eigen::Affine3f toEigenMatrix() const
00104 {
00105 return getTransformation(x, y, z, roll, pitch, yaw);
00106 }
00107
00108 inline void fromEigen(const Eigen::Affine3f& pose)
00109 {
00110 Eigen::Vector3f pos(pose.translation());
00111 getEulerAngles(pose, roll, pitch, yaw);
00112 getVector3fMap() = pos;
00113 }
00114
00115 inline void zero()
00116 {
00117 x = y = z = roll = pitch = yaw = dx = dy = dz = weight = 0.0;
00118 }
00119
00120 inline float volume() const
00121 {
00122 return dx * dy * dz;
00123 }
00124
00125 inline float area() const
00126 {
00127 return (dx * dy + dy * dz + dz * dx) * 2.0;
00128 }
00129
00130 static pcl::tracking::ParticleCuboid
00131 toState (const Eigen::Affine3f &trans)
00132 {
00133 float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
00134 getTranslationAndEulerAngles (trans,
00135 trans_x, trans_y, trans_z,
00136 trans_roll, trans_pitch, trans_yaw);
00137 return pcl::tracking::ParticleCuboid (trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw);
00138 }
00139
00140
00141 inline float operator [] (unsigned int i) const
00142 {
00143 switch (i)
00144 {
00145 case 0: return x;
00146 case 1: return y;
00147 case 2: return z;
00148 case 3: return roll;
00149 case 4: return pitch;
00150 case 5: return yaw;
00151 case 6: return dx;
00152 case 7: return dy;
00153 case 8: return dz;
00154 case 9: return weight;
00155 default: return 0.0;
00156 }
00157 }
00158
00159 inline void sample(
00160 const std::vector<double>& mean, const std::vector<double>& cov)
00161 {
00162
00163 }
00164
00165 inline static int stateDimension()
00166 {
00167 return 9;
00168 }
00169
00170 inline jsk_recognition_msgs::BoundingBox toBoundingBox()
00171 {
00172 jsk_recognition_msgs::BoundingBox box;
00173 Eigen::Affine3f affine = toEigenMatrix();
00174 tf::poseEigenToMsg(affine, box.pose);
00175 box.dimensions.x = dx;
00176 box.dimensions.y = dy;
00177 box.dimensions.z = dz;
00178 return box;
00179 }
00180
00181 inline std::vector<int> visibleFaceIndices(const Eigen::Vector3f local_view_point) const
00182 {
00183 std::vector<int> visible_faces;
00184 visible_faces.reserve(3);
00185 if (local_view_point[0] > 0) {
00186 visible_faces.push_back(0);
00187 }
00188 else if (local_view_point[0] < 0) {
00189 visible_faces.push_back(2);
00190 }
00191 if (local_view_point[1] > 0) {
00192 visible_faces.push_back(1);
00193 }
00194 else if (local_view_point[1] < 0) {
00195 visible_faces.push_back(3);
00196 }
00197 if (local_view_point[2] > 0) {
00198 visible_faces.push_back(4);
00199 }
00200 else if (local_view_point[2] < 0) {
00201 visible_faces.push_back(5);
00202 }
00203 return visible_faces;
00204 }
00205
00206 inline double distanceNearestToPlaneWithOcclusion(
00207 const Eigen::Vector3f& v,
00208 const std::vector<int>& visible_faces,
00209 std::vector<jsk_pcl_ros::Polygon::Ptr>& faces) const
00210 {
00211 double min_distance = DBL_MAX;
00212 for (size_t i = 0; i < visible_faces.size(); i++) {
00213 jsk_pcl_ros::Polygon::Ptr face = faces[visible_faces[i]];
00214 double d;
00215 face->nearestPoint(v, d);
00216 if (min_distance > d) {
00217 min_distance = d;
00218 }
00219 }
00220 return min_distance;
00221 }
00222
00223
00224
00225
00226 inline double distanceToPlane(const Eigen::Vector3f& v, const int plane_index) const
00227 {
00228 Eigen::Vector3f n;
00229 double d;
00230 switch (plane_index)
00231 {
00232 case 0: {
00233 n = Eigen::Vector3f::UnitX();
00234 d = - 0.5 * dx;
00235 break;
00236 }
00237 case 1: {
00238 n = Eigen::Vector3f::UnitY();
00239 d = - 0.5 * dy;
00240 break;
00241 }
00242 case 2: {
00243 n = - (Eigen::Vector3f::UnitX());
00244 d = - 0.5 * dx;
00245 break;
00246 }
00247 case 3: {
00248 n = - (Eigen::Vector3f::UnitY());
00249 d = - 0.5 * dy;
00250 break;
00251 }
00252 case 4: {
00253 n = Eigen::Vector3f::UnitZ();
00254 d = - 0.5 * dz;
00255 break;
00256 }
00257 case 5: {
00258 n = - (Eigen::Vector3f::UnitZ());
00259 d = - 0.5 * dz;
00260 break;
00261 }
00262
00263 }
00264 return std::abs(n.dot(v) + d) / sqrt(n.dot(n) + d * d);
00265 }
00266
00267 inline int nearestPlaneIndex(const Eigen::Vector3f& local_v) const
00268 {
00269 const float x = local_v[0];
00270 const float y = local_v[1];
00271 const float z = local_v[2];
00272 const float abs_x = std::abs(x);
00273 const float abs_y = std::abs(y);
00274 const float abs_z = std::abs(z);
00275 if (x > 0 && abs_x >= abs_y && abs_x >= abs_z) {
00276 return 0;
00277 }
00278 else if (x < 0 && abs_x >= abs_y && abs_x >= abs_z) {
00279 return 2;
00280 }
00281 else if (y > 0 && abs_y >= abs_x && abs_y >= abs_z) {
00282 return 1;
00283 }
00284 else if (y < 0 && abs_y >= abs_x && abs_y >= abs_z) {
00285 return 3;
00286 }
00287 else if (z > 0 && abs_z >= abs_x && abs_z >= abs_y) {
00288 return 4;
00289 }
00290 else if (z < 0 && abs_z >= abs_x && abs_z >= abs_y) {
00291 return 5;
00292 }
00293 }
00294
00295 inline jsk_pcl_ros::Cube::Ptr toCube() const
00296 {
00297 Eigen::Affine3f pose = toEigenMatrix();
00298 Eigen::Vector3f dimensions(dx, dy, dz);
00299 jsk_pcl_ros::Cube::Ptr cube(new jsk_pcl_ros::Cube(Eigen::Vector3f(pose.translation()),
00300 Eigen::Quaternionf(pose.rotation()),
00301 dimensions));
00302 return cube;
00303 }
00304
00305
00306 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00307 };
00308
00309 inline ParticleCuboid operator* (const ParticleCuboid& p, const Eigen::Affine3f& transform)
00310 {
00311 Eigen::Affine3f particle_affine = p.toEigenMatrix();
00312 Eigen::Affine3f transformed_affine = transform * particle_affine;
00313 ParticleCuboid new_p;
00314 new_p.x = transformed_affine.translation()[0];
00315 new_p.y = transformed_affine.translation()[1];
00316 new_p.z = transformed_affine.translation()[2];
00317 getEulerAngles(transformed_affine, new_p.roll, new_p.pitch, new_p.yaw);
00318 new_p.dx = p.dx;
00319 new_p.dy = p.dy;
00320 new_p.dz = p.dz;
00321 return new_p;
00322 }
00323
00324
00325 inline pcl::tracking::ParticleCuboid operator+ (const ParticleCuboid& a, const ParticleCuboid& b)
00326 {
00327 pcl::tracking::ParticleCuboid newp;
00328 newp.x = a.x + b.x;
00329 newp.y = a.y + b.y;
00330 newp.z = a.z + b.z;
00331 newp.roll = a.roll + b.roll;
00332 newp.pitch = a.pitch + b.pitch;
00333 newp.yaw = a.yaw + b.yaw;
00334 newp.dx = a.dx + b.dx;
00335 newp.dy = a.dy + b.dy;
00336 newp.dz = a.dz + b.dz;
00337 return (newp);
00338 }
00339
00340 inline pcl::tracking::ParticleCuboid operator * (const ParticleCuboid& p, double val)
00341 {
00342 pcl::tracking::ParticleCuboid newp;
00343 newp.x = static_cast<float> (p.x * val);
00344 newp.y = static_cast<float> (p.y * val);
00345 newp.z = static_cast<float> (p.z * val);
00346 newp.roll = static_cast<float> (p.roll * val);
00347 newp.pitch = static_cast<float> (p.pitch * val);
00348 newp.yaw = static_cast<float> (p.yaw * val);
00349 newp.dx = static_cast<float> (p.dx * val);
00350 newp.dy = static_cast<float> (p.dy * val);
00351 newp.dz = static_cast<float> (p.dz * val);
00352 return (newp);
00353 }
00354
00355 inline pcl::tracking::ParticleCuboid operator * (double val, const ParticleCuboid& p)
00356 {
00357 return p * val;
00358 }
00359
00360 inline pcl::tracking::ParticleCuboid operator- (const ParticleCuboid& a, const ParticleCuboid& b)
00361 {
00362 return a + (-1.0) * b;
00363 }
00364
00365 }
00366
00367
00368 template<>
00369 class DefaultPointRepresentation<pcl::tracking::ParticleCuboid>: public PointRepresentation<pcl::tracking::ParticleCuboid>
00370 {
00371 public:
00372 DefaultPointRepresentation()
00373 {
00374 nr_dimensions_ = 10;
00375 }
00376
00377 virtual void
00378 copyToFloatArray (const pcl::tracking::ParticleCuboid &p, float * out) const
00379 {
00380 for (int i = 0; i < nr_dimensions_; ++i)
00381 out[i] = p[i];
00382 }
00383 };
00384
00385 }
00386
00387
00388
00389
00390
00391 POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::tracking::_ParticleCuboid,
00392 (float, x, x)
00393 (float, y, y)
00394 (float, z, z)
00395 (float, roll, roll)
00396 (float, pitch, pitch)
00397 (float, yaw, yaw)
00398 (float, dx, dx)
00399 (float, dy, dy)
00400 (float, dz, dz)
00401 (float, weight, weight)
00402 )
00403 POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::tracking::ParticleCuboid, pcl::tracking::_ParticleCuboid)
00404
00405
00406 #endif