Skip to content

Commit

Permalink
Compilation for VS2008
Browse files Browse the repository at this point in the history
  • Loading branch information
oposniak committed Mar 25, 2013
1 parent 0ae4bdc commit 05b05c1
Show file tree
Hide file tree
Showing 8 changed files with 29 additions and 27 deletions.
2 changes: 1 addition & 1 deletion apps/src/openni_organized_edge_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@ class OpenNIOrganizedEdgeDetection
// Make gray point cloud
for (size_t idx = 0; idx < cloud_.points.size (); idx++)
{
uint8_t gray = uint8_t((cloud_.points[idx].r + cloud_.points[idx].g + cloud_.points[idx].b)/3);
pcl::uint8_t gray = pcl::uint8_t((cloud_.points[idx].r + cloud_.points[idx].g + cloud_.points[idx].b)/3);
cloud_.points[idx].r = cloud_.points[idx].g = cloud_.points[idx].b = gray;
}

Expand Down
4 changes: 2 additions & 2 deletions apps/src/openni_tracking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -503,7 +503,7 @@ class OpenNISegmentTracking
result.points.push_back(point);
}

result.width = static_cast<uint32_t> (result.points.size ());
result.width = static_cast<pcl::uint32_t> (result.points.size ());
result.height = 1;
result.is_dense = true;
}
Expand All @@ -519,7 +519,7 @@ class OpenNISegmentTracking
PointType point = cloud->points[segmented_indices.indices[i]];
result.points.push_back (point);
}
result.width = uint32_t (result.points.size ());
result.width = pcl::uint32_t (result.points.size ());
result.height = 1;
result.is_dense = true;
}
Expand Down
8 changes: 4 additions & 4 deletions apps/src/stereo_ground_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -277,7 +277,7 @@ class HRCSSegmentation
cloud->points[region_indices[i].indices[j]].y,
cloud->points[region_indices[i].indices[j]].z);
ground_cloud->points.push_back (ground_pt);
ground_image->points[region_indices[i].indices[j]].g = static_cast<uint8_t> ((cloud->points[region_indices[i].indices[j]].g + 255) / 2);
ground_image->points[region_indices[i].indices[j]].g = static_cast<pcl::uint8_t> ((cloud->points[region_indices[i].indices[j]].g + 255) / 2);
label_image->points[region_indices[i].indices[j]].r = 0;
label_image->points[region_indices[i].indices[j]].g = 255;
label_image->points[region_indices[i].indices[j]].b = 0;
Expand Down Expand Up @@ -367,8 +367,8 @@ class HRCSSegmentation
cloud->points[region_indices[i].indices[j]].y,
cloud->points[region_indices[i].indices[j]].z);
ground_cloud->points.push_back (ground_pt);
ground_image->points[region_indices[i].indices[j]].r = static_cast<uint8_t> ((cloud->points[region_indices[i].indices[j]].r + 255) / 2);
ground_image->points[region_indices[i].indices[j]].g = static_cast<uint8_t> ((cloud->points[region_indices[i].indices[j]].g + 255) / 2);
ground_image->points[region_indices[i].indices[j]].r = static_cast<pcl::uint8_t> ((cloud->points[region_indices[i].indices[j]].r + 255) / 2);
ground_image->points[region_indices[i].indices[j]].g = static_cast<pcl::uint8_t> ((cloud->points[region_indices[i].indices[j]].g + 255) / 2);
label_image->points[region_indices[i].indices[j]].r = 128;
label_image->points[region_indices[i].indices[j]].g = 128;
label_image->points[region_indices[i].indices[j]].b = 0;
Expand Down Expand Up @@ -455,7 +455,7 @@ class HRCSSegmentation
{
if (!pcl::isFinite (cloud->points[i]))
{
ground_image->points[i].b = static_cast<uint8_t>((cloud->points[i].b + 255) / 2);
ground_image->points[i].b = static_cast<pcl::uint8_t>((cloud->points[i].b + 255) / 2);
label_image->points[i].r = 0;
label_image->points[i].g = 0;
label_image->points[i].b = 255;
Expand Down
13 changes: 7 additions & 6 deletions common/include/pcl/common/impl/random.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,10 +41,11 @@
#define PCL_COMMON_RANDOM_HPP_

#include <boost/version.hpp>
#include <pcl/pcl_macros.h>

/////////////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T>
pcl::common::UniformGenerator<T>::UniformGenerator(T min, T max, uint32_t seed)
pcl::common::UniformGenerator<T>::UniformGenerator(T min, T max, pcl::uint32_t seed)
: distribution_ (min, max)
, generator_ (rng_, distribution_)
{
Expand All @@ -67,7 +68,7 @@ pcl::common::UniformGenerator<T>::UniformGenerator(const Parameters& parameters)

/////////////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T> void
pcl::common::UniformGenerator<T>::setSeed (uint32_t seed)
pcl::common::UniformGenerator<T>::setSeed (pcl::uint32_t seed)
{
if (seed != -1)
{
Expand All @@ -78,7 +79,7 @@ pcl::common::UniformGenerator<T>::setSeed (uint32_t seed)

/////////////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T> void
pcl::common::UniformGenerator<T>::setParameters (T min, T max, uint32_t seed)
pcl::common::UniformGenerator<T>::setParameters (T min, T max, pcl::uint32_t seed)
{
parameters_.min = min;
parameters_.max = max;
Expand Down Expand Up @@ -117,7 +118,7 @@ pcl::common::UniformGenerator<T>::setParameters (const Parameters& parameters)

/////////////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T>
pcl::common::NormalGenerator<T>::NormalGenerator(T mean, T sigma, uint32_t seed)
pcl::common::NormalGenerator<T>::NormalGenerator(T mean, T sigma, pcl::uint32_t seed)
: distribution_ (mean, sigma)
, generator_ (rng_, distribution_)
{
Expand All @@ -140,7 +141,7 @@ pcl::common::NormalGenerator<T>::NormalGenerator(const Parameters& parameters)

/////////////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T> void
pcl::common::NormalGenerator<T>::setSeed (uint32_t seed)
pcl::common::NormalGenerator<T>::setSeed (pcl::uint32_t seed)
{
if (seed != -1)
{
Expand All @@ -151,7 +152,7 @@ pcl::common::NormalGenerator<T>::setSeed (uint32_t seed)

/////////////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T> void
pcl::common::NormalGenerator<T>::setParameters (T mean, T sigma, uint32_t seed)
pcl::common::NormalGenerator<T>::setParameters (T mean, T sigma, pcl::uint32_t seed)
{
parameters_.mean = mean;
parameters_.sigma = sigma;
Expand Down
21 changes: 11 additions & 10 deletions common/include/pcl/common/random.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@
#include <boost/random/variate_generator.hpp>
#include <boost/random/normal_distribution.hpp>
#include <boost/random/mersenne_twister.hpp>
#include <pcl/pcl_macros.h>

namespace pcl
{
Expand Down Expand Up @@ -87,23 +88,23 @@ namespace pcl
public:
struct Parameters
{
Parameters (T _min = 0, T _max = 1, uint32_t _seed = 1)
Parameters (T _min = 0, T _max = 1, pcl::uint32_t _seed = 1)
: min (_min)
, max (_max)
, seed (_seed)
{}

T min;
T max;
uint32_t seed;
pcl::uint32_t seed;
};

/** Constructor
* \param min: included lower bound
* \param max: included higher bound
* \param seed: seeding value
*/
UniformGenerator(T min = 0, T max = 1, uint32_t seed = -1);
UniformGenerator(T min = 0, T max = 1, pcl::uint32_t seed = -1);

/** Constructor
* \param parameters uniform distribution parameters and generator seed
Expand All @@ -114,15 +115,15 @@ namespace pcl
* \param[in] seed new generator seed value
*/
void
setSeed (uint32_t seed);
setSeed (pcl::uint32_t seed);

/** Set the uniform number generator parameters
* \param[in] min minimum allowed value
* \param[in] max maximum allowed value
* \param[in] seed random number generator seed (applied if != -1)
*/
void
setParameters (T min, T max, uint32_t seed = -1);
setParameters (T min, T max, pcl::uint32_t seed = -1);

/** Set generator parameters
* \param parameters uniform distribution parameters and generator seed
Expand Down Expand Up @@ -162,23 +163,23 @@ namespace pcl
public:
struct Parameters
{
Parameters (T _mean = 0, T _sigma = 1, uint32_t _seed = 1)
Parameters (T _mean = 0, T _sigma = 1, pcl::uint32_t _seed = 1)
: mean (_mean)
, sigma (_sigma)
, seed (_seed)
{}

T mean;
T sigma;
uint32_t seed;
pcl::uint32_t seed;
};

/** Constructor
* \param[in] mean normal mean
* \param[in] sigma normal variation
* \param[in] seed seeding value
*/
NormalGenerator(T mean = 0, T sigma = 1, uint32_t seed = -1);
NormalGenerator(T mean = 0, T sigma = 1, pcl::uint32_t seed = -1);

/** Constructor
* \param parameters normal distribution parameters and seed
Expand All @@ -189,15 +190,15 @@ namespace pcl
* \param[in] seed new seed value
*/
void
setSeed (uint32_t seed);
setSeed (pcl::uint32_t seed);

/** Set the normal number generator parameters
* \param[in] mean mean of the normal distribution
* \param[in] sigma standard variation of the normal distribution
* \param[in] seed random number generator seed (applied if != -1)
*/
void
setParameters (T mean, T sigma, uint32_t seed = -1);
setParameters (T mean, T sigma, pcl::uint32_t seed = -1);

/** Set generator parameters
* \param parameters normal distribution parameters and seed
Expand Down
4 changes: 2 additions & 2 deletions io/tools/hdl_grabber_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,14 +49,14 @@ class SimpleHDLGrabber
static double last = pcl::getTime();

if (sweep->header.seq == 0) {
uint64_t stamp;
pcl::uint64_t stamp;
#ifdef USE_ROS
stamp = sweep->header.stamp.toNSec () / 1000;
#else //USE_ROS
stamp = sweep->header.stamp;
#endif //USE_ROS
time_t systemTime = static_cast<time_t>(((stamp & 0xffffffff00000000l) >> 32) & 0x00000000ffffffff);
uint32_t usec = static_cast<uint32_t>(stamp & 0x00000000ffffffff);
pcl::uint32_t usec = static_cast<pcl::uint32_t>(stamp & 0x00000000ffffffff);
std::cout << std::hex << stamp << " " << ctime(&systemTime) << " usec: " << usec << std::endl;
}

Expand Down
2 changes: 1 addition & 1 deletion tools/mesh_sampling.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ uniform_sampling (vtkSmartPointer<vtkPolyData> polydata, size_t n_samples, pcl::
}

cloud_out.points.resize (n_samples);
cloud_out.width = static_cast<uint32_t> (n_samples);
cloud_out.width = static_cast<pcl::uint32_t> (n_samples);
cloud_out.height = 1;

for (i = 0; i < n_samples; i++)
Expand Down
2 changes: 1 addition & 1 deletion visualization/tools/image_grabber_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ struct EventHelper
void
cloud_cb (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr & cloud)
{
uint64_t timestamp;
pcl::uint64_t timestamp;
#ifdef USE_ROS
timestamp = cloud->header.stamp.toNSec() / 1000; //Microseconds
#else
Expand Down

0 comments on commit 05b05c1

Please sign in to comment.