Skip to content

Commit

Permalink
remove boost and unused files (#122)
Browse files Browse the repository at this point in the history
* replace boost functionality by standard C++
* remove ROS nodelet metadata
* store parameter callback
* remove ROS1 node
* remove unused os import

Co-authored-by: Christian Rauch <Rauch.Christian@gmx.de>
  • Loading branch information
mikeferguson and christianrauch committed Feb 23, 2023
1 parent 2a22f7d commit c930cd7
Show file tree
Hide file tree
Showing 18 changed files with 120 additions and 255 deletions.
6 changes: 1 addition & 5 deletions openni2_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

find_package(Boost REQUIRED COMPONENTS system thread)
find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(camera_info_manager REQUIRED)
Expand All @@ -28,7 +27,6 @@ rosidl_generate_interfaces(${PROJECT_NAME}

include_directories(
include
${Boost_INCLUDE_DIRS}
${PC_OPENNI2_INCLUDE_DIRS}
)

Expand All @@ -45,7 +43,6 @@ add_library(openni2_wrapper SHARED
src/openni2_video_mode.cpp
)
target_link_libraries(openni2_wrapper
${Boost_LIBRARIES}
${PC_OPENNI2_LIBRARIES}
)
ament_target_dependencies(openni2_wrapper
Expand All @@ -59,14 +56,13 @@ ament_target_dependencies(openni2_wrapper
)

#add_executable(test_wrapper test/test_wrapper.cpp)
#target_link_libraries(test_wrapper openni2_wrapper ${Boost_LIBRARIES})
#target_link_libraries(test_wrapper openni2_wrapper)

add_library(openni2_camera_lib SHARED
src/openni2_driver.cpp
)
target_link_libraries(openni2_camera_lib
openni2_wrapper
${Boost_LIBRARIE}
)
ament_target_dependencies(openni2_camera_lib
camera_info_manager
Expand Down
29 changes: 13 additions & 16 deletions openni2_camera/include/openni2_camera/openni2_device.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,7 @@

#include "openni2_camera/openni2_exception.h"

#include <boost/shared_ptr.hpp>
#include <boost/cstdint.hpp>
#include <boost/bind.hpp>
#include <boost/function.hpp>
#include <functional>

#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>
Expand All @@ -58,7 +55,7 @@ class SensorInfo;
namespace openni2_wrapper
{

typedef boost::function<void(sensor_msgs::msg::Image::SharedPtr image)> FrameCallbackFunction;
typedef std::function<void(sensor_msgs::msg::Image::SharedPtr image)> FrameCallbackFunction;

class OpenNI2FrameListener;

Expand Down Expand Up @@ -139,20 +136,20 @@ class OpenNI2Device
protected:
void shutdown();

boost::shared_ptr<openni::VideoStream> getIRVideoStream() const;
boost::shared_ptr<openni::VideoStream> getColorVideoStream() const;
boost::shared_ptr<openni::VideoStream> getDepthVideoStream() const;
std::shared_ptr<openni::VideoStream> getIRVideoStream() const;
std::shared_ptr<openni::VideoStream> getColorVideoStream() const;
std::shared_ptr<openni::VideoStream> getDepthVideoStream() const;

boost::shared_ptr<openni::Device> openni_device_;
boost::shared_ptr<openni::DeviceInfo> device_info_;
std::shared_ptr<openni::Device> openni_device_;
std::shared_ptr<openni::DeviceInfo> device_info_;

boost::shared_ptr<OpenNI2FrameListener> ir_frame_listener;
boost::shared_ptr<OpenNI2FrameListener> color_frame_listener;
boost::shared_ptr<OpenNI2FrameListener> depth_frame_listener;
std::shared_ptr<OpenNI2FrameListener> ir_frame_listener;
std::shared_ptr<OpenNI2FrameListener> color_frame_listener;
std::shared_ptr<OpenNI2FrameListener> depth_frame_listener;

mutable boost::shared_ptr<openni::VideoStream> ir_video_stream_;
mutable boost::shared_ptr<openni::VideoStream> color_video_stream_;
mutable boost::shared_ptr<openni::VideoStream> depth_video_stream_;
mutable std::shared_ptr<openni::VideoStream> ir_video_stream_;
mutable std::shared_ptr<openni::VideoStream> color_video_stream_;
mutable std::shared_ptr<openni::VideoStream> depth_video_stream_;

mutable std::vector<OpenNI2VideoMode> ir_video_modes_;
mutable std::vector<OpenNI2VideoMode> color_video_modes_;
Expand Down
2 changes: 0 additions & 2 deletions openni2_camera/include/openni2_camera/openni2_device_info.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,6 @@

#include <ostream>

#include <boost/cstdint.hpp>

namespace openni2_wrapper
{

Expand Down
16 changes: 7 additions & 9 deletions openni2_camera/include/openni2_camera/openni2_device_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,6 @@

#include "openni2_camera/openni2_device_info.h"

#include <boost/thread/mutex.hpp>

#include <rclcpp/rclcpp.hpp>

#include <vector>
Expand All @@ -54,21 +52,21 @@ class OpenNI2DeviceManager
OpenNI2DeviceManager();
virtual ~OpenNI2DeviceManager();

static boost::shared_ptr<OpenNI2DeviceManager> getSingelton();
static std::shared_ptr<OpenNI2DeviceManager> getSingelton();

boost::shared_ptr<std::vector<OpenNI2DeviceInfo> > getConnectedDeviceInfos() const;
boost::shared_ptr<std::vector<std::string> > getConnectedDeviceURIs() const;
std::shared_ptr<std::vector<OpenNI2DeviceInfo> > getConnectedDeviceInfos() const;
std::shared_ptr<std::vector<std::string> > getConnectedDeviceURIs() const;
std::size_t getNumOfConnectedDevices() const;

boost::shared_ptr<OpenNI2Device> getAnyDevice(rclcpp::Node* node);
boost::shared_ptr<OpenNI2Device> getDevice(const std::string& device_URI, rclcpp::Node* node);
std::shared_ptr<OpenNI2Device> getAnyDevice(rclcpp::Node* node);
std::shared_ptr<OpenNI2Device> getDevice(const std::string& device_URI, rclcpp::Node* node);

std::string getSerial(const std::string& device_URI) const;

protected:
boost::shared_ptr<OpenNI2DeviceListener> device_listener_;
std::shared_ptr<OpenNI2DeviceListener> device_listener_;

static boost::shared_ptr<OpenNI2DeviceManager> singelton_;
static std::shared_ptr<OpenNI2DeviceManager> singelton_;
};


Expand Down
13 changes: 6 additions & 7 deletions openni2_camera/include/openni2_camera/openni2_driver.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,7 @@
#ifndef OPENNI2_DRIVER_H
#define OPENNI2_DRIVER_H

#include <boost/shared_ptr.hpp>
#include <boost/cstdint.hpp>
#include <boost/bind.hpp>
#include <boost/function.hpp>
#include <functional>

#include <sensor_msgs/msg/image.hpp>

Expand Down Expand Up @@ -110,8 +107,8 @@ class OpenNI2Driver : public rclcpp::Node

void forceSetExposure();

boost::shared_ptr<OpenNI2DeviceManager> device_manager_;
boost::shared_ptr<OpenNI2Device> device_;
std::shared_ptr<OpenNI2DeviceManager> device_manager_;
std::shared_ptr<OpenNI2Device> device_;

std::string device_id_;
int bus_id_;
Expand All @@ -131,7 +128,7 @@ class OpenNI2Driver : public rclcpp::Node
/** \brief get_serial server*/
rclcpp::Service<openni2_camera::srv::GetSerial>::SharedPtr get_serial_server;

boost::mutex connect_mutex_;
std::mutex connect_mutex_;
// published topics
image_transport::CameraPublisher pub_color_;
image_transport::CameraPublisher pub_depth_;
Expand All @@ -145,6 +142,8 @@ class OpenNI2Driver : public rclcpp::Node
/** \brief Camera info manager objects. */
std::shared_ptr<camera_info_manager::CameraInfoManager> color_info_manager_, ir_info_manager_;

OnSetParametersCallbackHandle::SharedPtr parameters_callback_;

OpenNI2VideoMode ir_video_mode_;
OpenNI2VideoMode color_video_mode_;
OpenNI2VideoMode depth_video_mode_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ class OpenNI2FrameListener : public openni::VideoStream::NewFrameListener
FrameCallbackFunction callback_;

bool user_device_timer_;
boost::shared_ptr<OpenNI2TimerFilter> timer_filter_;
std::shared_ptr<OpenNI2TimerFilter> timer_filter_;

rclcpp::Node* node_; // needed for time
rclcpp::Time prev_time_stamp_;
Expand Down
2 changes: 0 additions & 2 deletions openni2_camera/launch/camera_only.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,6 @@
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

import os

import launch
import launch_ros.actions
import launch_ros.descriptions
Expand Down
2 changes: 0 additions & 2 deletions openni2_camera/launch/camera_with_cloud.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,6 @@
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.

import os

import launch
import launch_ros.actions
import launch_ros.descriptions
Expand Down
10 changes: 0 additions & 10 deletions openni2_camera/openni2_nodelets.xml

This file was deleted.

1 change: 0 additions & 1 deletion openni2_camera/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>

<depend>boost</depend>
<depend>builtin_interfaces</depend>
<depend>camera_info_manager</depend>
<depend>libopenni2-dev</depend>
Expand Down
45 changes: 0 additions & 45 deletions openni2_camera/ros/openni2_camera_node.cpp

This file was deleted.

57 changes: 0 additions & 57 deletions openni2_camera/ros/openni2_camera_nodelet.cpp

This file was deleted.

2 changes: 1 addition & 1 deletion openni2_camera/src/list_devices.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ using openni2_wrapper::OpenNI2Exception;
int main(int arc, char** argv)
{
openni2_wrapper::OpenNI2DeviceManager manager;
boost::shared_ptr<std::vector<openni2_wrapper::OpenNI2DeviceInfo> > device_infos = manager.getConnectedDeviceInfos();
std::shared_ptr<std::vector<openni2_wrapper::OpenNI2DeviceInfo> > device_infos = manager.getConnectedDeviceInfos();
std::cout << "Found " << device_infos->size() << " devices:" << std::endl << std::endl;
for (size_t i = 0; i < device_infos->size(); ++i)
{
Expand Down
2 changes: 0 additions & 2 deletions openni2_camera/src/openni2_convert.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,6 @@
#include "openni2_camera/openni2_convert.h"
#include "openni2_camera/openni2_exception.h"

#include <boost/make_shared.hpp>

#include <string>

namespace openni2_wrapper
Expand Down
Loading

0 comments on commit c930cd7

Please sign in to comment.