37 #ifndef JSK_PCL_ROS_PARTICLE_CUBOID_H_ 
   38 #define JSK_PCL_ROS_PARTICLE_CUBOID_H_ 
   40 #include <pcl/point_cloud.h> 
   47     struct _ParticleCuboid
 
   74       inline ParticleCuboid(
const ParticleCuboid& obj)
 
   86         plane_index = 
obj.plane_index;
 
   89       inline ParticleCuboid()
 
   91         x = 
y = 
z = roll = pitch = yaw = dx = dy = dz = weight = 0.0;
 
   95       inline ParticleCuboid (
float _x, 
float _y, 
float _z, 
float _roll, 
float _pitch, 
float _yaw)
 
   97         x = _x; 
y = _y; 
z = _z;
 
   98         roll = _roll; pitch = _pitch; yaw = _yaw;
 
  103       inline Eigen::Affine3f toEigenMatrix()
 const 
  108       inline void fromEigen(
const Eigen::Affine3f& pose) 
 
  110         Eigen::Vector3f 
pos(
pose.translation());
 
  111         getEulerAngles(pose, roll, pitch, yaw);
 
  112         getVector3fMap() = 
pos;
 
  117         x = 
y = 
z = roll = pitch = yaw = dx = dy = dz = weight = 0.0;
 
  120       inline float volume()
 const 
  125       inline float area()
 const 
  127         return (dx * dy + dy * dz + dz * dx) * 2.0;
 
  131       toState (
const Eigen::Affine3f &trans)
 
  133         float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw;
 
  134         getTranslationAndEulerAngles (trans,
 
  135                                       trans_x, trans_y, trans_z,
 
  136                                       trans_roll, trans_pitch, trans_yaw);
 
  141       inline float operator [] (
unsigned int i)
 const 
  149         case 4: 
return pitch;
 
  154         case 9: 
return weight;
 
  160         const std::vector<double>& 
mean, 
const std::vector<double>& cov)
 
  165       inline static int stateDimension()
 
  170       inline jsk_recognition_msgs::BoundingBox toBoundingBox()
 
  172         jsk_recognition_msgs::BoundingBox 
box;
 
  173         Eigen::Affine3f affine = toEigenMatrix();
 
  175         box.dimensions.x = dx;
 
  176         box.dimensions.y = dy;
 
  177         box.dimensions.z = dz;
 
  181       inline std::vector<int> visibleFaceIndices(
const Eigen::Vector3f local_view_point)
 const 
  183         std::vector<int> visible_faces;
 
  184         visible_faces.reserve(3);
 
  185         if (local_view_point[0] > 0) {
 
  186           visible_faces.push_back(0);
 
  188         else if (local_view_point[0] < 0) {
 
  189           visible_faces.push_back(2);
 
  191         if (local_view_point[1] > 0) {
 
  192           visible_faces.push_back(1);
 
  194         else if (local_view_point[1] < 0) {
 
  195           visible_faces.push_back(3);
 
  197         if (local_view_point[2] > 0) {
 
  198           visible_faces.push_back(4);
 
  200         else if (local_view_point[2] < 0) {
 
  201           visible_faces.push_back(5);
 
  203         return visible_faces;
 
  206       inline double distanceNearestToPlaneWithOcclusion(
 
  207         const Eigen::Vector3f& v,
 
  208         const std::vector<int>& visible_faces,
 
  209         std::vector<jsk_pcl_ros::Polygon::Ptr>& faces)
 const 
  211         double min_distance = DBL_MAX;
 
  212         for (
size_t i = 0; 
i < visible_faces.size(); 
i++) {
 
  216           if (min_distance > 
d) {
 
  226       inline double signedDistanceToPlane(
 
  227         const Eigen::Vector3f& v, 
const int plane_index)
 const 
  234           n = Eigen::Vector3f::UnitX();
 
  239           n = Eigen::Vector3f::UnitY();
 
  244           n = - (Eigen::Vector3f::UnitX());
 
  249           n = - (Eigen::Vector3f::UnitY());
 
  254           n = Eigen::Vector3f::UnitZ();
 
  259           n = - (Eigen::Vector3f::UnitZ());
 
  265         return (
n.dot(v) + 
d) / 
sqrt(
n.dot(n) + 
d * 
d);
 
  268       inline double distanceToPlane(
 
  269         const Eigen::Vector3f& v, 
const int plane_index)
 const 
  271         return std::abs(signedDistanceToPlane(
v, plane_index));
 
  276       inline int nearestPlaneIndex(
const Eigen::Vector3f& local_v)
 const 
  278         const float x = local_v[0];
 
  279         const float y = local_v[1];
 
  280         const float z = local_v[2];
 
  281         const float abs_x = std::abs(
x);
 
  282         const float abs_y = std::abs(
y);
 
  283         const float abs_z = std::abs(
z);
 
  284         if (
x > 0 && abs_x >= abs_y && abs_x >= abs_z) {
 
  287         else if (x < 0 && abs_x >= abs_y && abs_x >= abs_z) {
 
  290         else if (
y > 0 && abs_y >= abs_x && abs_y >= abs_z) {
 
  293         else if (y < 0 && abs_y >= abs_x && abs_y >= abs_z) {
 
  296         else if (
z > 0 && abs_z >= abs_x && abs_z >= abs_y) {
 
  299         else if (z < 0 && abs_z >= abs_x && abs_z >= abs_y) {
 
  306         Eigen::Affine3f 
pose = toEigenMatrix();
 
  307         Eigen::Vector3f dimensions(dx, dy, dz);
 
  309                                                           Eigen::Quaternionf(
pose.rotation()),
 
  316       template <
class InputIterator>
 
  317         static ParticleCuboid weightedAverage(InputIterator first, InputIterator last)
 
  320         for (
auto cuboid = first; cuboid != last; ++cuboid) {
 
  321           wa = wa + *(cuboid) * cuboid->weight;
 
  326       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  329     inline ParticleCuboid 
operator* (
const ParticleCuboid& p, 
const Eigen::Affine3f& transform)
 
  331       Eigen::Affine3f particle_affine = 
p.toEigenMatrix();
 
  332       Eigen::Affine3f transformed_affine = 
transform * particle_affine;
 
  334       new_p.x = transformed_affine.translation()[0];
 
  335       new_p.y = transformed_affine.translation()[1];
 
  336       new_p.z = transformed_affine.translation()[2];
 
  337       getEulerAngles(transformed_affine, new_p.
roll, new_p.
pitch, new_p.
yaw);
 
  351       newp.
roll = 
a.roll + 
b.roll;
 
  352       newp.
pitch = 
a.pitch + 
b.pitch;
 
  353       newp.
yaw = 
a.yaw + 
b.yaw;
 
  354       newp.
dx = 
a.dx + 
b.dx;
 
  355       newp.
dy = 
a.dy + 
b.dy;
 
  356       newp.
dz = 
a.dz + 
b.dz;
 
  363       newp.x     = 
static_cast<float> (
p.x * val);
 
  364       newp.y     = 
static_cast<float> (
p.y * val);
 
  365       newp.z     = 
static_cast<float> (
p.z * val);
 
  366       newp.
roll  = 
static_cast<float> (
p.roll * val);
 
  367       newp.
pitch = 
static_cast<float> (
p.pitch * val);
 
  368       newp.
yaw   = 
static_cast<float> (
p.yaw * val);
 
  369       newp.
dx = 
static_cast<float> (
p.dx * val);
 
  370       newp.
dy = 
static_cast<float> (
p.dy * val);
 
  371       newp.
dz = 
static_cast<float> (
p.dz * val);
 
  382       return a + (-1.0) * 
b;
 
  392     DefaultPointRepresentation()
 
  400       for (
int i = 0; 
i < nr_dimensions_; ++
i)
 
  416                                    (
float, pitch, pitch)
 
  421                                    (
float, weight, weight)