Skip to content

Commit

Permalink
Merge pull request #3012 from SunBlack/modernize-use-nullptr_io
Browse files Browse the repository at this point in the history
Use nullptr in module io
  • Loading branch information
SergioRAgostinho authored Apr 22, 2019
2 parents 69e5e98 + 939012e commit 0fab882
Show file tree
Hide file tree
Showing 21 changed files with 113 additions and 115 deletions.
2 changes: 1 addition & 1 deletion io/include/pcl/io/grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@ namespace pcl
signals_[typeid (T).name ()] = signal;
return (signal);
}
return (0);
return (nullptr);
}

template<typename T> boost::signals2::connection
Expand Down
6 changes: 3 additions & 3 deletions io/include/pcl/io/impl/pcd_io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,7 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
return (-1);
}

char *map = static_cast<char*> (::mmap (0, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0));
char *map = static_cast<char*> (::mmap (nullptr, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0));
if (map == reinterpret_cast<char*> (-1)) //MAP_FAILED)
{
io::raw_close (fd);
Expand Down Expand Up @@ -384,7 +384,7 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name,
return (-1);
}

char *map = static_cast<char*> (::mmap (0, compressed_final_size, PROT_WRITE, MAP_SHARED, fd, 0));
char *map = static_cast<char*> (::mmap (nullptr, compressed_final_size, PROT_WRITE, MAP_SHARED, fd, 0));
if (map == reinterpret_cast<char*> (-1)) //MAP_FAILED)
{
io::raw_close (fd);
Expand Down Expand Up @@ -663,7 +663,7 @@ pcl::PCDWriter::writeBinary (const std::string &file_name,
return (-1);
}

char *map = static_cast<char*> (::mmap (0, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0));
char *map = static_cast<char*> (::mmap (nullptr, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0));
if (map == reinterpret_cast<char*> (-1)) //MAP_FAILED)
{
io::raw_close (fd);
Expand Down
4 changes: 2 additions & 2 deletions io/include/pcl/io/impl/point_cloud_image_extractors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ pcl::io::PointCloudImageExtractorFromLabelField<PointT>::extractImpl (const Poin
img.step = img.width * sizeof (unsigned char) * 3;
img.data.resize (img.step * img.height);

std::srand(std::time(0));
std::srand(std::time(nullptr));
std::map<uint32_t, size_t> colormap;

for (size_t i = 0; i < cloud.points.size (); ++i)
Expand Down Expand Up @@ -199,7 +199,7 @@ pcl::io::PointCloudImageExtractorFromLabelField<PointT>::extractImpl (const Poin
img.step = img.width * sizeof (unsigned char) * 3;
img.data.resize (img.step * img.height);

std::srand(std::time(0));
std::srand(std::time(nullptr));
std::set<uint32_t> labels;
std::map<uint32_t, size_t> colormap;

Expand Down
2 changes: 1 addition & 1 deletion io/include/pcl/io/openni2/openni2_frame_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ namespace pcl
public:

OpenNI2FrameListener ()
: callback_(0) {}
: callback_() {}
OpenNI2FrameListener (StreamCallbackFunction cb)
: callback_(cb) {}

Expand Down
12 changes: 6 additions & 6 deletions io/include/pcl/io/openni_camera/openni_device.h
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,7 @@ namespace openni_wrapper
* \return a callback handler that can be used to remove the user callback from list of image-stream callbacks.
*/
CallbackHandle
registerImageCallback (const ImageCallbackFunction& callback, void* cookie = NULL) throw ();
registerImageCallback (const ImageCallbackFunction& callback, void* cookie = nullptr) throw ();

/** \brief registers a callback function for the image stream with an optional user defined parameter.
* This version is used to register a member function of any class.
Expand All @@ -295,7 +295,7 @@ namespace openni_wrapper
* \return a callback handler that can be used to remove the user callback from list of image-stream callbacks.
*/
template<typename T> CallbackHandle
registerImageCallback (void (T::*callback)(boost::shared_ptr<Image>, void* cookie), T& instance, void* cookie = NULL) throw ();
registerImageCallback (void (T::*callback)(boost::shared_ptr<Image>, void* cookie), T& instance, void* cookie = nullptr) throw ();

/** \brief unregisters a callback function. i.e. removes that function from the list of image stream callbacks.
* \param[in] callbackHandle the handle of the callback to unregister.
Expand All @@ -312,7 +312,7 @@ namespace openni_wrapper
* \return a callback handler that can be used to remove the user callback from list of depth-stream callbacks.
*/
CallbackHandle
registerDepthCallback (const DepthImageCallbackFunction& callback, void* cookie = NULL) throw ();
registerDepthCallback (const DepthImageCallbackFunction& callback, void* cookie = nullptr) throw ();

/** \brief registers a callback function for the depth stream with an optional user defined parameter.
* This version is used to register a member function of any class.
Expand All @@ -323,7 +323,7 @@ namespace openni_wrapper
* \return a callback handler that can be used to remove the user callback from list of depth-stream callbacks.
*/
template<typename T> CallbackHandle
registerDepthCallback (void (T::*callback)(boost::shared_ptr<DepthImage>, void* cookie), T& instance, void* cookie = NULL) throw ();
registerDepthCallback (void (T::*callback)(boost::shared_ptr<DepthImage>, void* cookie), T& instance, void* cookie = nullptr) throw ();

/** \brief unregisters a callback function. i.e. removes that function from the list of depth stream callbacks.
* \param[in] callbackHandle the handle of the callback to unregister.
Expand All @@ -339,7 +339,7 @@ namespace openni_wrapper
* \return a callback handler that can be used to remove the user callback from list of IR-stream callbacks.
*/
CallbackHandle
registerIRCallback (const IRImageCallbackFunction& callback, void* cookie = NULL) throw ();
registerIRCallback (const IRImageCallbackFunction& callback, void* cookie = nullptr) throw ();

/** \brief registers a callback function for the IR stream with an optional user defined parameter.
* This version is used to register a member function of any class.
Expand All @@ -350,7 +350,7 @@ namespace openni_wrapper
* \return a callback handler that can be used to remove the user callback from list of IR-stream callbacks.
*/
template<typename T> CallbackHandle
registerIRCallback (void (T::*callback)(boost::shared_ptr<IRImage>, void* cookie), T& instance, void* cookie = NULL) throw ();
registerIRCallback (void (T::*callback)(boost::shared_ptr<IRImage>, void* cookie), T& instance, void* cookie = nullptr) throw ();

/** \brief unregisters a callback function. i.e. removes that function from the list of IR stream callbacks.
* \param[in] callbackHandle the handle of the callback to unregister.
Expand Down
8 changes: 4 additions & 4 deletions io/include/pcl/io/ply_io.h
Original file line number Diff line number Diff line change
Expand Up @@ -90,10 +90,10 @@ namespace pcl
, cloud_ ()
, vertex_count_ (0)
, vertex_offset_before_ (0)
, range_grid_ (0)
, range_grid_ (nullptr)
, rgb_offset_before_ (0)
, do_resize_ (false)
, polygons_ (0)
, polygons_ (nullptr)
, r_(0), g_(0), b_(0)
, a_(0), rgba_(0)
{}
Expand All @@ -106,10 +106,10 @@ namespace pcl
, cloud_ ()
, vertex_count_ (0)
, vertex_offset_before_ (0)
, range_grid_ (0)
, range_grid_ (nullptr)
, rgb_offset_before_ (0)
, do_resize_ (false)
, polygons_ (0)
, polygons_ (nullptr)
, r_(0), g_(0), b_(0)
, a_(0), rgba_(0)
{
Expand Down
6 changes: 3 additions & 3 deletions io/src/dinast_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ pcl::DinastGrabber::DinastGrabber (const int device_position)
, image_height_ (240)
, sync_packet_size_ (512)
, fov_ (64. * M_PI / 180.)
, context_ (NULL)
, context_ (nullptr)
, bulk_ep_ (std::numeric_limits<unsigned char>::max ())
, second_image_ (false)
, running_ (false)
Expand Down Expand Up @@ -131,7 +131,7 @@ pcl::DinastGrabber::setupDevice (int device_position, const int id_vendor, const
#else
libusb_set_debug (context_, 3);
#endif
libusb_device **devs = NULL;
libusb_device **devs = nullptr;

// Get the list of USB devices
ssize_t number_devices = libusb_get_device_list (context_, &devs);
Expand Down Expand Up @@ -187,7 +187,7 @@ pcl::DinastGrabber::setupDevice (int device_position, const int id_vendor, const
libusb_free_device_list (devs, 1);

// Check if device founded if not notify
if (device_handle_ == NULL)
if (device_handle_ == nullptr)
PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::setupDevice] Failed to find any DINAST devices attached");

// Claim device interface
Expand Down
38 changes: 19 additions & 19 deletions io/src/hdl_grabber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@
#include <pcap.h>
#endif // #ifdef HAVE_PCAP

double *pcl::HDLGrabber::cos_lookup_table_ = NULL;
double *pcl::HDLGrabber::sin_lookup_table_ = NULL;
double *pcl::HDLGrabber::cos_lookup_table_ = nullptr;
double *pcl::HDLGrabber::sin_lookup_table_ = nullptr;

using boost::asio::ip::udp;

Expand All @@ -78,10 +78,10 @@ pcl::HDLGrabber::HDLGrabber (const std::string& correctionsFile,
source_address_filter_ (),
source_port_filter_ (443),
hdl_read_socket_service_ (),
hdl_read_socket_ (NULL),
hdl_read_socket_ (nullptr),
pcap_file_name_ (pcapFile),
queue_consumer_thread_ (NULL),
hdl_read_packet_thread_ (NULL),
queue_consumer_thread_ (nullptr),
hdl_read_packet_thread_ (nullptr),
min_distance_threshold_ (0.0),
max_distance_threshold_ (10000.0)
{
Expand Down Expand Up @@ -110,10 +110,10 @@ pcl::HDLGrabber::HDLGrabber (const boost::asio::ip::address& ipAddress,
source_address_filter_ (),
source_port_filter_ (443),
hdl_read_socket_service_ (),
hdl_read_socket_ (NULL),
hdl_read_socket_ (nullptr),
pcap_file_name_ (),
queue_consumer_thread_ (NULL),
hdl_read_packet_thread_ (NULL),
queue_consumer_thread_ (nullptr),
hdl_read_packet_thread_ (nullptr),
min_distance_threshold_ (0.0),
max_distance_threshold_ (10000.0)
{
Expand All @@ -137,7 +137,7 @@ pcl::HDLGrabber::~HDLGrabber () throw ()
void
pcl::HDLGrabber::initialize (const std::string& correctionsFile)
{
if (cos_lookup_table_ == NULL && sin_lookup_table_ == NULL)
if (cos_lookup_table_ == nullptr && sin_lookup_table_ == nullptr)
{
cos_lookup_table_ = static_cast<double *> (malloc (HDL_NUM_ROT_ANGLES * sizeof (*cos_lookup_table_)));
sin_lookup_table_ = static_cast<double *> (malloc (HDL_NUM_ROT_ANGLES * sizeof (*sin_lookup_table_)));
Expand Down Expand Up @@ -443,13 +443,13 @@ pcl::HDLGrabber::computeXYZI (pcl::PointXYZI& point,
void
pcl::HDLGrabber::fireCurrentSweep ()
{
if (sweep_xyz_signal_ != NULL && sweep_xyz_signal_->num_slots () > 0)
if (sweep_xyz_signal_ != nullptr && sweep_xyz_signal_->num_slots () > 0)
sweep_xyz_signal_->operator() (current_sweep_xyz_);

if (sweep_xyzrgba_signal_ != NULL && sweep_xyzrgba_signal_->num_slots () > 0)
if (sweep_xyzrgba_signal_ != nullptr && sweep_xyzrgba_signal_->num_slots () > 0)
sweep_xyzrgba_signal_->operator() (current_sweep_xyzrgba_);

if (sweep_xyzi_signal_ != NULL && sweep_xyzi_signal_->num_slots () > 0)
if (sweep_xyzi_signal_ != nullptr && sweep_xyzi_signal_->num_slots () > 0)
sweep_xyzi_signal_->operator() (current_sweep_xyzi_);
}

Expand Down Expand Up @@ -541,32 +541,32 @@ pcl::HDLGrabber::stop ()
terminate_read_packet_thread_ = true;
hdl_data_.stopQueue ();

if (hdl_read_packet_thread_ != NULL)
if (hdl_read_packet_thread_ != nullptr)
{
hdl_read_packet_thread_->interrupt ();
hdl_read_packet_thread_->join ();
delete hdl_read_packet_thread_;
hdl_read_packet_thread_ = NULL;
hdl_read_packet_thread_ = nullptr;
}
if (queue_consumer_thread_ != NULL)
if (queue_consumer_thread_ != nullptr)
{
queue_consumer_thread_->join ();
delete queue_consumer_thread_;
queue_consumer_thread_ = NULL;
queue_consumer_thread_ = nullptr;
}

if (hdl_read_socket_ != NULL)
if (hdl_read_socket_ != nullptr)
{
delete hdl_read_socket_;
hdl_read_socket_ = NULL;
hdl_read_socket_ = nullptr;
}
}

/////////////////////////////////////////////////////////////////////////////
bool
pcl::HDLGrabber::isRunning () const
{
return (!hdl_data_.isEmpty () || (hdl_read_packet_thread_ != NULL && !hdl_read_packet_thread_->timed_join (boost::posix_time::milliseconds (10))));
return (!hdl_data_.isEmpty () || (hdl_read_packet_thread_ != nullptr && !hdl_read_packet_thread_->timed_join (boost::posix_time::milliseconds (10))));
}

/////////////////////////////////////////////////////////////////////////////
Expand Down
12 changes: 6 additions & 6 deletions io/src/libpng_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ namespace pcl
assert (image_arg.size () == width_arg*height_arg*channels);

// Initialize write structure
png_ptr = png_create_write_struct (PNG_LIBPNG_VER_STRING, 0, 0, 0);
png_ptr = png_create_write_struct (PNG_LIBPNG_VER_STRING, nullptr, nullptr, nullptr);
assert (png_ptr && "creating png_create_write_structpng_create_write_struct failed");

// Initialize info structure
Expand Down Expand Up @@ -163,12 +163,12 @@ namespace pcl
}

// End write
png_write_end (png_ptr, 0);
png_write_end (png_ptr, nullptr);

if (info_ptr)
png_free_data (png_ptr, info_ptr, PNG_FREE_ALL, -1);
if (png_ptr)
png_destroy_write_struct (&png_ptr, 0);
png_destroy_write_struct (&png_ptr, nullptr);
}

///////////////////////////////////////////////////////////////////////////////////////////
Expand All @@ -190,7 +190,7 @@ namespace pcl
if (pngData_arg.size () == 0)
return;

png_ptr = png_create_read_struct (PNG_LIBPNG_VER_STRING, 0, 0, 0);
png_ptr = png_create_read_struct (PNG_LIBPNG_VER_STRING, nullptr, nullptr, nullptr);
assert (png_ptr && "creating png_create_write_structpng_create_write_struct failed");

// Initialize info structure
Expand All @@ -206,7 +206,7 @@ namespace pcl
png_read_info (png_ptr, info_ptr);

png_get_IHDR (png_ptr, info_ptr, &png_width, &png_height, &png_bit_depth,
&png_color_type, &png_interlace_type, NULL, NULL);
&png_color_type, &png_interlace_type, nullptr, nullptr);

// ensure a color bit depth of 8
assert(png_bit_depth==sizeof(T)*8);
Expand Down Expand Up @@ -248,7 +248,7 @@ namespace pcl
if (info_ptr)
png_free_data (png_ptr, info_ptr, PNG_FREE_ALL, -1);
if (png_ptr)
png_destroy_read_struct (&png_ptr, 0, 0);
png_destroy_read_struct (&png_ptr, nullptr, nullptr);
if (row_pointers)
free (row_pointers);
}
Expand Down
6 changes: 3 additions & 3 deletions io/src/lzf_image_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ pcl::io::LZFImageWriter::saveImageBlob (const char* data,
return (false);
}

char *map = static_cast<char*> (::mmap (0, data_size, PROT_WRITE, MAP_SHARED, fd, 0));
char *map = static_cast<char*> (::mmap (nullptr, data_size, PROT_WRITE, MAP_SHARED, fd, 0));
if (map == reinterpret_cast<char*> (-1)) // MAP_FAILED
{
raw_close (fd);
Expand Down Expand Up @@ -399,7 +399,7 @@ pcl::io::LZFImageReader::loadImageBlob (const std::string &filename,
return (false);
}
#else
char *map = static_cast<char*> (::mmap (0, data_size, PROT_READ, MAP_SHARED, fd, 0));
char *map = static_cast<char*> (::mmap (nullptr, data_size, PROT_READ, MAP_SHARED, fd, 0));
if (map == reinterpret_cast<char*> (-1)) // MAP_FAILED
{
raw_close (fd);
Expand Down Expand Up @@ -492,7 +492,7 @@ pcl::io::LZFImageReader::readParameters (const std::string &filename)
{
std::filebuf fb;
std::filebuf *f = fb.open (filename.c_str (), std::ios::in);
if (f == NULL)
if (f == nullptr)
return (false);
std::istream is (&fb);
bool res = readParameters (is);
Expand Down
Loading

0 comments on commit 0fab882

Please sign in to comment.