Skip to content

Commit

Permalink
[done]task PointCloudLibrary#1
Browse files Browse the repository at this point in the history
1,Convert RBG to intensity
2,bug: crashed
  • Loading branch information
Chris.Shu committed Sep 12, 2017
1 parent c78d6b5 commit 26e89bc
Show file tree
Hide file tree
Showing 15 changed files with 146 additions and 135 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::ihs::_PointIHS,
(float, normal_x, normal_x)
(float, normal_y, normal_y)
(float, normal_z, normal_z)
(float, rgb, rgb)
(float, intensity, intensity)
(float, weight, weight)
(unsigned int, age, age)
(uint32_t, directions, directions)
Expand Down
12 changes: 6 additions & 6 deletions apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,10 +72,10 @@ namespace pcl
{
public:

typedef pcl::PointXYZRGBNormal PointXYZRGBNormal;
typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal;
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr;
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr;
typedef pcl::PointXYZINormal PointXYZINormal;
typedef pcl::PointCloud <PointXYZINormal> CloudXYZINormal;
typedef CloudXYZINormal::Ptr CloudXYZINormalPtr;
typedef CloudXYZINormal::ConstPtr CloudXYZINormalConstPtr;

typedef pcl::ihs::Mesh Mesh;
typedef pcl::ihs::MeshPtr MeshPtr;
Expand Down Expand Up @@ -159,7 +159,7 @@ namespace pcl
*/
bool
findTransformation (const MeshConstPtr& mesh_model,
const CloudXYZRGBNormalConstPtr& cloud_data,
const CloudXYZINormalConstPtr& cloud_data,
const Eigen::Matrix4f& T_init,
Eigen::Matrix4f& T_final);

Expand Down Expand Up @@ -188,7 +188,7 @@ namespace pcl
* \return Cloud containing the selected points.
*/
CloudNormalConstPtr
selectDataPoints (const CloudXYZRGBNormalConstPtr& cloud_data) const;
selectDataPoints (const CloudXYZINormalConstPtr& cloud_data) const;

/** \brief Finds the transformation that minimizes the point to plane distance from the source to the target cloud. The input clouds must be arranged to have one to one correspondences (point 0 in source corresponds to point 0 in target, point 1 in source to point 1 in target and so on).
* \param[in] cloud_source Source cloud (data).
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ namespace pcl
{
PCL_ADD_POINT4D
PCL_ADD_NORMAL4D
PCL_ADD_RGB
PCL_ADD_INTENSITY
float weight;
unsigned int age;
uint32_t directions;
Expand All @@ -69,8 +69,7 @@ namespace pcl

this->normal_x = this->normal_y = this->normal_z = std::numeric_limits<float>::quiet_NaN ();
this->data_n[3] = 0.f;

this->b = this->g = this->r = 0; this->a = 255;
this->intensity = 0;

this->weight = 0.f;
this->age = 0;
Expand All @@ -89,14 +88,14 @@ namespace pcl
this->normal_z = other.normal_z;
this->data_n[3] = other.data_n[3];

this->rgba = other.rgba;
this->intensity = other.intensity;

this->weight = other.weight;
this->age = other.age;
this->directions = other.directions;
}

inline PointIHS (const pcl::PointXYZRGBNormal& other, const float weight)
inline PointIHS (const pcl::PointXYZINormal& other, const float weight)
{
this->x = other.x;
this->y = other.y;
Expand All @@ -108,17 +107,17 @@ namespace pcl
this->normal_z = other.normal_z;
this->data_n[3] = other.data_n[3];

this->rgba = other.rgba;
this->intensity = other.intensity;

this->weight = weight;
this->age = 0;
this->directions = 0;
}

// inline Eigen::Vector3i getRGBVector3i () {return (Eigen::Vector3i (r, g, b));}
inline const Eigen::Vector3i getRGBVector3i () const {return (Eigen::Vector3i (r, g, b));}
//inline const Eigen::Vector3i getRGBVector3i () const {return (Eigen::Vector3i (r, g, b));}
// inline Eigen::Vector4i getRGBVector4i () {return (Eigen::Vector4i (r, g, b, a));}
inline const Eigen::Vector4i getRGBVector4i () const {return (Eigen::Vector4i (r, g, b, a));}
//inline const Eigen::Vector4i getRGBVector4i () const {return (Eigen::Vector4i (r, g, b, a));}
};

} // End namespace ihs
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -191,15 +191,27 @@ namespace pcl

private:

typedef pcl::PointXYZRGBA PointXYZRGBA;
typedef pcl::PointCloud <PointXYZRGBA> CloudXYZRGBA;
typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr;
typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr;

typedef pcl::PointXYZRGBNormal PointXYZRGBNormal;
typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal;
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr;
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr;
#if 0
typedef pcl::PointXYZRGBA PointXYZRGBA;
typedef pcl::PointCloud <PointXYZRGBA> CloudXYZRGBA;
typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr;
typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr;

typedef pcl::PointXYZRGBNormal PointXYZRGBNormal;
typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal;
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr;
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr;
#else
typedef pcl::PointXYZI PointXYZI;
typedef pcl::PointCloud <PointXYZI> CloudXYZI;
typedef CloudXYZI::Ptr CloudXYZIPtr;
typedef CloudXYZI::ConstPtr CloudXYZIConstPtr;

typedef pcl::PointXYZINormal PointXYZINormal;
typedef pcl::PointCloud <PointXYZINormal> CloudXYZINormal;
typedef CloudXYZINormal::Ptr CloudXYZINormalPtr;
typedef CloudXYZINormal::ConstPtr CloudXYZINormalConstPtr;
#endif

typedef pcl::ihs::PointIHS PointIHS;
typedef pcl::ihs::CloudIHS CloudIHS;
Expand All @@ -210,7 +222,7 @@ namespace pcl
typedef pcl::ihs::MeshPtr MeshPtr;
typedef pcl::ihs::MeshConstPtr MeshConstPtr;

typedef pcl::io::OpenNI2Grabber Grabber;
typedef pcl::io::OpenNI2Grabber Grabber;
typedef boost::shared_ptr <Grabber> GrabberPtr;
typedef boost::shared_ptr <const Grabber> GrabberConstPtr;

Expand All @@ -232,7 +244,7 @@ namespace pcl

/** \brief Called when new data arries from the grabber. The grabbing - registration - integration pipeline is implemented here. */
void
newDataCallback (const CloudXYZRGBAConstPtr& cloud_in);
newDataCallback (const CloudXYZIConstPtr& cloud_in);

/** \see http://doc.qt.digia.com/qt/qwidget.html#paintEvent
* \see http://doc.qt.digia.com/qt/opengl-overpainting.html
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,15 +72,15 @@ namespace pcl
{
public:

typedef pcl::PointXYZRGBA PointXYZRGBA;
typedef pcl::PointCloud <PointXYZRGBA> CloudXYZRGBA;
typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr;
typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr;
typedef pcl::PointXYZI PointXYZI;
typedef pcl::PointCloud <PointXYZI> CloudXYZI;
typedef CloudXYZI::Ptr CloudXYZIPtr;
typedef CloudXYZI::ConstPtr CloudXYZIConstPtr;

typedef pcl::PointXYZRGBNormal PointXYZRGBNormal;
typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal;
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr;
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr;
typedef pcl::PointXYZINormal PointXYZINormal;
typedef pcl::PointCloud <PointXYZINormal> CloudXYZINormal;
typedef CloudXYZINormal::Ptr CloudXYZINormalPtr;
typedef CloudXYZINormal::ConstPtr CloudXYZINormalConstPtr;

/** \brief Constructor */
InputDataProcessing ();
Expand All @@ -93,9 +93,9 @@ namespace pcl
* \note Converts from m to cm.
*/
bool
segment (const CloudXYZRGBAConstPtr& cloud_in,
CloudXYZRGBNormalPtr& cloud_out,
CloudXYZRGBNormalPtr& cloud_discarded) const;
segment (const CloudXYZIConstPtr& cloud_in,
CloudXYZINormalPtr& cloud_out,
CloudXYZINormalPtr& cloud_discarded) const;

/** \brief Calculate the normals of the input cloud.
* \param[in] cloud_in The input cloud.
Expand All @@ -104,8 +104,8 @@ namespace pcl
* \note Converts from m to cm.
*/
bool
calculateNormals (const CloudXYZRGBAConstPtr& cloud_in,
CloudXYZRGBNormalPtr& cloud_out) const;
calculateNormals (const CloudXYZIConstPtr& cloud_in,
CloudXYZINormalPtr& cloud_out) const;

/** @{ */
/** \brief Points outside of X - Y - Z - min / max are discarded. The unit is cm. The min values must be smaller than the max values. */
Expand Down Expand Up @@ -174,7 +174,7 @@ namespace pcl
typedef boost::shared_ptr <CloudNormals> CloudNormalsPtr;
typedef boost::shared_ptr <const CloudNormals> CloudNormalsConstPtr;

typedef pcl::IntegralImageNormalEstimation <PointXYZRGBA, Normal> NormalEstimation;
typedef pcl::IntegralImageNormalEstimation <PointXYZI, Normal> NormalEstimation;
typedef boost::shared_ptr <NormalEstimation> NormalEstimationPtr;
typedef boost::shared_ptr <const NormalEstimation> NormalEstimationConstPtr;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,10 +72,10 @@ namespace pcl
{
public:

typedef pcl::PointXYZRGBNormal PointXYZRGBNormal;
typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal;
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr;
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr;
typedef pcl::PointXYZINormal PointXYZINormal;
typedef pcl::PointCloud <PointXYZINormal> CloudXYZINormal;
typedef CloudXYZINormal::Ptr CloudXYZINormalPtr;
typedef CloudXYZINormal::ConstPtr CloudXYZINormalConstPtr;

typedef pcl::ihs::Mesh Mesh;
typedef pcl::ihs::MeshPtr MeshPtr;
Expand All @@ -92,7 +92,7 @@ namespace pcl
* \return true if success.
*/
bool
reconstructMesh (const CloudXYZRGBNormalConstPtr& cloud_data,
reconstructMesh (const CloudXYZINormalConstPtr& cloud_data,
MeshPtr& mesh_model) const;

/** \brief Merge the organized cloud into the mesh.
Expand All @@ -102,7 +102,7 @@ namespace pcl
* \return true if success.
*/
bool
merge (const CloudXYZRGBNormalConstPtr& cloud_data,
merge (const CloudXYZINormalConstPtr& cloud_data,
MeshPtr& mesh_model,
const Eigen::Matrix4f& T) const;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,15 +106,15 @@ namespace pcl

private:

typedef pcl::PointXYZRGBA PointXYZRGBA;
typedef pcl::PointCloud <PointXYZRGBA> CloudXYZRGBA;
typedef CloudXYZRGBA::Ptr CloudXYZRGBAPtr;
typedef CloudXYZRGBA::ConstPtr CloudXYZRGBAConstPtr;
typedef pcl::PointXYZI PointXYZI;
typedef pcl::PointCloud <PointXYZI> CloudXYZI;
typedef CloudXYZI::Ptr CloudXYZIPtr;
typedef CloudXYZI::ConstPtr CloudXYZIConstPtr;

typedef pcl::PointXYZRGBNormal PointXYZRGBNormal;
typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal;
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr;
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr;
typedef pcl::PointXYZINormal PointXYZINormal;
typedef pcl::PointCloud <PointXYZINormal> CloudXYZINormal;
typedef CloudXYZINormal::Ptr CloudXYZINormalPtr;
typedef CloudXYZINormal::ConstPtr CloudXYZINormalConstPtr;

typedef pcl::ihs::Mesh Mesh;
typedef pcl::ihs::MeshPtr MeshPtr;
Expand All @@ -124,7 +124,7 @@ namespace pcl
typedef boost::shared_ptr <Integration> IntegrationPtr;
typedef boost::shared_ptr <const Integration> IntegrationConstPtr;

typedef pcl::IntegralImageNormalEstimation <PointXYZRGBA, PointXYZRGBNormal> NormalEstimation;
typedef pcl::IntegralImageNormalEstimation <PointXYZI, PointXYZINormal> NormalEstimation;
typedef boost::shared_ptr <NormalEstimation> NormalEstimationPtr;
typedef boost::shared_ptr <const NormalEstimation> NormalEstimationConstPtr;

Expand Down Expand Up @@ -173,7 +173,7 @@ namespace pcl
*/
bool
load (const std::string& filename,
CloudXYZRGBNormalPtr& cloud,
CloudXYZINormalPtr& cloud,
Eigen::Matrix4f& T) const;

/** \see http://doc.qt.digia.com/qt/qwidget.html#paintEvent
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,10 +110,10 @@ namespace pcl

public:

typedef pcl::PointXYZRGBNormal PointXYZRGBNormal;
typedef pcl::PointCloud <PointXYZRGBNormal> CloudXYZRGBNormal;
typedef CloudXYZRGBNormal::Ptr CloudXYZRGBNormalPtr;
typedef CloudXYZRGBNormal::ConstPtr CloudXYZRGBNormalConstPtr;
typedef pcl::PointXYZINormal PointXYZINormal;
typedef pcl::PointCloud <PointXYZINormal> CloudXYZINormal;
typedef CloudXYZINormal::Ptr CloudXYZINormalPtr;
typedef CloudXYZINormal::ConstPtr CloudXYZINormalConstPtr;

typedef pcl::ihs::Mesh Mesh;
typedef pcl::ihs::MeshPtr MeshPtr;
Expand Down Expand Up @@ -193,7 +193,7 @@ namespace pcl
* \note This method takes some time for the conversion).
*/
bool
addMesh (const CloudXYZRGBNormalConstPtr& cloud, const std::string& id, const Eigen::Isometry3d& T = Eigen::Isometry3d::Identity ());
addMesh (const CloudXYZINormalConstPtr& cloud, const std::string& id, const Eigen::Isometry3d& T = Eigen::Isometry3d::Identity ());

/** \brief Remove the mesh with the given id.
* \param[in] id Identifier of the mesh (results in a failure if the id does not exist).
Expand Down Expand Up @@ -331,7 +331,7 @@ namespace pcl
typedef Eigen::Matrix <unsigned char, 3, Eigen::Dynamic> Colors;
typedef Eigen::Matrix <unsigned char, 3, 256 > Colormap;

typedef boost::unordered_map <std::string, CloudXYZRGBNormalPtr> CloudXYZRGBNormalMap;
typedef boost::unordered_map <std::string, CloudXYZINormalPtr> CloudXYZINormalMap;

typedef pcl::ihs::PointIHS PointIHS;
typedef pcl::ihs::CloudIHS CloudIHS;
Expand Down
6 changes: 3 additions & 3 deletions apps/in_hand_scanner/src/icp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ pcl::ihs::ICP::getMaxAngle () const

bool
pcl::ihs::ICP::findTransformation (const MeshConstPtr& mesh_model,
const CloudXYZRGBNormalConstPtr& cloud_data,
const CloudXYZINormalConstPtr& cloud_data,
const Eigen::Matrix4f& T_init,
Eigen::Matrix4f& T_final)
{
Expand Down Expand Up @@ -399,12 +399,12 @@ pcl::ihs::ICP::selectModelPoints (const MeshConstPtr& mesh_model,
////////////////////////////////////////////////////////////////////////////////

pcl::ihs::ICP::CloudNormalConstPtr
pcl::ihs::ICP::selectDataPoints (const CloudXYZRGBNormalConstPtr& cloud_data) const
pcl::ihs::ICP::selectDataPoints (const CloudXYZINormalConstPtr& cloud_data) const
{
const CloudNormalPtr cloud_data_out (new CloudNormal ());
cloud_data_out->reserve (cloud_data->size ());

CloudXYZRGBNormal::const_iterator it_in = cloud_data->begin ();
CloudXYZINormal::const_iterator it_in = cloud_data->begin ();
for (; it_in!=cloud_data->end (); ++it_in)
{
if (!boost::math::isnan (it_in->x))
Expand Down
14 changes: 7 additions & 7 deletions apps/in_hand_scanner/src/in_hand_scanner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,7 @@ pcl::ihs::InHandScanner::keyPressEvent (QKeyEvent* event)
////////////////////////////////////////////////////////////////////////////////

void
pcl::ihs::InHandScanner::newDataCallback (const CloudXYZRGBAConstPtr& cloud_in)
pcl::ihs::InHandScanner::newDataCallback (const CloudXYZIConstPtr& cloud_in)
{
Base::calcFPS (computation_fps_); // Must come before the lock!

Expand All @@ -295,11 +295,11 @@ pcl::ihs::InHandScanner::newDataCallback (const CloudXYZRGBAConstPtr& cloud_in)
pcl::StopWatch sw;

// Input data processing
CloudXYZRGBNormalPtr cloud_data;
CloudXYZRGBNormalPtr cloud_discarded;
CloudXYZINormalPtr cloud_data;
CloudXYZINormalPtr cloud_discarded;
if (running_mode_ == RM_SHOW_MODEL)
{
cloud_data = CloudXYZRGBNormalPtr (new CloudXYZRGBNormal ());
cloud_data = CloudXYZINormalPtr (new CloudXYZINormal ());
}
else if (running_mode_ == RM_UNPROCESSED)
{
Expand Down Expand Up @@ -332,7 +332,7 @@ pcl::ihs::InHandScanner::newDataCallback (const CloudXYZRGBAConstPtr& cloud_in)
<< " - time reconstruct mesh : "
<< std::setw (8) << std::right << sw.getTime () << " ms\n";

cloud_data = CloudXYZRGBNormalPtr (new CloudXYZRGBNormal ());
cloud_data = CloudXYZINormalPtr (new CloudXYZINormal ());
++iteration_;
}
else
Expand Down Expand Up @@ -364,7 +364,7 @@ pcl::ihs::InHandScanner::newDataCallback (const CloudXYZRGBAConstPtr& cloud_in)
std::cerr << " - time mesh processing : "
<< std::setw (8) << std::right << sw.getTime () << " ms\n";

cloud_data = CloudXYZRGBNormalPtr (new CloudXYZRGBNormal ());
cloud_data = CloudXYZINormalPtr (new CloudXYZINormal ());
++iteration_;
}
}
Expand Down Expand Up @@ -488,7 +488,7 @@ pcl::ihs::InHandScanner::startGrabberImpl ()
lock.lock ();
if (destructor_called_) return;

boost::function <void (const CloudXYZRGBAConstPtr&)> new_data_cb = boost::bind (&pcl::ihs::InHandScanner::newDataCallback, this, _1);
boost::function <void (const CloudXYZIConstPtr&)> new_data_cb = boost::bind (&pcl::ihs::InHandScanner::newDataCallback, this, _1);
new_data_connection_ = grabber_->registerCallback (new_data_cb);
grabber_->start ();

Expand Down
Loading

0 comments on commit 26e89bc

Please sign in to comment.