Skip to content

Commit

Permalink
Use std::uint* types. (#264)
Browse files Browse the repository at this point in the history
  • Loading branch information
mikepurvis authored Feb 25, 2020
1 parent e8f8a92 commit 8e2543a
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 19 deletions.
18 changes: 9 additions & 9 deletions pcl_conversions/include/pcl_conversions/pcl_conversions.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,29 +77,29 @@ namespace pcl_conversions {
/** PCLHeader <=> Header **/

inline
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
void fromPCL(const std::uint64_t &pcl_stamp, ros::Time &stamp)
{
stamp.fromNSec(pcl_stamp * 1000ull); // Convert from us to ns
}

inline
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
{
pcl_stamp = stamp.toNSec() / 1000ull; // Convert from ns to us
}

inline
ros::Time fromPCL(const pcl::uint64_t &pcl_stamp)
ros::Time fromPCL(const std::uint64_t &pcl_stamp)
{
ros::Time stamp;
fromPCL(pcl_stamp, stamp);
return stamp;
}

inline
pcl::uint64_t toPCL(const ros::Time &stamp)
std::uint64_t toPCL(const ros::Time &stamp)
{
pcl::uint64_t pcl_stamp;
std::uint64_t pcl_stamp;
toPCL(stamp, pcl_stamp);
return pcl_stamp;
}
Expand Down Expand Up @@ -520,14 +520,14 @@ namespace pcl {

// sensor_msgs::image_encodings::BGR8;
msg.encoding = "bgr8";
msg.step = msg.width * sizeof (uint8_t) * 3;
msg.step = msg.width * sizeof (std::uint8_t) * 3;
msg.data.resize (msg.step * msg.height);
for (size_t y = 0; y < cloud.height; y++)
{
for (size_t x = 0; x < cloud.width; x++)
{
uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(uint8_t));
std::uint8_t * pixel = &(msg.data[y * msg.step + x * 3]);
memcpy (pixel, &cloud (x, y).rgb, 3 * sizeof(std::uint8_t));
}
}
}
Expand Down Expand Up @@ -822,7 +822,7 @@ namespace ros
length += 4; // point_step
length += 4; // row_step
length += 4; // data's size
length += m.data.size() * sizeof(pcl::uint8_t);
length += m.data.size() * sizeof(std::uint8_t);
length += 1; // is_dense

return length;
Expand Down
2 changes: 1 addition & 1 deletion pcl_conversions/test/test_pcl_conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ struct StampTestData
explicit StampTestData(const ros::Time &stamp)
: stamp_(stamp)
{
pcl::uint64_t pcl_stamp;
std::uint64_t pcl_stamp;
pcl_conversions::toPCL(stamp_, pcl_stamp);
pcl_conversions::fromPCL(pcl_stamp, stamp2_);
}
Expand Down
12 changes: 6 additions & 6 deletions pcl_ros/include/pcl_ros/point_cloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,18 +23,18 @@ namespace pcl
template<typename U> void operator() ()
{
const char* name = traits::name<PointT, U>::value;
uint32_t name_length = strlen(name);
std::uint32_t name_length = strlen(name);
stream_.next(name_length);
if (name_length > 0)
memcpy(stream_.advance(name_length), name, name_length);

uint32_t offset = traits::offset<PointT, U>::value;
std::uint32_t offset = traits::offset<PointT, U>::value;
stream_.next(offset);

uint8_t datatype = traits::datatype<PointT, U>::value;
std::uint8_t datatype = traits::datatype<PointT, U>::value;
stream_.next(datatype);

uint32_t count = traits::datatype<PointT, U>::size;
std::uint32_t count = traits::datatype<PointT, U>::size;
stream_.next(count);
}

Expand All @@ -48,11 +48,11 @@ namespace pcl

template<typename U> void operator() ()
{
uint32_t name_length = strlen(traits::name<PointT, U>::value);
std::uint32_t name_length = strlen(traits::name<PointT, U>::value);
length += name_length + 13;
}

uint32_t length;
std::uint32_t length;
};
} // namespace pcl::detail
} // namespace pcl
Expand Down
6 changes: 3 additions & 3 deletions pcl_ros/src/test/test_tf_message_filter_pcl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ typedef pcl::PointCloud<pcl::PointXYZRGBNormal> PCDType;
/// Sets pcl_stamp from stamp, BUT alters stamp
/// a little to round it to millisecond. This is because converting back
/// and forth from pcd to ros time induces some rounding errors.
void setStamp(ros::Time &stamp, pcl::uint64_t &pcl_stamp)
void setStamp(ros::Time &stamp, std::uint64_t &pcl_stamp)
{
// round to millisecond
static const uint32_t mult = 1e6;
Expand Down Expand Up @@ -187,7 +187,7 @@ TEST(MessageFilter, queueSize)
filter.registerFailureCallback(boost::bind(&Notification::failure, &n, _1, _2));

ros::Time stamp = ros::Time::now();
pcl::uint64_t pcl_stamp;
std::uint64_t pcl_stamp;
setStamp(stamp, pcl_stamp);

for (int i = 0; i < 20; ++i)
Expand Down Expand Up @@ -281,7 +281,7 @@ TEST(MessageFilter, tolerance)
filter.setTolerance(offset);

ros::Time stamp = ros::Time::now();
pcl::uint64_t pcl_stamp;
std::uint64_t pcl_stamp;
setStamp(stamp, pcl_stamp);
tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1", "frame2");
tf_client.setTransform(transform);
Expand Down

0 comments on commit 8e2543a

Please sign in to comment.