Skip to content

Commit

Permalink
Fix some implicit-widening-of-multiplication-result warnings (#6138)
Browse files Browse the repository at this point in the history
* Fix some implicit-widening-of-multiplication-result warnings
See https://clang.llvm.org/extra/clang-tidy/checks/bugprone/implicit-widening-of-multiplication-result.html

I applied the following rules of thumb:
- use point_cloud.resize(width, height) instead of point_cloud.resize(width*height)
- cast factors to `std::size_t` if multiplication result would be cast to `std::size_t` later anyway (e.g. used for vector.resize, vector.reserve, vector[])
- change some variables to type `std::size_t` if they otherwise had to be cast repeatedly

We actually had some reports in the past where people were working with large point types (at least 32 bytes per point) and a large number of points, so that (bytes per point)*(height)*(width) would overflow if done in 32 bit types (e.g. when accessing the binary data in PCLPointCloud2). Fixing the implicit-widening-of-multiplication-result warnings would prevent such kinds of problems.

* Resolve ambiguous call to resize (if uindex_t != uint32_t)
  • Loading branch information
mvieth authored Sep 20, 2024
1 parent 9f6b2dc commit 3b44145
Show file tree
Hide file tree
Showing 18 changed files with 56 additions and 64 deletions.
4 changes: 1 addition & 3 deletions 2d/include/pcl/2d/impl/edge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -259,9 +259,7 @@ Edge<PointInT, PointOutT>::suppressNonMaxima(
const int height = edges.height;
const int width = edges.width;

maxima.height = height;
maxima.width = width;
maxima.resize(height * width);
maxima.resize(edges.width, edges.height);

for (auto& point : maxima)
point.intensity = 0.0f;
Expand Down
4 changes: 1 addition & 3 deletions common/include/pcl/common/impl/generate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -276,9 +276,7 @@ CloudGenerator<pcl::PointXY, GeneratorT>::fill (int width, int height, pcl::Poin
if (!cloud.empty ())
PCL_WARN ("[pcl::common::CloudGenerator] Cloud data will be erased with new data\n!");

cloud.width = width;
cloud.height = height;
cloud.resize (cloud.width * cloud.height);
cloud.resize (width, height);
cloud.is_dense = true;

for (auto &point : cloud)
Expand Down
2 changes: 1 addition & 1 deletion common/include/pcl/range_image/impl/range_image.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -194,7 +194,7 @@ RangeImage::createFromPointCloudWithKnownSize (const PointCloudType& point_cloud
image_offset_y_ = (std::max) (0, center_pixel_y-pixel_radius_y);

points.clear ();
points.resize (width*height, unobserved_point);
points.resize (static_cast<std::size_t>(width)*static_cast<std::size_t>(height), unobserved_point);

int top=height, right=-1, bottom=-1, left=width;
doZBuffer (point_cloud, noise_level, min_range, top, right, bottom, left);
Expand Down
4 changes: 2 additions & 2 deletions common/src/PCLPointCloud2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,13 +146,13 @@ pcl::PCLPointCloud2::concatenate (pcl::PCLPointCloud2 &cloud1, const pcl::PCLPoi
}
const auto data1_size = cloud1.data.size ();
cloud1.data.resize(data1_size + cloud2.data.size ());
for (uindex_t cp = 0; cp < size2; ++cp)
for (std::size_t cp = 0; cp < size2; ++cp)
{
for (const auto& field_data: valid_fields)
{
const auto& i = field_data.idx1;
const auto& j = field_data.idx2;
const auto& size = field_data.size;
const std::size_t size = field_data.size;
// Leave the data for the skip fields untouched in cloud1
// Copy only the required data from cloud2 to the correct location for cloud1
memcpy (reinterpret_cast<char*> (&cloud1.data[data1_size + cp * cloud1.point_step + cloud1.fields[i].offset]),
Expand Down
8 changes: 2 additions & 6 deletions common/src/gaussian.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,9 +145,7 @@ pcl::GaussianKernel::convolveRows (const pcl::PointCloud<float>& input,
{
if (output.height < input.height || output.width < input.width)
{
output.width = input.width;
output.height = input.height;
output.resize (input.height * input.width);
output.resize (static_cast<uindex_t>(input.width), static_cast<uindex_t>(input.height)); // Casting is necessary to resolve ambiguous call to resize
}
unaliased_input = &input;
}
Expand Down Expand Up @@ -189,9 +187,7 @@ pcl::GaussianKernel::convolveCols (const pcl::PointCloud<float>& input,
{
if (output.height < input.height || output.width < input.width)
{
output.width = input.width;
output.height = input.height;
output.resize (input.height * input.width);
output.resize (static_cast<uindex_t>(input.width), static_cast<uindex_t>(input.height)); // Casting is necessary to resolve ambiguous call to resize
}
unaliased_input = &input;
}
Expand Down
17 changes: 9 additions & 8 deletions common/src/io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1,

//the total size of extra data should be the size of data per point
//multiplied by the total number of points in the cloud
std::uint32_t cloud1_unique_data_size = cloud1_unique_point_step * cloud1.width * cloud1.height;
const std::size_t cloud1_unique_data_size = static_cast<std::size_t>(cloud1_unique_point_step) * cloud1.width * cloud1.height;

// Point step must increase with the length of each matching field
cloud_out.point_step = cloud2.point_step + cloud1_unique_point_step;
Expand All @@ -177,8 +177,9 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1,
}

// Iterate over each point and perform the appropriate memcpys
int point_offset = 0;
for (uindex_t cp = 0; cp < cloud_out.width * cloud_out.height; ++cp)
std::size_t point_offset = 0;
const std::size_t npts = static_cast<std::size_t>(cloud_out.width) * static_cast<std::size_t>(cloud_out.height);
for (std::size_t cp = 0; cp < npts; ++cp)
{
memcpy (&cloud_out.data[point_offset], &cloud2.data[cp * cloud2.point_step], cloud2.point_step);
int field_offset = cloud2.point_step;
Expand Down Expand Up @@ -231,7 +232,7 @@ pcl::getPointCloudAsEigen (const pcl::PCLPointCloud2 &in, Eigen::MatrixXf &out)
return (false);
}

std::size_t npts = in.width * in.height;
std::size_t npts = static_cast<std::size_t>(in.width) * static_cast<std::size_t>(in.height);
out = Eigen::MatrixXf::Ones (4, npts);

Eigen::Array4i xyz_offset (in.fields[x_idx].offset, in.fields[y_idx].offset, in.fields[z_idx].offset, 0);
Expand Down Expand Up @@ -313,11 +314,11 @@ pcl::copyPointCloud (
cloud_out.row_step = cloud_in.point_step * static_cast<std::uint32_t> (indices.size ());
cloud_out.is_dense = cloud_in.is_dense;

cloud_out.data.resize (cloud_out.width * cloud_out.height * cloud_out.point_step);
cloud_out.data.resize (static_cast<std::size_t>(cloud_out.width) * static_cast<std::size_t>(cloud_out.height) * static_cast<std::size_t>(cloud_out.point_step));

// Iterate over each point
for (std::size_t i = 0; i < indices.size (); ++i)
memcpy (&cloud_out.data[i * cloud_out.point_step], &cloud_in.data[indices[i] * cloud_in.point_step], cloud_in.point_step);
memcpy (&cloud_out.data[i * cloud_out.point_step], &cloud_in.data[static_cast<std::size_t>(indices[i]) * cloud_in.point_step], cloud_in.point_step);
}

//////////////////////////////////////////////////////////////////////////
Expand All @@ -336,11 +337,11 @@ pcl::copyPointCloud (
cloud_out.row_step = cloud_in.point_step * static_cast<std::uint32_t> (indices.size ());
cloud_out.is_dense = cloud_in.is_dense;

cloud_out.data.resize (cloud_out.width * cloud_out.height * cloud_out.point_step);
cloud_out.data.resize (static_cast<std::size_t>(cloud_out.width) * cloud_out.height * cloud_out.point_step);

// Iterate over each point
for (std::size_t i = 0; i < indices.size (); ++i)
memcpy (&cloud_out.data[i * cloud_out.point_step], &cloud_in.data[indices[i] * cloud_in.point_step], cloud_in.point_step);
memcpy (&cloud_out.data[i * cloud_out.point_step], &cloud_in.data[static_cast<std::size_t>(indices[i]) * cloud_in.point_step], cloud_in.point_step);
}

////////////////////////////////////////////////////////////////////////////////
Expand Down
4 changes: 2 additions & 2 deletions common/src/pcl_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,12 +114,12 @@ pcl::PCLBase<pcl::PCLPointCloud2>::initCompute ()
}

// If we have a set of fake indices, but they do not match the number of points in the cloud, update them
if (fake_indices_ && indices_->size () != (input_->width * input_->height))
if (fake_indices_ && indices_->size () != (static_cast<std::size_t>(input_->width) * static_cast<std::size_t>(input_->height)))
{
const auto indices_size = indices_->size ();
try
{
indices_->resize (input_->width * input_->height);
indices_->resize (static_cast<std::size_t>(input_->width) * static_cast<std::size_t>(input_->height));
}
catch (const std::bad_alloc&)
{
Expand Down
10 changes: 5 additions & 5 deletions common/src/range_image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,7 @@ RangeImage::cropImage (int borderSize, int top, int right, int bottom, int left)
width = right-left+1; height = bottom-top+1;
image_offset_x_ = left+oldRangeImage.image_offset_x_;
image_offset_y_ = top+oldRangeImage.image_offset_y_;
points.resize (width*height);
points.resize (static_cast<std::size_t>(width)*static_cast<std::size_t>(height));

//std::cout << oldRangeImage.width<<"x"<<oldRangeImage.height<<" -> "<<width<<"x"<<height<<"\n";

Expand Down Expand Up @@ -289,9 +289,9 @@ RangeImage::getRangesArray () const
void
RangeImage::getIntegralImage (float*& integral_image, int*& valid_points_num_image) const
{
integral_image = new float[width*height];
integral_image = new float[static_cast<std::size_t>(width)*static_cast<std::size_t>(height)];
float* integral_image_ptr = integral_image;
valid_points_num_image = new int[width*height];
valid_points_num_image = new int[static_cast<std::size_t>(width)*static_cast<std::size_t>(height)];
int* valid_points_num_image_ptr = valid_points_num_image;
for (int y = 0; y < static_cast<int> (height); ++y)
{
Expand Down Expand Up @@ -350,7 +350,7 @@ RangeImage::getHalfImage (RangeImage& half_image) const
half_image.height = height/2;
half_image.is_dense = is_dense;
half_image.clear ();
half_image.resize (half_image.width*half_image.height);
half_image.resize (half_image.width, half_image.height);

int src_start_x = 2*half_image.image_offset_x_ - image_offset_x_,
src_start_y = 2*half_image.image_offset_y_ - image_offset_y_;
Expand Down Expand Up @@ -394,7 +394,7 @@ RangeImage::getSubImage (int sub_image_image_offset_x, int sub_image_image_offse
sub_image.height = sub_image_height;
sub_image.is_dense = is_dense;
sub_image.clear ();
sub_image.resize (sub_image.width*sub_image.height);
sub_image.resize (sub_image.width, sub_image.height);

int src_start_x = combine_pixels*sub_image.image_offset_x_ - image_offset_x_,
src_start_y = combine_pixels*sub_image.image_offset_y_ - image_offset_y_;
Expand Down
6 changes: 3 additions & 3 deletions common/src/range_image_planar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ namespace pcl
focal_length_x_reciprocal_ = focal_length_y_reciprocal_ = 1.0f / focal_length_x_;
center_x_ = static_cast<float> (di_width) / static_cast<float> (2 * skip);
center_y_ = static_cast<float> (di_height) / static_cast<float> (2 * skip);
points.resize (width*height);
points.resize (static_cast<std::size_t>(width)*static_cast<std::size_t>(height));

//std::cout << PVARN (*this);

Expand Down Expand Up @@ -130,7 +130,7 @@ namespace pcl
focal_length_y_reciprocal_ = 1.0f / focal_length_y_;
center_x_ = static_cast<float> (di_center_x) / static_cast<float> (skip);
center_y_ = static_cast<float> (di_center_y) / static_cast<float> (skip);
points.resize (width * height);
points.resize (static_cast<std::size_t>(width) * static_cast<std::size_t>(height));

for (int y=0; y < static_cast<int> (height); ++y)
{
Expand Down Expand Up @@ -176,7 +176,7 @@ namespace pcl
focal_length_y_reciprocal_ = 1.0f / focal_length_y_;
center_x_ = static_cast<float> (di_center_x) / static_cast<float> (skip);
center_y_ = static_cast<float> (di_center_y) / static_cast<float> (skip);
points.resize (width * height);
points.resize (static_cast<std::size_t>(width) * static_cast<std::size_t>(height));

for (int y = 0; y < static_cast<int> (height); ++y)
{
Expand Down
4 changes: 1 addition & 3 deletions examples/common/example_organized_point_cloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,8 @@ main ()
CloudType::Ptr cloud (new CloudType);

// Make the cloud a 10x10 grid
cloud->height = 10;
cloud->width = 10;
cloud->is_dense = true;
cloud->resize(cloud->height * cloud->width);
cloud->resize(10, 10);

// Output the (0,0) point
std::cout << (*cloud)(0,0) << std::endl;
Expand Down
2 changes: 1 addition & 1 deletion examples/segmentation/example_supervoxels.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -194,7 +194,7 @@ main (int argc, char ** argv)
return (1);
}

cloud->points.reserve (depth_dims[0] * depth_dims[1]);
cloud->reserve (static_cast<std::size_t>(depth_dims[0]) * static_cast<std::size_t>(depth_dims[1]));
cloud->width = depth_dims[0];
cloud->height = depth_dims[1];
cloud->is_dense = false;
Expand Down
10 changes: 5 additions & 5 deletions features/include/pcl/features/impl/brisk_2d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::generateKernel (
points_ += number;

// set up the patterns
pattern_points_ = new BriskPatternPoint[points_*scales_*n_rot_];
pattern_points_ = new BriskPatternPoint[static_cast<std::size_t>(points_)*static_cast<std::size_t>(scales_)*static_cast<std::size_t>(n_rot_)];
BriskPatternPoint* pattern_iterator = pattern_points_;

// define the scale discretization:
Expand Down Expand Up @@ -223,7 +223,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
const float yf = brisk_point.y + key_y;
const int x = static_cast<int>(xf);
const int y = static_cast<int>(yf);
const int& imagecols = image_width;
const std::ptrdiff_t imagecols = image_width;

// get the sigma:
const float sigma_half = brisk_point.sigma;
Expand Down Expand Up @@ -271,7 +271,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::smoothedIntensity
const int scaling2 = static_cast<int> (static_cast<float>(scaling) * area / 1024.0f);

// the integral image is larger:
const int integralcols = imagecols + 1;
const std::ptrdiff_t integralcols = image_width + 1;

// calculate borders
const float x_1 = xf - sigma_half;
Expand Down Expand Up @@ -450,7 +450,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (
const auto height = static_cast<index_t>(input_cloud_->height);

// destination for intensity data; will be forwarded to BRISK
std::vector<unsigned char> image_data (width*height);
std::vector<unsigned char> image_data (static_cast<std::size_t>(width)*static_cast<std::size_t>(height));

for (std::size_t i = 0; i < image_data.size (); ++i)
image_data[i] = static_cast<unsigned char> (intensity_ ((*input_cloud_)[i]));
Expand Down Expand Up @@ -512,7 +512,7 @@ BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT>::compute (

// first, calculate the integral image over the whole image:
// current integral image
std::vector<int> integral ((width+1)*(height+1), 0); // the integral image
std::vector<int> integral (static_cast<std::size_t>(width+1)*static_cast<std::size_t>(height+1), 0); // the integral image

for (index_t row_index = 1; row_index < height; ++row_index)
{
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/impl/esf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ pcl::ESFEstimation<PointInT, PointOutT>::computeESF (
PointCloudIn &pc, std::vector<float> &hist)
{
const int binsize = 64;
unsigned int sample_size = 20000;
const std::size_t sample_size = 20000;
// @TODO: Replace with c++ stdlib uniform_random_generator
srand (static_cast<unsigned int> (time (nullptr)));
const auto maxindex = pc.size ();
Expand Down Expand Up @@ -269,7 +269,7 @@ pcl::ESFEstimation<PointInT, PointOutT>::computeESF (
//float weights[10] = {1, 1, 1, 1, 1, 1, 1, 1 , 1 , 1};
float weights[10] = {0.5f, 0.5f, 0.5f, 0.5f, 0.5f, 1.0f, 1.0f, 2.0f, 2.0f, 2.0f};

hist.reserve (binsize * 10);
hist.reserve (static_cast<std::size_t>(binsize) * 10);
for (const float &i : h_a3_in)
hist.push_back (i * weights[0]);
for (const float &i : h_a3_out)
Expand Down
14 changes: 8 additions & 6 deletions features/include/pcl/features/impl/integral_image2D.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,11 @@ IntegralImage2D<DataType, Dimension>::setInput (const DataType * data, unsigned
{
width_ = width;
height_ = height;
first_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
finite_values_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
const std::size_t ii_size = static_cast<std::size_t>(width_ + 1) * static_cast<std::size_t>(height_ + 1);
first_order_integral_image_.resize (ii_size);
finite_values_integral_image_.resize (ii_size);
if (compute_second_order_integral_images_)
second_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
second_order_integral_image_.resize (ii_size);
}
computeIntegralImages (data, row_stride, element_stride);
}
Expand Down Expand Up @@ -230,10 +231,11 @@ IntegralImage2D<DataType, 1>::setInput (const DataType * data, unsigned width,un
{
width_ = width;
height_ = height;
first_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
finite_values_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
const std::size_t ii_size = static_cast<std::size_t>(width_ + 1) * static_cast<std::size_t>(height_ + 1);
first_order_integral_image_.resize (ii_size);
finite_values_integral_image_.resize (ii_size);
if (compute_second_order_integral_images_)
second_order_integral_image_.resize ( (width_ + 1) * (height_ + 1) );
second_order_integral_image_.resize (ii_size);
}
computeIntegralImages (data, row_stride, element_stride);
}
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/pfh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ pcl::PFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut
std::queue<std::pair<int, int> > empty;
std::swap (key_list_, empty);

pfh_histogram_.setZero (nr_subdiv_ * nr_subdiv_ * nr_subdiv_);
pfh_histogram_.setZero (static_cast<Eigen::Index>(nr_subdiv_) * nr_subdiv_ * nr_subdiv_);

// Allocate enough space to hold the results
// \note This resize is irrelevant for a radiusSearch ().
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/pfhrgb.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ template <typename PointInT, typename PointNT, typename PointOutT> void
pcl::PFHRGBEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
{
/// nr_subdiv^3 for RGB and nr_subdiv^3 for the angular features
pfhrgb_histogram_.setZero (2 * nr_subdiv_ * nr_subdiv_ * nr_subdiv_);
pfhrgb_histogram_.setZero (static_cast<Eigen::Index>(2) * nr_subdiv_ * nr_subdiv_ * nr_subdiv_);
pfhrgb_tuple_.setZero (7);

// Allocate enough space to hold the results
Expand Down
10 changes: 5 additions & 5 deletions features/src/narf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,9 +109,9 @@ Narf::deepCopy (const Narf& other)
{
surface_patch_pixel_size_ = other.surface_patch_pixel_size_;
delete[] surface_patch_;
surface_patch_ = new float[surface_patch_pixel_size_*surface_patch_pixel_size_];
surface_patch_ = new float[static_cast<std::size_t>(surface_patch_pixel_size_)*static_cast<std::size_t>(surface_patch_pixel_size_)];
}
std::copy(other.surface_patch_, other.surface_patch_ + surface_patch_pixel_size_*surface_patch_pixel_size_, surface_patch_);
std::copy(other.surface_patch_, other.surface_patch_ + static_cast<ptrdiff_t>(surface_patch_pixel_size_)*static_cast<ptrdiff_t>(surface_patch_pixel_size_), surface_patch_);
surface_patch_world_size_ = other.surface_patch_world_size_;
surface_patch_rotation_ = other.surface_patch_rotation_;

Expand Down Expand Up @@ -521,7 +521,7 @@ Narf::saveBinary (std::ostream& file) const
pcl::saveBinary(transformation_.matrix(), file);
file.write(reinterpret_cast<const char*>(&surface_patch_pixel_size_), sizeof(surface_patch_pixel_size_));
file.write(reinterpret_cast<const char*>(surface_patch_),
surface_patch_pixel_size_*surface_patch_pixel_size_*sizeof(*surface_patch_));
sizeof(*surface_patch_)*surface_patch_pixel_size_*surface_patch_pixel_size_);
file.write(reinterpret_cast<const char*>(&surface_patch_world_size_), sizeof(surface_patch_world_size_));
file.write(reinterpret_cast<const char*>(&surface_patch_rotation_), sizeof(surface_patch_rotation_));
file.write(reinterpret_cast<const char*>(&descriptor_size_), sizeof(descriptor_size_));
Expand Down Expand Up @@ -573,9 +573,9 @@ Narf::loadBinary (std::istream& file)
pcl::loadBinary(position_.matrix(), file);
pcl::loadBinary(transformation_.matrix(), file);
file.read(reinterpret_cast<char*>(&surface_patch_pixel_size_), sizeof(surface_patch_pixel_size_));
surface_patch_ = new float[surface_patch_pixel_size_*surface_patch_pixel_size_];
surface_patch_ = new float[static_cast<std::size_t>(surface_patch_pixel_size_)*static_cast<std::size_t>(surface_patch_pixel_size_)];
file.read(reinterpret_cast<char*>(surface_patch_),
surface_patch_pixel_size_*surface_patch_pixel_size_*sizeof(*surface_patch_));
sizeof(*surface_patch_)*surface_patch_pixel_size_*surface_patch_pixel_size_);
file.read(reinterpret_cast<char*>(&surface_patch_world_size_), sizeof(surface_patch_world_size_));
file.read(reinterpret_cast<char*>(&surface_patch_rotation_), sizeof(surface_patch_rotation_));
file.read(reinterpret_cast<char*>(&descriptor_size_), sizeof(descriptor_size_));
Expand Down
Loading

0 comments on commit 3b44145

Please sign in to comment.