From e13ccd4126409ac9b2f8a8527c2bf30baa899a02 Mon Sep 17 00:00:00 2001 From: v4hn Date: Sun, 12 Feb 2023 00:01:00 +0100 Subject: [PATCH 1/4] add boost::placeholders:: --- openni_camera/include/openni_camera/openni_device.h | 6 +++--- openni_camera/src/openni_device.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/openni_camera/include/openni_camera/openni_device.h b/openni_camera/include/openni_camera/openni_device.h index 6a5e4a8..12e2101 100644 --- a/openni_camera/include/openni_camera/openni_device.h +++ b/openni_camera/include/openni_camera/openni_device.h @@ -264,19 +264,19 @@ float OpenNIDevice::getBaseline () const throw () template OpenNIDevice::CallbackHandle OpenNIDevice::registerImageCallback (void (T::*callback)(boost::shared_ptr, void* cookie), T& instance, void* custom_data) throw () { - image_callback_[image_callback_handle_counter_] = boost::bind (callback, boost::ref (instance), _1, custom_data); + image_callback_[image_callback_handle_counter_] = boost::bind (callback, boost::ref (instance), boost::placeholders::_1, custom_data); return image_callback_handle_counter_++; } template OpenNIDevice::CallbackHandle OpenNIDevice::registerDepthCallback (void (T::*callback)(boost::shared_ptr, void* cookie), T& instance, void* custom_data) throw () { - depth_callback_[depth_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), _1, custom_data); + depth_callback_[depth_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), boost::placeholders::_1, custom_data); return depth_callback_handle_counter_++; } template OpenNIDevice::CallbackHandle OpenNIDevice::registerIRCallback (void (T::*callback)(boost::shared_ptr, void* cookie), T& instance, void* custom_data) throw () { - ir_callback_[ir_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), _1, custom_data); + ir_callback_[ir_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), boost::placeholders::_1, custom_data); return ir_callback_handle_counter_++; } diff --git a/openni_camera/src/openni_device.cpp b/openni_camera/src/openni_device.cpp index 314c2f0..87608c6 100644 --- a/openni_camera/src/openni_device.cpp +++ b/openni_camera/src/openni_device.cpp @@ -606,7 +606,7 @@ OpenNIDevice::CallbackHandle OpenNIDevice::registerImageCallback (const ImageCal if (!hasImageStream ()) THROW_OPENNI_EXCEPTION ("Device does not provide an image stream"); - image_callback_[image_callback_handle_counter_] = boost::bind (callback, _1, custom_data); + image_callback_[image_callback_handle_counter_] = boost::bind (callback, boost::placeholders::_1, custom_data); return image_callback_handle_counter_++; } @@ -623,7 +623,7 @@ OpenNIDevice::CallbackHandle OpenNIDevice::registerDepthCallback (const DepthIma if (!hasDepthStream ()) THROW_OPENNI_EXCEPTION ("Device does not provide a depth image"); - depth_callback_[depth_callback_handle_counter_] = boost::bind (callback, _1, custom_data); + depth_callback_[depth_callback_handle_counter_] = boost::bind (callback, boost::placeholders::_1, custom_data); return depth_callback_handle_counter_++; } @@ -641,7 +641,7 @@ OpenNIDevice::CallbackHandle OpenNIDevice::registerIRCallback (const IRImageCall if (!hasDepthStream ()) THROW_OPENNI_EXCEPTION ("Device does not provide an IR stream"); - ir_callback_[ir_callback_handle_counter_] = boost::bind (callback, _1, custom_data); + ir_callback_[ir_callback_handle_counter_] = boost::bind (callback, boost::placeholders::_1, custom_data); return ir_callback_handle_counter_++; } From 8eba74d8d60edeb8ba8b48f33686cf078efcf821 Mon Sep 17 00:00:00 2001 From: v4hn Date: Sun, 12 Feb 2023 00:01:54 +0100 Subject: [PATCH 2/4] drop all throw declarations sed -i 's/throw (OpenNIException)//' $(grep -r "throw ([^)]" -l) Required in c++17 --- .../openni_camera/openni_depth_image.h | 6 +- .../include/openni_camera/openni_device.h | 70 +++++++++---------- .../openni_camera/openni_device_kinect.h | 12 ++-- .../include/openni_camera/openni_device_oni.h | 26 +++---- .../openni_camera/openni_device_primesense.h | 10 +-- .../openni_camera/openni_device_xtion.h | 8 +-- .../include/openni_camera/openni_driver.h | 18 ++--- .../include/openni_camera/openni_image.h | 6 +- .../openni_camera/openni_image_bayer_grbg.h | 4 +- .../openni_camera/openni_image_rgb24.h | 4 +- .../openni_camera/openni_image_yuv_422.h | 4 +- .../include/openni_camera/openni_ir_image.h | 2 +- openni_camera/src/openni_depth_image.cpp | 6 +- openni_camera/src/openni_device.cpp | 68 +++++++++--------- openni_camera/src/openni_device_kinect.cpp | 12 ++-- openni_camera/src/openni_device_oni.cpp | 26 +++---- .../src/openni_device_primesense.cpp | 10 +-- openni_camera/src/openni_device_xtion.cpp | 6 +- openni_camera/src/openni_driver.cpp | 12 ++-- openni_camera/src/openni_image_bayer_grbg.cpp | 4 +- openni_camera/src/openni_image_rgb24.cpp | 4 +- openni_camera/src/openni_image_yuv_422.cpp | 4 +- openni_camera/src/openni_ir_image.cpp | 2 +- 23 files changed, 162 insertions(+), 162 deletions(-) diff --git a/openni_camera/include/openni_camera/openni_depth_image.h b/openni_camera/include/openni_camera/openni_depth_image.h index 491be44..0a284bd 100644 --- a/openni_camera/include/openni_camera/openni_depth_image.h +++ b/openni_camera/include/openni_camera/openni_depth_image.h @@ -59,9 +59,9 @@ class DepthImage inline virtual ~DepthImage () throw (); inline const xn::DepthMetaData& getDepthMetaData () const throw (); - void fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const throw (OpenNIException); - void fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const throw (OpenNIException); - void fillDepthImageRaw (unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step = 0) const throw (OpenNIException); + void fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const ; + void fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const ; + void fillDepthImageRaw (unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step = 0) const ; inline float getBaseline () const throw (); inline float getFocalLength () const throw (); diff --git a/openni_camera/include/openni_camera/openni_device.h b/openni_camera/include/openni_camera/openni_device.h index 12e2101..3a7a37a 100644 --- a/openni_camera/include/openni_camera/openni_device.h +++ b/openni_camera/include/openni_camera/openni_device.h @@ -75,35 +75,35 @@ class OpenNIDevice : public boost::noncopyable virtual ~OpenNIDevice () throw (); void shutdown (); - virtual bool findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (OpenNIException); - virtual bool findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (OpenNIException); + virtual bool findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const ; + virtual bool findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const ; - virtual bool isImageModeSupported (const XnMapOutputMode& output_mode) const throw (OpenNIException); - virtual bool isDepthModeSupported (const XnMapOutputMode& output_mode) const throw (OpenNIException); + virtual bool isImageModeSupported (const XnMapOutputMode& output_mode) const ; + virtual bool isDepthModeSupported (const XnMapOutputMode& output_mode) const ; virtual const XnMapOutputMode& getDefaultImageMode () const throw (); virtual const XnMapOutputMode& getDefaultDepthMode () const throw (); virtual const XnMapOutputMode& getDefaultIRMode () const throw (); - virtual void setImageOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException); - virtual void setDepthOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException); - virtual void setIROutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException); + virtual void setImageOutputMode (const XnMapOutputMode& output_mode) ; + virtual void setDepthOutputMode (const XnMapOutputMode& output_mode) ; + virtual void setIROutputMode (const XnMapOutputMode& output_mode) ; - XnMapOutputMode getImageOutputMode () const throw (OpenNIException); - XnMapOutputMode getDepthOutputMode () const throw (OpenNIException); - XnMapOutputMode getIROutputMode () const throw (OpenNIException); + XnMapOutputMode getImageOutputMode () const ; + XnMapOutputMode getDepthOutputMode () const ; + XnMapOutputMode getIROutputMode () const ; - virtual void setDepthRegistration (bool on_off) throw (OpenNIException); - bool isDepthRegistered () const throw (OpenNIException); - virtual bool isDepthRegistrationSupported () const throw (OpenNIException); + virtual void setDepthRegistration (bool on_off) ; + bool isDepthRegistered () const ; + virtual bool isDepthRegistrationSupported () const ; - virtual void setSynchronization (bool on_off) throw (OpenNIException); - virtual bool isSynchronized () const throw (OpenNIException); + virtual void setSynchronization (bool on_off) ; + virtual bool isSynchronized () const ; virtual bool isSynchronizationSupported () const throw (); // just supported by primesense -> virtual - virtual bool isDepthCropped () const throw (OpenNIException); - virtual void setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) throw (OpenNIException); + virtual bool isDepthCropped () const ; + virtual void setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) ; virtual bool isDepthCroppingSupported () const throw (); /** \brief returns the focal length for the color camera in pixels. The pixels are assumed to be square. @@ -117,22 +117,22 @@ class OpenNIDevice : public boost::noncopyable inline float getDepthFocalLength (int output_x_resolution = 0) const throw (); inline float getBaseline () const throw (); - virtual void startImageStream () throw (OpenNIException); - virtual void stopImageStream () throw (OpenNIException); + virtual void startImageStream () ; + virtual void stopImageStream () ; - virtual void startDepthStream () throw (OpenNIException); - virtual void stopDepthStream () throw (OpenNIException); + virtual void startDepthStream () ; + virtual void stopDepthStream () ; - virtual void startIRStream () throw (OpenNIException); - virtual void stopIRStream () throw (OpenNIException); + virtual void startIRStream () ; + virtual void stopIRStream () ; bool hasImageStream () const throw (); bool hasDepthStream () const throw (); bool hasIRStream () const throw (); - virtual bool isImageStreamRunning () const throw (OpenNIException); - virtual bool isDepthStreamRunning () const throw (OpenNIException); - virtual bool isIRStreamRunning () const throw (OpenNIException); + virtual bool isImageStreamRunning () const ; + virtual bool isDepthStreamRunning () const ; + virtual bool isIRStreamRunning () const ; CallbackHandle registerImageCallback (const ImageCallbackFunction& callback, void* cookie = NULL) throw (); template CallbackHandle registerImageCallback (void (T::*callback)(boost::shared_ptr, void* cookie), T& instance, void* cookie = NULL) throw (); @@ -164,26 +164,26 @@ class OpenNIDevice : public boost::noncopyable typedef boost::function) > ActualDepthImageCallbackFunction; typedef boost::function) > ActualIRImageCallbackFunction; - OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException); - OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException); - OpenNIDevice (xn::Context& context) throw (OpenNIException); + OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) ; + OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) ; + OpenNIDevice (xn::Context& context) ; static void __stdcall NewDepthDataAvailable (xn::ProductionNode& node, void* cookie) throw (); static void __stdcall NewImageDataAvailable (xn::ProductionNode& node, void* cookie) throw (); static void __stdcall NewIRDataAvailable (xn::ProductionNode& node, void* cookie) throw (); // This is a workaround, since in the NewDepthDataAvailable function WaitAndUpdateData leads to a dead-lock behaviour // and retrieving image data without WaitAndUpdateData leads to incomplete images!!! - void ImageDataThreadFunction () throw (OpenNIException); - void DepthDataThreadFunction () throw (OpenNIException); - void IRDataThreadFunction () throw (OpenNIException); + void ImageDataThreadFunction () ; + void DepthDataThreadFunction () ; + void IRDataThreadFunction () ; virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () = 0; - void setRegistration (bool on_off) throw (OpenNIException); + void setRegistration (bool on_off) ; virtual boost::shared_ptr getCurrentImage (boost::shared_ptr image_data) const throw () = 0; - virtual void enumAvailableModes () throw (OpenNIException); - void Init () throw (OpenNIException); + virtual void enumAvailableModes () ; + void Init () ; // holds the callback functions together with custom data // since same callback function can be registered multiple times with e.g. different custom data // we use a map structure with a handle as the key diff --git a/openni_camera/include/openni_camera/openni_device_kinect.h b/openni_camera/include/openni_camera/openni_device_kinect.h index c0e4886..6935d5c 100644 --- a/openni_camera/include/openni_camera/openni_device_kinect.h +++ b/openni_camera/include/openni_camera/openni_device_kinect.h @@ -54,24 +54,24 @@ class DeviceKinect : public OpenNIDevice { friend class OpenNIDriver; public: - DeviceKinect (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException); + DeviceKinect (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) ; virtual ~DeviceKinect () throw (); inline void setDebayeringMethod (const ImageBayerGRBG::DebayeringMethod& debayering_method) throw (); inline const ImageBayerGRBG::DebayeringMethod& getDebayeringMethod () const throw (); // these capabilities are not supported for kinect - virtual void setSynchronization (bool on_off) throw (OpenNIException); - virtual bool isSynchronized () const throw (OpenNIException); + virtual void setSynchronization (bool on_off) ; + virtual bool isSynchronized () const ; virtual bool isSynchronizationSupported () const throw (); - virtual bool isDepthCropped () const throw (OpenNIException); - virtual void setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) throw (OpenNIException); + virtual bool isDepthCropped () const ; + virtual void setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) ; virtual bool isDepthCroppingSupported () const throw (); protected: virtual boost::shared_ptr getCurrentImage (boost::shared_ptr image_meta_data) const throw (); - virtual void enumAvailableModes () throw (OpenNIException); + virtual void enumAvailableModes () ; virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw (); ImageBayerGRBG::DebayeringMethod debayering_method_; }; diff --git a/openni_camera/include/openni_camera/openni_device_oni.h b/openni_camera/include/openni_camera/openni_device_oni.h index 23221d6..b4cfd98 100644 --- a/openni_camera/include/openni_camera/openni_device_oni.h +++ b/openni_camera/include/openni_camera/openni_device_oni.h @@ -54,30 +54,30 @@ class DeviceONI : public OpenNIDevice { friend class OpenNIDriver; public: - DeviceONI (xn::Context& context, const std::string& file_name, bool repeat = false, bool streaming = true) throw (OpenNIException); + DeviceONI (xn::Context& context, const std::string& file_name, bool repeat = false, bool streaming = true) ; virtual ~DeviceONI () throw (); - virtual void startImageStream () throw (OpenNIException); - virtual void stopImageStream () throw (OpenNIException); + virtual void startImageStream () ; + virtual void stopImageStream () ; - virtual void startDepthStream () throw (OpenNIException); - virtual void stopDepthStream () throw (OpenNIException); + virtual void startDepthStream () ; + virtual void stopDepthStream () ; - virtual void startIRStream () throw (OpenNIException); - virtual void stopIRStream () throw (OpenNIException); + virtual void startIRStream () ; + virtual void stopIRStream () ; - virtual bool isImageStreamRunning () const throw (OpenNIException); - virtual bool isDepthStreamRunning () const throw (OpenNIException); - virtual bool isIRStreamRunning () const throw (OpenNIException); + virtual bool isImageStreamRunning () const ; + virtual bool isDepthStreamRunning () const ; + virtual bool isIRStreamRunning () const ; virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw (); - bool trigger () throw (OpenNIException); - bool isStreaming () const throw (OpenNIException); + bool trigger () ; + bool isStreaming () const ; protected: virtual boost::shared_ptr getCurrentImage (boost::shared_ptr image_meta_data) const throw (); - void PlayerThreadFunction () throw (OpenNIException); + void PlayerThreadFunction () ; static void __stdcall NewONIDepthDataAvailable (xn::ProductionNode& node, void* cookie) throw (); static void __stdcall NewONIImageDataAvailable (xn::ProductionNode& node, void* cookie) throw (); static void __stdcall NewONIIRDataAvailable (xn::ProductionNode& node, void* cookie) throw (); diff --git a/openni_camera/include/openni_camera/openni_device_primesense.h b/openni_camera/include/openni_camera/openni_device_primesense.h index a767931..e7927d8 100644 --- a/openni_camera/include/openni_camera/openni_device_primesense.h +++ b/openni_camera/include/openni_camera/openni_device_primesense.h @@ -52,17 +52,17 @@ class DevicePrimesense : public OpenNIDevice { friend class OpenNIDriver; public: - DevicePrimesense (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException); + DevicePrimesense (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) ; virtual ~DevicePrimesense () throw (); - //virtual void setImageOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException); + //virtual void setImageOutputMode (const XnMapOutputMode& output_mode) ; protected: virtual boost::shared_ptr getCurrentImage (boost::shared_ptr image_meta_data) const throw (); - virtual void enumAvailableModes () throw (OpenNIException); + virtual void enumAvailableModes () ; virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw (); - virtual void startImageStream () throw (OpenNIException); - virtual void startDepthStream () throw (OpenNIException); + virtual void startImageStream () ; + virtual void startDepthStream () ; }; } // namespace diff --git a/openni_camera/include/openni_camera/openni_device_xtion.h b/openni_camera/include/openni_camera/openni_device_xtion.h index 5bacd85..5b0cc5e 100644 --- a/openni_camera/include/openni_camera/openni_device_xtion.h +++ b/openni_camera/include/openni_camera/openni_device_xtion.h @@ -53,16 +53,16 @@ class DeviceXtionPro : public OpenNIDevice { friend class OpenNIDriver; public: - DeviceXtionPro (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException); + DeviceXtionPro (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) ; virtual ~DeviceXtionPro () throw (); - //virtual void setImageOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException); + //virtual void setImageOutputMode (const XnMapOutputMode& output_mode) ; protected: virtual boost::shared_ptr getCurrentImage (boost::shared_ptr image_meta_data) const throw (); - virtual void enumAvailableModes () throw (OpenNIException); + virtual void enumAvailableModes () ; virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw (); - virtual void startDepthStream () throw (OpenNIException); + virtual void startDepthStream () ; }; } // namespace diff --git a/openni_camera/include/openni_camera/openni_driver.h b/openni_camera/include/openni_camera/openni_driver.h index 624f2d8..0795b50 100644 --- a/openni_camera/include/openni_camera/openni_driver.h +++ b/openni_camera/include/openni_camera/openni_driver.h @@ -60,15 +60,15 @@ class OpenNIDriver public: ~OpenNIDriver () throw (); - inline static OpenNIDriver& getInstance () throw (OpenNIException); + inline static OpenNIDriver& getInstance () ; unsigned updateDeviceList () throw (); inline unsigned getNumberDevices () const throw (); - boost::shared_ptr createVirtualDevice (const std::string& path, bool repeat, bool stream) const throw (OpenNIException); - boost::shared_ptr getDeviceByIndex (unsigned index) const throw (OpenNIException); + boost::shared_ptr createVirtualDevice (const std::string& path, bool repeat, bool stream) const ; + boost::shared_ptr getDeviceByIndex (unsigned index) const ; #ifndef _WIN32 - boost::shared_ptr getDeviceBySerialNumber (const std::string& serial_number) const throw (OpenNIException); - boost::shared_ptr getDeviceByAddress (unsigned char bus, unsigned char address) const throw (OpenNIException); + boost::shared_ptr getDeviceBySerialNumber (const std::string& serial_number) const ; + boost::shared_ptr getDeviceByAddress (unsigned char bus, unsigned char address) const ; #endif const char* getSerialNumber (unsigned index) const throw (); @@ -84,7 +84,7 @@ class OpenNIDriver void getPrimesenseSerial(xn::NodeInfo info, char* buffer, unsigned buf_size) const throw (); - void stopAll () throw (OpenNIException); + void stopAll () ; static void getDeviceType (const std::string& connection_string, unsigned short& vendorId, unsigned short& productId); protected: @@ -100,8 +100,8 @@ class OpenNIDriver boost::weak_ptr device; }; - OpenNIDriver () throw (OpenNIException); - boost::shared_ptr getDevice (unsigned index) const throw (OpenNIException); + OpenNIDriver () ; + boost::shared_ptr getDevice (unsigned index) const ; #ifndef _WIN32 // workaround to get additional device nformation like serial number, vendor and product name, until Primesense fix this @@ -116,7 +116,7 @@ class OpenNIDriver std::map< std::string, unsigned > connection_string_map_; }; -OpenNIDriver& OpenNIDriver::getInstance () throw (OpenNIException) +OpenNIDriver& OpenNIDriver::getInstance () { static OpenNIDriver driver; return driver; diff --git a/openni_camera/include/openni_camera/openni_image.h b/openni_camera/include/openni_camera/openni_image.h index ddd38ef..3aefb09 100644 --- a/openni_camera/include/openni_camera/openni_image.h +++ b/openni_camera/include/openni_camera/openni_image.h @@ -69,18 +69,18 @@ class Image virtual bool isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const = 0; virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, - unsigned rgb_line_step = 0) const throw (OpenNIException) = 0; + unsigned rgb_line_step = 0) const = 0; virtual Encoding getEncoding () const = 0; inline void - fillRaw (unsigned char* rgb_buffer) const throw (OpenNIException) + fillRaw (unsigned char* rgb_buffer) const { memcpy (rgb_buffer, image_md_->WritableData(), image_md_->DataSize ()); } virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, - unsigned gray_line_step = 0) const throw (OpenNIException) = 0; + unsigned gray_line_step = 0) const = 0; inline unsigned getWidth () const throw (); inline unsigned getHeight () const throw (); diff --git a/openni_camera/include/openni_camera/openni_image_bayer_grbg.h b/openni_camera/include/openni_camera/openni_image_bayer_grbg.h index 6e89ba3..6084554 100644 --- a/openni_camera/include/openni_camera/openni_image_bayer_grbg.h +++ b/openni_camera/include/openni_camera/openni_image_bayer_grbg.h @@ -65,8 +65,8 @@ class ImageBayerGRBG : public Image return (BAYER_GRBG); } - virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const throw (OpenNIException); - virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const throw (OpenNIException); + virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const ; + virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const ; virtual bool isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const; inline void setDebayeringMethod (const DebayeringMethod& method) throw (); inline DebayeringMethod getDebayeringMethod () const throw (); diff --git a/openni_camera/include/openni_camera/openni_image_rgb24.h b/openni_camera/include/openni_camera/openni_image_rgb24.h index 6c02669..67f7d57 100644 --- a/openni_camera/include/openni_camera/openni_image_rgb24.h +++ b/openni_camera/include/openni_camera/openni_image_rgb24.h @@ -59,8 +59,8 @@ class ImageRGB24 : public Image return (RGB); } - virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const throw (OpenNIException); - virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const throw (OpenNIException); + virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const ; + virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const ; virtual bool isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const; inline static bool resizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height); }; diff --git a/openni_camera/include/openni_camera/openni_image_yuv_422.h b/openni_camera/include/openni_camera/openni_image_yuv_422.h index c94f7ca..791ea2c 100644 --- a/openni_camera/include/openni_camera/openni_image_yuv_422.h +++ b/openni_camera/include/openni_camera/openni_image_yuv_422.h @@ -59,8 +59,8 @@ class ImageYUV422 : public Image } virtual bool isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const; - virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const throw (OpenNIException); - virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const throw (OpenNIException); + virtual void fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step = 0) const ; + virtual void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const ; inline static bool resizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height); }; diff --git a/openni_camera/include/openni_camera/openni_ir_image.h b/openni_camera/include/openni_camera/openni_ir_image.h index fc21672..0fae175 100644 --- a/openni_camera/include/openni_camera/openni_ir_image.h +++ b/openni_camera/include/openni_camera/openni_ir_image.h @@ -56,7 +56,7 @@ class IRImage inline IRImage (boost::shared_ptr ir_meta_data) throw (); inline virtual ~IRImage () throw (); - void fillRaw (unsigned width, unsigned height, unsigned short* ir_buffer, unsigned line_step = 0) const throw (OpenNIException); + void fillRaw (unsigned width, unsigned height, unsigned short* ir_buffer, unsigned line_step = 0) const ; inline unsigned getWidth () const throw (); inline unsigned getHeight () const throw (); diff --git a/openni_camera/src/openni_depth_image.cpp b/openni_camera/src/openni_depth_image.cpp index 9f2e985..45d4d60 100644 --- a/openni_camera/src/openni_depth_image.cpp +++ b/openni_camera/src/openni_depth_image.cpp @@ -44,7 +44,7 @@ using namespace std; namespace openni_wrapper { -void DepthImage::fillDepthImageRaw(unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step) const throw (OpenNIException) +void DepthImage::fillDepthImageRaw(unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step) const { if (width > depth_md_->XRes () || height > depth_md_->YRes ()) THROW_OPENNI_EXCEPTION ("upsampling not supported: %d x %d -> %d x %d", depth_md_->XRes (), depth_md_->YRes (), width, height); @@ -96,7 +96,7 @@ void DepthImage::fillDepthImageRaw(unsigned width, unsigned height, unsigned sho } } -void DepthImage::fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step) const throw (OpenNIException) +void DepthImage::fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step) const { if (width > depth_md_->XRes () || height > depth_md_->YRes ()) THROW_OPENNI_EXCEPTION ("upsampling not supported: %d x %d -> %d x %d", depth_md_->XRes (), depth_md_->YRes (), width, height); @@ -141,7 +141,7 @@ void DepthImage::fillDepthImage (unsigned width, unsigned height, float* depth_b } } -void DepthImage::fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step) const throw (OpenNIException) +void DepthImage::fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step) const { if (width > depth_md_->XRes () || height > depth_md_->YRes ()) THROW_OPENNI_EXCEPTION ("upsampling not supported: %d x %d -> %d x %d", depth_md_->XRes (), depth_md_->YRes (), width, height); diff --git a/openni_camera/src/openni_device.cpp b/openni_camera/src/openni_device.cpp index 87608c6..01386eb 100644 --- a/openni_camera/src/openni_device.cpp +++ b/openni_camera/src/openni_device.cpp @@ -51,7 +51,7 @@ using namespace boost; namespace openni_wrapper { -OpenNIDevice::OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException) +OpenNIDevice::OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) : context_ (context) , device_node_info_ (device_node) { @@ -89,7 +89,7 @@ OpenNIDevice::OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_nod Init (); } -OpenNIDevice::OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException) +OpenNIDevice::OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) : context_ (context) , device_node_info_ (device_node) { @@ -119,7 +119,7 @@ OpenNIDevice::OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_nod } // For ONI Player devices -OpenNIDevice::OpenNIDevice (xn::Context& context) throw (OpenNIException) +OpenNIDevice::OpenNIDevice (xn::Context& context) : context_ (context) , device_node_info_ (0) { @@ -159,7 +159,7 @@ void OpenNIDevice::shutdown () data_threads_.join_all (); } -void OpenNIDevice::Init () throw (OpenNIException) +void OpenNIDevice::Init () { quit_ = false; XnDouble pixel_size; @@ -212,7 +212,7 @@ void OpenNIDevice::Init () throw (OpenNIException) } } -void OpenNIDevice::startImageStream () throw (OpenNIException) +void OpenNIDevice::startImageStream () { if (hasImageStream ()) { @@ -228,7 +228,7 @@ void OpenNIDevice::startImageStream () throw (OpenNIException) THROW_OPENNI_EXCEPTION ("Device does not provide an image stream"); } -void OpenNIDevice::stopImageStream () throw (OpenNIException) +void OpenNIDevice::stopImageStream () { if (hasImageStream ()) { @@ -244,7 +244,7 @@ void OpenNIDevice::stopImageStream () throw (OpenNIException) THROW_OPENNI_EXCEPTION ("Device does not provide an image stream"); } -void OpenNIDevice::startDepthStream () throw (OpenNIException) +void OpenNIDevice::startDepthStream () { if (hasDepthStream ()) { @@ -261,7 +261,7 @@ void OpenNIDevice::startDepthStream () throw (OpenNIException) THROW_OPENNI_EXCEPTION ("Device does not provide a depth stream"); } -void OpenNIDevice::stopDepthStream () throw (OpenNIException) +void OpenNIDevice::stopDepthStream () { if (hasDepthStream ()) { @@ -278,7 +278,7 @@ void OpenNIDevice::stopDepthStream () throw (OpenNIException) THROW_OPENNI_EXCEPTION ("Device does not provide a depth stream"); } -void OpenNIDevice::startIRStream () throw (OpenNIException) +void OpenNIDevice::startIRStream () { if (hasIRStream ()) { @@ -295,7 +295,7 @@ void OpenNIDevice::startIRStream () throw (OpenNIException) THROW_OPENNI_EXCEPTION ("Device does not provide an IR stream"); } -void OpenNIDevice::stopIRStream () throw (OpenNIException) +void OpenNIDevice::stopIRStream () { if (hasIRStream ()) { @@ -312,19 +312,19 @@ void OpenNIDevice::stopIRStream () throw (OpenNIException) THROW_OPENNI_EXCEPTION ("Device does not provide an IR stream"); } -bool OpenNIDevice::isImageStreamRunning () const throw (OpenNIException) +bool OpenNIDevice::isImageStreamRunning () const { lock_guard image_lock (image_mutex_); return ( image_generator_.IsValid () && image_generator_.IsGenerating ()); } -bool OpenNIDevice::isDepthStreamRunning () const throw (OpenNIException) +bool OpenNIDevice::isDepthStreamRunning () const { lock_guard depth_lock (depth_mutex_); return ( depth_generator_.IsValid () && depth_generator_.IsGenerating ()); } -bool OpenNIDevice::isIRStreamRunning () const throw (OpenNIException) +bool OpenNIDevice::isIRStreamRunning () const { lock_guard ir_lock (ir_mutex_); return ( ir_generator_.IsValid () && ir_generator_.IsGenerating ()); @@ -350,7 +350,7 @@ bool OpenNIDevice::hasIRStream () const throw () return ir_generator_.IsValid (); } -void OpenNIDevice::setDepthRegistration (bool on_off) throw (OpenNIException) +void OpenNIDevice::setDepthRegistration (bool on_off) { if (hasDepthStream () && hasImageStream()) { @@ -379,7 +379,7 @@ void OpenNIDevice::setDepthRegistration (bool on_off) throw (OpenNIException) THROW_OPENNI_EXCEPTION ("Device does not provide image + depth stream"); } -bool OpenNIDevice::isDepthRegistered () const throw (OpenNIException) +bool OpenNIDevice::isDepthRegistered () const { if (hasDepthStream () && hasImageStream() ) { @@ -393,7 +393,7 @@ bool OpenNIDevice::isDepthRegistered () const throw (OpenNIException) return false; } -bool OpenNIDevice::isDepthRegistrationSupported () const throw (OpenNIException) +bool OpenNIDevice::isDepthRegistrationSupported () const { lock_guard image_lock (image_mutex_); lock_guard depth_lock (depth_mutex_); @@ -408,7 +408,7 @@ bool OpenNIDevice::isSynchronizationSupported () const throw () return ( depth_generator_.IsValid() && image_generator_.IsValid() && depth_generator_.IsCapabilitySupported (XN_CAPABILITY_FRAME_SYNC)); } -void OpenNIDevice::setSynchronization (bool on_off) throw (OpenNIException) +void OpenNIDevice::setSynchronization (bool on_off) { if (hasDepthStream () && hasImageStream()) { @@ -433,7 +433,7 @@ void OpenNIDevice::setSynchronization (bool on_off) throw (OpenNIException) THROW_OPENNI_EXCEPTION ("Device does not provide image + depth stream"); } -bool OpenNIDevice::isSynchronized () const throw (OpenNIException) +bool OpenNIDevice::isSynchronized () const { if (hasDepthStream () && hasImageStream()) { @@ -453,7 +453,7 @@ bool OpenNIDevice::isDepthCroppingSupported () const throw () return ( image_generator_.IsValid() && depth_generator_.IsCapabilitySupported (XN_CAPABILITY_CROPPING) ); } -bool OpenNIDevice::isDepthCropped () const throw (OpenNIException) +bool OpenNIDevice::isDepthCropped () const { if (hasDepthStream ()) { @@ -469,7 +469,7 @@ bool OpenNIDevice::isDepthCropped () const throw (OpenNIException) return false; } -void OpenNIDevice::setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) throw (OpenNIException) +void OpenNIDevice::setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) { if (hasDepthStream ()) { @@ -489,7 +489,7 @@ void OpenNIDevice::setDepthCropping (unsigned x, unsigned y, unsigned width, uns THROW_OPENNI_EXCEPTION ("Device does not provide depth stream"); } -void OpenNIDevice::ImageDataThreadFunction () throw (OpenNIException) +void OpenNIDevice::ImageDataThreadFunction () { while (true) { @@ -519,7 +519,7 @@ void OpenNIDevice::ImageDataThreadFunction () throw (OpenNIException) } } -void OpenNIDevice::DepthDataThreadFunction () throw (OpenNIException) +void OpenNIDevice::DepthDataThreadFunction () { while (true) { @@ -551,7 +551,7 @@ void OpenNIDevice::DepthDataThreadFunction () throw (OpenNIException) } } -void OpenNIDevice::IRDataThreadFunction () throw (OpenNIException) +void OpenNIDevice::IRDataThreadFunction () { while (true) { @@ -749,7 +749,7 @@ const char* OpenNIDevice::getProductName () const throw () return description.strName; } -bool OpenNIDevice::findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const throw (OpenNIException) +bool OpenNIDevice::findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const { if (isImageModeSupported (output_mode)) { @@ -779,7 +779,7 @@ bool OpenNIDevice::findCompatibleImageMode (const XnMapOutputMode& output_mode, } } -bool OpenNIDevice::findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const throw (OpenNIException) +bool OpenNIDevice::findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const { if (isDepthModeSupported (output_mode)) { @@ -809,7 +809,7 @@ bool OpenNIDevice::findCompatibleDepthMode (const XnMapOutputMode& output_mode, } } -void OpenNIDevice::enumAvailableModes () throw (OpenNIException) +void OpenNIDevice::enumAvailableModes () { // we use the overloaded methods from subclasses! /* @@ -847,7 +847,7 @@ void OpenNIDevice::enumAvailableModes () throw (OpenNIException) */ } -bool OpenNIDevice::isImageModeSupported (const XnMapOutputMode& output_mode) const throw (OpenNIException) +bool OpenNIDevice::isImageModeSupported (const XnMapOutputMode& output_mode) const { for (vector::const_iterator modeIt = available_image_modes_.begin (); modeIt != available_image_modes_.end (); ++modeIt) { @@ -857,7 +857,7 @@ bool OpenNIDevice::isImageModeSupported (const XnMapOutputMode& output_mode) con return false; } -bool OpenNIDevice::isDepthModeSupported (const XnMapOutputMode& output_mode) const throw (OpenNIException) +bool OpenNIDevice::isDepthModeSupported (const XnMapOutputMode& output_mode) const { for (vector::const_iterator modeIt = available_depth_modes_.begin (); modeIt != available_depth_modes_.end (); ++modeIt) { @@ -883,7 +883,7 @@ const XnMapOutputMode& OpenNIDevice::getDefaultIRMode () const throw () return available_depth_modes_[0]; } -void OpenNIDevice::setImageOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException) +void OpenNIDevice::setImageOutputMode (const XnMapOutputMode& output_mode) { if (hasImageStream ()) { @@ -896,7 +896,7 @@ void OpenNIDevice::setImageOutputMode (const XnMapOutputMode& output_mode) throw THROW_OPENNI_EXCEPTION ("Device does not provide an image stream"); } -void OpenNIDevice::setDepthOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException) +void OpenNIDevice::setDepthOutputMode (const XnMapOutputMode& output_mode) { if (hasDepthStream ()) { @@ -909,7 +909,7 @@ void OpenNIDevice::setDepthOutputMode (const XnMapOutputMode& output_mode) throw THROW_OPENNI_EXCEPTION ("Device does not provide a depth stream"); } -void OpenNIDevice::setIROutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException) +void OpenNIDevice::setIROutputMode (const XnMapOutputMode& output_mode) { if (hasIRStream ()) { @@ -922,7 +922,7 @@ void OpenNIDevice::setIROutputMode (const XnMapOutputMode& output_mode) throw (O THROW_OPENNI_EXCEPTION ("Device does not provide an IR stream"); } -XnMapOutputMode OpenNIDevice::getImageOutputMode () const throw (OpenNIException) +XnMapOutputMode OpenNIDevice::getImageOutputMode () const { if (!hasImageStream ()) THROW_OPENNI_EXCEPTION ("Device does not provide an image stream"); @@ -935,7 +935,7 @@ XnMapOutputMode OpenNIDevice::getImageOutputMode () const throw (OpenNIException return output_mode; } -XnMapOutputMode OpenNIDevice::getDepthOutputMode () const throw (OpenNIException) +XnMapOutputMode OpenNIDevice::getDepthOutputMode () const { if (!hasDepthStream () ) THROW_OPENNI_EXCEPTION ("Device does not provide a depth stream"); @@ -948,7 +948,7 @@ XnMapOutputMode OpenNIDevice::getDepthOutputMode () const throw (OpenNIException return output_mode; } -XnMapOutputMode OpenNIDevice::getIROutputMode () const throw (OpenNIException) +XnMapOutputMode OpenNIDevice::getIROutputMode () const { if (!hasIRStream ()) THROW_OPENNI_EXCEPTION ("Device does not provide an IR stream"); diff --git a/openni_camera/src/openni_device_kinect.cpp b/openni_camera/src/openni_device_kinect.cpp index 99bf277..94cd3ab 100644 --- a/openni_camera/src/openni_device_kinect.cpp +++ b/openni_camera/src/openni_device_kinect.cpp @@ -45,7 +45,7 @@ using namespace boost; namespace openni_wrapper { -DeviceKinect::DeviceKinect (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException) +DeviceKinect::DeviceKinect (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) : OpenNIDevice (context, device_node, image_node, depth_node, ir_node) , debayering_method_ (ImageBayerGRBG::EdgeAwareWeighted) { @@ -93,7 +93,7 @@ bool DeviceKinect::isImageResizeSupported (unsigned input_width, unsigned input_ return ImageBayerGRBG::resizingSupported (input_width, input_height, output_width, output_height); } -void DeviceKinect::enumAvailableModes () throw (OpenNIException) +void DeviceKinect::enumAvailableModes () { XnMapOutputMode output_mode; available_image_modes_.clear(); @@ -116,13 +116,13 @@ boost::shared_ptr DeviceKinect::getCurrentImage (boost::shared_ptr (new ImageBayerGRBG (image_data, debayering_method_)); } -void DeviceKinect::setSynchronization (bool on_off) throw (OpenNIException) +void DeviceKinect::setSynchronization (bool on_off) { if (on_off) THROW_OPENNI_EXCEPTION ("Microsoft Kinect does not support Hardware synchronization."); } -bool DeviceKinect::isSynchronized () const throw (OpenNIException) +bool DeviceKinect::isSynchronized () const { return false; } @@ -132,12 +132,12 @@ bool DeviceKinect::isSynchronizationSupported () const throw () return false; } -bool DeviceKinect::isDepthCropped () const throw (OpenNIException) +bool DeviceKinect::isDepthCropped () const { return false; } -void DeviceKinect::setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) throw (OpenNIException) +void DeviceKinect::setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) { if (width != 0 && height != 0) THROW_OPENNI_EXCEPTION ("Microsoft Kinect does not support cropping for the depth stream."); diff --git a/openni_camera/src/openni_device_oni.cpp b/openni_camera/src/openni_device_oni.cpp index ff008b3..3413e5e 100644 --- a/openni_camera/src/openni_device_oni.cpp +++ b/openni_camera/src/openni_device_oni.cpp @@ -43,7 +43,7 @@ using namespace boost; namespace openni_wrapper { -DeviceONI::DeviceONI(xn::Context& context, const std::string& file_name, bool repeat, bool streaming) throw (OpenNIException) +DeviceONI::DeviceONI(xn::Context& context, const std::string& file_name, bool repeat, bool streaming) : OpenNIDevice(context) , streaming_ (streaming) , depth_stream_running_ (false) @@ -97,58 +97,58 @@ DeviceONI::~DeviceONI() throw () } } -void DeviceONI::startImageStream () throw (OpenNIException) +void DeviceONI::startImageStream () { if (hasImageStream() && !image_stream_running_) image_stream_running_ = true; } -void DeviceONI::stopImageStream () throw (OpenNIException) +void DeviceONI::stopImageStream () { if (hasImageStream() && image_stream_running_) image_stream_running_ = false; } -void DeviceONI::startDepthStream () throw (OpenNIException) +void DeviceONI::startDepthStream () { if (hasDepthStream() && !depth_stream_running_) depth_stream_running_ = true; } -void DeviceONI::stopDepthStream () throw (OpenNIException) +void DeviceONI::stopDepthStream () { if (hasDepthStream() && depth_stream_running_) depth_stream_running_ = false; } -void DeviceONI::startIRStream () throw (OpenNIException) +void DeviceONI::startIRStream () { if (hasIRStream() && !ir_stream_running_) ir_stream_running_ = true; } -void DeviceONI::stopIRStream () throw (OpenNIException) +void DeviceONI::stopIRStream () { if (hasIRStream() && ir_stream_running_) ir_stream_running_ = false; } -bool DeviceONI::isImageStreamRunning () const throw (OpenNIException) +bool DeviceONI::isImageStreamRunning () const { return image_stream_running_; } -bool DeviceONI::isDepthStreamRunning () const throw (OpenNIException) +bool DeviceONI::isDepthStreamRunning () const { return depth_stream_running_; } -bool DeviceONI::isIRStreamRunning () const throw (OpenNIException) +bool DeviceONI::isIRStreamRunning () const { return ir_stream_running_; } -bool DeviceONI::trigger () throw (OpenNIException) +bool DeviceONI::trigger () { if (player_.IsEOF()) return false; @@ -160,12 +160,12 @@ bool DeviceONI::trigger () throw (OpenNIException) return true; } -bool DeviceONI::isStreaming () const throw (OpenNIException) +bool DeviceONI::isStreaming () const { return streaming_; } -void DeviceONI::PlayerThreadFunction() throw (OpenNIException) +void DeviceONI::PlayerThreadFunction() { quit_ = false; while (!quit_) diff --git a/openni_camera/src/openni_device_primesense.cpp b/openni_camera/src/openni_device_primesense.cpp index d43bee4..e2c2d6c 100644 --- a/openni_camera/src/openni_device_primesense.cpp +++ b/openni_camera/src/openni_device_primesense.cpp @@ -45,7 +45,7 @@ using namespace boost; namespace openni_wrapper { -DevicePrimesense::DevicePrimesense (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException) +DevicePrimesense::DevicePrimesense (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) : OpenNIDevice (context, device_node, image_node, depth_node, ir_node) { // setup stream modes @@ -90,7 +90,7 @@ bool DevicePrimesense::isImageResizeSupported (unsigned input_width, unsigned in return ImageYUV422::resizingSupported (input_width, input_height, output_width, output_height); } -//void DevicePrimesense::setImageOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException) +//void DevicePrimesense::setImageOutputMode (const XnMapOutputMode& output_mode) //{ // if (output_mode.nFPS == 30 && output_mode.nXRes == XN_UXGA_X_RES && output_mode.nYRes == XN_UXGA_Y_RES ) // { @@ -131,7 +131,7 @@ bool DevicePrimesense::isImageResizeSupported (unsigned input_width, unsigned in // OpenNIDevice::setImageOutputMode (output_mode); //} -void DevicePrimesense::enumAvailableModes () throw (OpenNIException) +void DevicePrimesense::enumAvailableModes () { XnMapOutputMode output_mode; available_image_modes_.clear(); @@ -200,7 +200,7 @@ boost::shared_ptr DevicePrimesense::getCurrentImage (boost::shared_ptr ( new ImageYUV422 (image_data) ); } -void DevicePrimesense::startImageStream () throw (OpenNIException) +void DevicePrimesense::startImageStream () { // Suat: Ugly workaround... but on some usb-ports its not possible to start the image stream after the depth stream. // turning on and off registration solves for some reason the problem! @@ -240,7 +240,7 @@ void DevicePrimesense::startImageStream () throw (OpenNIException) OpenNIDevice::startImageStream (); } -void DevicePrimesense::startDepthStream () throw (OpenNIException) +void DevicePrimesense::startDepthStream () { if (isDepthRegistered ()) { diff --git a/openni_camera/src/openni_device_xtion.cpp b/openni_camera/src/openni_device_xtion.cpp index 0ee1411..92f8497 100644 --- a/openni_camera/src/openni_device_xtion.cpp +++ b/openni_camera/src/openni_device_xtion.cpp @@ -44,7 +44,7 @@ using namespace boost; namespace openni_wrapper { -DeviceXtionPro::DeviceXtionPro (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException) +DeviceXtionPro::DeviceXtionPro (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) : OpenNIDevice (context, device_node, depth_node, ir_node) { // setup stream modes @@ -70,7 +70,7 @@ bool DeviceXtionPro::isImageResizeSupported (unsigned input_width, unsigned inpu return false; } -void DeviceXtionPro::enumAvailableModes () throw (OpenNIException) +void DeviceXtionPro::enumAvailableModes () { XnMapOutputMode output_mode; available_image_modes_.clear(); @@ -108,7 +108,7 @@ boost::shared_ptr DeviceXtionPro::getCurrentImage (boost::shared_ptr ((Image*)0); } -void DeviceXtionPro::startDepthStream () throw (OpenNIException) +void DeviceXtionPro::startDepthStream () { if (isDepthRegistered ()) { diff --git a/openni_camera/src/openni_driver.cpp b/openni_camera/src/openni_driver.cpp index d255ac5..9386f35 100644 --- a/openni_camera/src/openni_driver.cpp +++ b/openni_camera/src/openni_driver.cpp @@ -58,7 +58,7 @@ using namespace boost; namespace openni_wrapper { -OpenNIDriver::OpenNIDriver () throw (OpenNIException) +OpenNIDriver::OpenNIDriver () { // Initialize the Engine XnStatus status = context_.Init (); @@ -208,7 +208,7 @@ unsigned OpenNIDriver::updateDeviceList () throw () return (device_context_.size ()); } -void OpenNIDriver::stopAll () throw (OpenNIException) +void OpenNIDriver::stopAll () { XnStatus status = context_.StopGeneratingAll (); if (status != XN_STATUS_OK) @@ -229,7 +229,7 @@ OpenNIDriver::~OpenNIDriver () throw () context_.Shutdown (); } -boost::shared_ptr OpenNIDriver::createVirtualDevice (const string& path, bool repeat, bool stream) const throw (OpenNIException) +boost::shared_ptr OpenNIDriver::createVirtualDevice (const string& path, bool repeat, bool stream) const { return boost::shared_ptr (new DeviceONI (context_, path, repeat, stream)); } @@ -250,7 +250,7 @@ void OpenNIDriver::getPrimesenseSerial(xn::NodeInfo info, char* buffer, unsigned device.Release(); } -boost::shared_ptr OpenNIDriver::getDeviceByIndex (unsigned index) const throw (OpenNIException) +boost::shared_ptr OpenNIDriver::getDeviceByIndex (unsigned index) const { using namespace std; @@ -292,7 +292,7 @@ boost::shared_ptr OpenNIDriver::getDeviceByIndex (unsigned index) #ifndef _WIN32 boost::shared_ptr -OpenNIDriver::getDeviceBySerialNumber (const std::string& serial_number) const throw (OpenNIException) +OpenNIDriver::getDeviceBySerialNumber (const std::string& serial_number) const { std::map::const_iterator it = serial_map_.find (serial_number); @@ -308,7 +308,7 @@ OpenNIDriver::getDeviceBySerialNumber (const std::string& serial_number) const t } boost::shared_ptr -OpenNIDriver::getDeviceByAddress (unsigned char bus, unsigned char address) const throw (OpenNIException) +OpenNIDriver::getDeviceByAddress (unsigned char bus, unsigned char address) const { std::map >::const_iterator busIt = bus_map_.find (bus); if (busIt != bus_map_.end ()) diff --git a/openni_camera/src/openni_image_bayer_grbg.cpp b/openni_camera/src/openni_image_bayer_grbg.cpp index 564f6df..e1f3b54 100644 --- a/openni_camera/src/openni_image_bayer_grbg.cpp +++ b/openni_camera/src/openni_image_bayer_grbg.cpp @@ -62,7 +62,7 @@ bool ImageBayerGRBG::isResizingSupported (unsigned input_width, unsigned input_h return ImageBayerGRBG::resizingSupported (input_width, input_height, output_width, output_height); } -void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step) const throw (OpenNIException) +void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step) const { if (width > image_md_->XRes () || height > image_md_->YRes ()) THROW_OPENNI_EXCEPTION ("Upsampling not supported. Request was: %d x %d -> %d x %d", image_md_->XRes (), image_md_->YRes (), width, height); @@ -285,7 +285,7 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch } // downsampling } -void ImageBayerGRBG::fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step) const throw (OpenNIException) +void ImageBayerGRBG::fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step) const { if (width > image_md_->XRes () || height > image_md_->YRes ()) THROW_OPENNI_EXCEPTION ("Upsampling only possible for multiple of 2 in both dimensions. Request was %d x %d -> %d x %d.", image_md_->XRes (), image_md_->YRes (), width, height); diff --git a/openni_camera/src/openni_image_rgb24.cpp b/openni_camera/src/openni_image_rgb24.cpp index 0dd846a..acc066a 100644 --- a/openni_camera/src/openni_image_rgb24.cpp +++ b/openni_camera/src/openni_image_rgb24.cpp @@ -11,7 +11,7 @@ ImageRGB24::~ImageRGB24 () throw () { } -void ImageRGB24::fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step) const throw (OpenNIException) +void ImageRGB24::fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step) const { if (width > image_md_->XRes () || height > image_md_->YRes ()) THROW_OPENNI_EXCEPTION ("Up-sampling not supported. Request was %d x %d -> %d x %d.", image_md_->XRes (), image_md_->YRes (), width, height); @@ -43,7 +43,7 @@ void ImageRGB24::fillGrayscale (unsigned width, unsigned height, unsigned char* } } -void ImageRGB24::fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step) const throw (OpenNIException) +void ImageRGB24::fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step) const { if (width > image_md_->XRes () || height > image_md_->YRes ()) THROW_OPENNI_EXCEPTION ("Up-sampling not supported. Request was %d x %d -> %d x %d.", image_md_->XRes (), image_md_->YRes (), width, height); diff --git a/openni_camera/src/openni_image_yuv_422.cpp b/openni_camera/src/openni_image_yuv_422.cpp index d62af35..7e134db 100644 --- a/openni_camera/src/openni_image_yuv_422.cpp +++ b/openni_camera/src/openni_image_yuv_422.cpp @@ -58,7 +58,7 @@ bool ImageYUV422::isResizingSupported (unsigned input_width, unsigned input_heig return ImageYUV422::resizingSupported (input_width, input_height, output_width, output_height); } -void ImageYUV422::fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step) const throw (OpenNIException) +void ImageYUV422::fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step) const { // 0 1 2 3 // u y1 v y2 @@ -119,7 +119,7 @@ void ImageYUV422::fillRGB (unsigned width, unsigned height, unsigned char* rgb_b } } -void ImageYUV422::fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step) const throw (OpenNIException) +void ImageYUV422::fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step) const { // u y1 v y2 if (width > image_md_->XRes () || height > image_md_->YRes ()) diff --git a/openni_camera/src/openni_ir_image.cpp b/openni_camera/src/openni_ir_image.cpp index daab94c..a91989f 100644 --- a/openni_camera/src/openni_ir_image.cpp +++ b/openni_camera/src/openni_ir_image.cpp @@ -44,7 +44,7 @@ using namespace std; namespace openni_wrapper { -void IRImage::fillRaw (unsigned width, unsigned height, unsigned short* ir_buffer, unsigned line_step) const throw (OpenNIException) +void IRImage::fillRaw (unsigned width, unsigned height, unsigned short* ir_buffer, unsigned line_step) const { if (width > ir_md_->XRes () || height > ir_md_->YRes ()) THROW_OPENNI_EXCEPTION ("upsampling not supported: %d x %d -> %d x %d", ir_md_->XRes (), ir_md_->YRes (), width, height); From 3796be6c712d7880115fb03873894c0d02078ee1 Mon Sep 17 00:00:00 2001 From: v4hn Date: Wed, 14 Aug 2024 12:18:43 +0200 Subject: [PATCH 3/4] drop implicitly included use of boost _1 The symbol was included through ros_comm, but ROS-O plans to change that include due to excessive deprecation warnings: https://github.com/ros-o/ros_comm/pull/3 Lambdas should be preferred over bind these days. --- openni_camera/src/nodelets/driver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/openni_camera/src/nodelets/driver.cpp b/openni_camera/src/nodelets/driver.cpp index 204bc74..61a8388 100644 --- a/openni_camera/src/nodelets/driver.cpp +++ b/openni_camera/src/nodelets/driver.cpp @@ -88,7 +88,7 @@ void DriverNodelet::onInit () // Initialize dynamic reconfigure reconfigure_server_.reset( new ReconfigureServer(param_nh) ); - reconfigure_server_->setCallback(boost::bind(&DriverNodelet::configCb, this, _1, _2)); + reconfigure_server_->setCallback([this](auto cfg, uint32_t lvl){ configCb(cfg, lvl); }); // Setting up device can take awhile but onInit shouldn't block, so we spawn a // new thread to do all the initialization From 1dae828893830e44f6ecd682c4a194048c1069b6 Mon Sep 17 00:00:00 2001 From: v4hn Date: Wed, 14 Aug 2024 12:31:01 +0200 Subject: [PATCH 4/4] avoid "register" keyword it was officially deprecated since c++11 and removed in c++17 https://www.open-std.org/jtc1/sc22/wg21/docs/papers/2015/n4340 leading to compiler failure on standard systems by now. --- openni_camera/src/openni_image_bayer_grbg.cpp | 54 +++++++++---------- openni_camera/src/openni_image_yuv_422.cpp | 28 +++++----- 2 files changed, 41 insertions(+), 41 deletions(-) diff --git a/openni_camera/src/openni_image_bayer_grbg.cpp b/openni_camera/src/openni_image_bayer_grbg.cpp index e1f3b54..c3f26fe 100644 --- a/openni_camera/src/openni_image_bayer_grbg.cpp +++ b/openni_camera/src/openni_image_bayer_grbg.cpp @@ -79,7 +79,7 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch if (debayering_method_ == Bilinear) { // first line GRGRGR - for (register unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { gray_buffer[0] = bayer_pixel[0]; // green pixel gray_buffer[1] = AVG3 (bayer_pixel[0], bayer_pixel[2], bayer_pixel[1 + line_skip]); // interpolated green pixel @@ -89,14 +89,14 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch gray_buffer += 2 + gray_line_skip; bayer_pixel += 2; - for (register unsigned yIdx = 1; yIdx < height - 1; yIdx += 2) + for (unsigned yIdx = 1; yIdx < height - 1; yIdx += 2) { // blue line gray_buffer[0] = AVG3 (bayer_pixel[-line_skip], bayer_pixel[line_skip], bayer_pixel[1]); gray_buffer[1] = bayer_pixel[1]; gray_buffer += 2; bayer_pixel += 2; - for (register unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { gray_buffer[0] = AVG4 (bayer_pixel[-line_skip], bayer_pixel[line_skip], bayer_pixel[-1], bayer_pixel[1]); gray_buffer[1] = bayer_pixel[1]; @@ -104,7 +104,7 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch gray_buffer += gray_line_skip; // red line - for (register unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { gray_buffer[0] = bayer_pixel[0]; // green pixel gray_buffer[1] = AVG4 (bayer_pixel[0], bayer_pixel[2], bayer_pixel[-line_skip + 1], bayer_pixel[line_skip + 1]); // interpolated green pixel @@ -120,7 +120,7 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch gray_buffer[1] = bayer_pixel[1]; gray_buffer += 2; bayer_pixel += 2; - for (register unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { gray_buffer[0] = AVG3 (bayer_pixel[-1], bayer_pixel[1], bayer_pixel[-line_skip]); gray_buffer[1] = bayer_pixel[1]; @@ -130,7 +130,7 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch { int dv, dh; // first line GRGRGR - for (register unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { gray_buffer[0] = bayer_pixel[0]; // green pixel gray_buffer[1] = AVG3 (bayer_pixel[0], bayer_pixel[2], bayer_pixel[1 + line_skip]); // interpolated green pixel @@ -140,14 +140,14 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch gray_buffer += 2 + gray_line_skip; bayer_pixel += 2; - for (register unsigned yIdx = 1; yIdx < height - 1; yIdx += 2) + for (unsigned yIdx = 1; yIdx < height - 1; yIdx += 2) { // blue line gray_buffer[0] = AVG3 (bayer_pixel[-line_skip], bayer_pixel[line_skip], bayer_pixel[1]); gray_buffer[1] = bayer_pixel[1]; gray_buffer += 2; bayer_pixel += 2; - for (register unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { dv = abs (bayer_pixel[-line_skip] - bayer_pixel[line_skip]); dh = abs (bayer_pixel[-1] - bayer_pixel[1]); @@ -163,7 +163,7 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch gray_buffer += gray_line_skip; // red line - for (register unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { gray_buffer[0] = bayer_pixel[0]; @@ -187,7 +187,7 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch gray_buffer[1] = bayer_pixel[1]; gray_buffer += 2; bayer_pixel += 2; - for (register unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { gray_buffer[0] = AVG3 (bayer_pixel[-1], bayer_pixel[1], bayer_pixel[-line_skip]); gray_buffer[1] = bayer_pixel[1]; @@ -197,7 +197,7 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch { int dv, dh; // first line GRGRGR - for (register unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { gray_buffer[0] = bayer_pixel[0]; // green pixel gray_buffer[1] = AVG3 (bayer_pixel[0], bayer_pixel[2], bayer_pixel[1 + line_skip]); // interpolated green pixel @@ -207,14 +207,14 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch gray_buffer += 2 + gray_line_skip; bayer_pixel += 2; - for (register unsigned yIdx = 1; yIdx < height - 1; yIdx += 2) + for (unsigned yIdx = 1; yIdx < height - 1; yIdx += 2) { // blue line gray_buffer[0] = AVG3 (bayer_pixel[-line_skip], bayer_pixel[line_skip], bayer_pixel[1]); gray_buffer[1] = bayer_pixel[1]; gray_buffer += 2; bayer_pixel += 2; - for (register unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { dv = abs (bayer_pixel[-line_skip] - bayer_pixel[line_skip]); dh = abs (bayer_pixel[-1] - bayer_pixel[1]); @@ -230,7 +230,7 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch gray_buffer += gray_line_skip; // red line - for (register unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 0; xIdx < width - 2; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { gray_buffer[0] = bayer_pixel[0]; @@ -253,7 +253,7 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch gray_buffer[1] = bayer_pixel[1]; gray_buffer += 2; bayer_pixel += 2; - for (register unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) + for (unsigned xIdx = 2; xIdx < width; xIdx += 2, gray_buffer += 2, bayer_pixel += 2) { gray_buffer[0] = AVG3 (bayer_pixel[-1], bayer_pixel[1], bayer_pixel[-line_skip]); gray_buffer[1] = bayer_pixel[1]; @@ -269,15 +269,15 @@ void ImageBayerGRBG::fillGrayscale (unsigned width, unsigned height, unsigned ch THROW_OPENNI_EXCEPTION ("Downsampling only possible for multiple of 2 in both dimensions. Request was %d x %d -> %d x %d.", image_md_->XRes (), image_md_->YRes (), width, height); // fast method -> simply takes each or each 2nd pixel-group to get gray values out - register unsigned bayerXStep = image_md_->XRes () / width; - register unsigned bayerYSkip = (image_md_->YRes () / height - 1) * image_md_->XRes (); + unsigned bayerXStep = image_md_->XRes () / width; + unsigned bayerYSkip = (image_md_->YRes () / height - 1) * image_md_->XRes (); // Downsampling and debayering at once - register const XnUInt8* bayer_buffer = image_md_->WritableData (); + const XnUInt8* bayer_buffer = image_md_->WritableData (); - for (register unsigned yIdx = 0; yIdx < height; ++yIdx, bayer_buffer += bayerYSkip, gray_buffer += gray_line_skip) // skip a line + for (unsigned yIdx = 0; yIdx < height; ++yIdx, bayer_buffer += bayerYSkip, gray_buffer += gray_line_skip) // skip a line { - for (register unsigned xIdx = 0; xIdx < width; ++xIdx, ++gray_buffer, bayer_buffer += bayerXStep) + for (unsigned xIdx = 0; xIdx < width; ++xIdx, ++gray_buffer, bayer_buffer += bayerXStep) { *gray_buffer = AVG (bayer_buffer[0], bayer_buffer[ image_md_->XRes () + 1]); } @@ -298,8 +298,8 @@ void ImageBayerGRBG::fillRGB (unsigned width, unsigned height, unsigned char* rg if (image_md_->XRes () == width && image_md_->YRes () == height) { - register const XnUInt8 *bayer_pixel = image_md_->WritableData (); - register unsigned yIdx, xIdx; + const XnUInt8 *bayer_pixel = image_md_->WritableData (); + unsigned yIdx, xIdx; int bayer_line_step = image_md_->XRes (); int bayer_line_step2 = image_md_->XRes () << 1; @@ -1400,15 +1400,15 @@ void ImageBayerGRBG::fillRGB (unsigned width, unsigned height, unsigned char* rg THROW_OPENNI_EXCEPTION ("Downsampling only possible for integer scales in both dimensions. Request was %d x %d -> %d x %d.", image_md_->XRes (), image_md_->YRes (), width, height); // get each or each 2nd pixel group to find rgb values! - register unsigned bayerXStep = image_md_->XRes () / width; - register unsigned bayerYSkip = (image_md_->YRes () / height - 1) * image_md_->XRes (); + unsigned bayerXStep = image_md_->XRes () / width; + unsigned bayerYSkip = (image_md_->YRes () / height - 1) * image_md_->XRes (); // Downsampling and debayering at once - register const XnUInt8* bayer_buffer = image_md_->WritableData (); + const XnUInt8* bayer_buffer = image_md_->WritableData (); - for (register unsigned yIdx = 0; yIdx < height; ++yIdx, bayer_buffer += bayerYSkip, rgb_buffer += rgb_line_skip) // skip a line + for (unsigned yIdx = 0; yIdx < height; ++yIdx, bayer_buffer += bayerYSkip, rgb_buffer += rgb_line_skip) // skip a line { - for (register unsigned xIdx = 0; xIdx < width; ++xIdx, rgb_buffer += 3, bayer_buffer += bayerXStep) + for (unsigned xIdx = 0; xIdx < width; ++xIdx, rgb_buffer += 3, bayer_buffer += bayerXStep) { rgb_buffer[ 2 ] = bayer_buffer[ image_md_->XRes () ]; rgb_buffer[ 1 ] = AVG (bayer_buffer[0], bayer_buffer[ image_md_->XRes () + 1]); diff --git a/openni_camera/src/openni_image_yuv_422.cpp b/openni_camera/src/openni_image_yuv_422.cpp index 7e134db..3c397a1 100644 --- a/openni_camera/src/openni_image_yuv_422.cpp +++ b/openni_camera/src/openni_image_yuv_422.cpp @@ -73,7 +73,7 @@ void ImageYUV422::fillRGB (unsigned width, unsigned height, unsigned char* rgb_b THROW_OPENNI_EXCEPTION ("Downsampling only possible for power of two scale in both dimensions. Request was %d x %d -> %d x %d.", image_md_->XRes (), image_md_->YRes (), width, height); } - register const XnUInt8* yuv_buffer = image_md_->WritableData(); + const XnUInt8* yuv_buffer = image_md_->WritableData(); unsigned rgb_line_skip = 0; if (rgb_line_step != 0) @@ -81,9 +81,9 @@ void ImageYUV422::fillRGB (unsigned width, unsigned height, unsigned char* rgb_b if (image_md_->XRes() == width && image_md_->YRes() == height) { - for( register unsigned yIdx = 0; yIdx < height; ++yIdx, rgb_buffer += rgb_line_skip ) + for( unsigned yIdx = 0; yIdx < height; ++yIdx, rgb_buffer += rgb_line_skip ) { - for( register unsigned xIdx = 0; xIdx < width; xIdx += 2, rgb_buffer += 6, yuv_buffer += 4 ) + for( unsigned xIdx = 0; xIdx < width; xIdx += 2, rgb_buffer += 6, yuv_buffer += 4 ) { int v = yuv_buffer[2] - 128; int u = yuv_buffer[0] - 128; @@ -100,13 +100,13 @@ void ImageYUV422::fillRGB (unsigned width, unsigned height, unsigned char* rgb_b } else { - register unsigned yuv_step = image_md_->XRes() / width; - register unsigned yuv_x_step = yuv_step << 1; - register unsigned yuv_skip = (image_md_->YRes() / height - 1) * ( image_md_->XRes() << 1 ); + unsigned yuv_step = image_md_->XRes() / width; + unsigned yuv_x_step = yuv_step << 1; + unsigned yuv_skip = (image_md_->YRes() / height - 1) * ( image_md_->XRes() << 1 ); - for( register unsigned yIdx = 0; yIdx < image_md_->YRes(); yIdx += yuv_step, yuv_buffer += yuv_skip, rgb_buffer += rgb_line_skip ) + for( unsigned yIdx = 0; yIdx < image_md_->YRes(); yIdx += yuv_step, yuv_buffer += yuv_skip, rgb_buffer += rgb_line_skip ) { - for( register unsigned xIdx = 0; xIdx < image_md_->XRes(); xIdx += yuv_step, rgb_buffer += 3, yuv_buffer += yuv_x_step ) + for( unsigned xIdx = 0; xIdx < image_md_->XRes(); xIdx += yuv_step, rgb_buffer += 3, yuv_buffer += yuv_x_step ) { int v = yuv_buffer[2] - 128; int u = yuv_buffer[0] - 128; @@ -132,14 +132,14 @@ void ImageYUV422::fillGrayscale (unsigned width, unsigned height, unsigned char* if (gray_line_step != 0) gray_line_skip = gray_line_step - width; - register unsigned yuv_step = image_md_->XRes() / width; - register unsigned yuv_x_step = yuv_step << 1; - register unsigned yuv_skip = (image_md_->YRes() / height - 1) * ( image_md_->XRes() << 1 ); - register const XnUInt8* yuv_buffer = (image_md_->WritableData() + 1); + unsigned yuv_step = image_md_->XRes() / width; + unsigned yuv_x_step = yuv_step << 1; + unsigned yuv_skip = (image_md_->YRes() / height - 1) * ( image_md_->XRes() << 1 ); + const XnUInt8* yuv_buffer = (image_md_->WritableData() + 1); - for( register unsigned yIdx = 0; yIdx < image_md_->YRes(); yIdx += yuv_step, yuv_buffer += yuv_skip, gray_buffer += gray_line_skip ) + for( unsigned yIdx = 0; yIdx < image_md_->YRes(); yIdx += yuv_step, yuv_buffer += yuv_skip, gray_buffer += gray_line_skip ) { - for( register unsigned xIdx = 0; xIdx < image_md_->XRes(); xIdx += yuv_step, ++gray_buffer, yuv_buffer += yuv_x_step ) + for( unsigned xIdx = 0; xIdx < image_md_->XRes(); xIdx += yuv_step, ++gray_buffer, yuv_buffer += yuv_x_step ) { *gray_buffer = *yuv_buffer; }