Skip to content

Commit

Permalink
New package to advertise virtual RGB-D camera
Browse files Browse the repository at this point in the history
it publishes:

- camera_info with calibration_file.
- image with image_file.
- points with pcd_file.
  • Loading branch information
wkentaro committed Oct 10, 2016
1 parent ebef339 commit 8ddacf4
Show file tree
Hide file tree
Showing 13 changed files with 307,812 additions and 1 deletion.
2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ env:
- ROS_DISTRO=hydro USE_DEB=false CATKIN_TOOLS_BUILD_OPTIONS="-iv --summarize --no-status --no-color"
- ROS_DISTRO=indigo USE_DEB=true
- ROS_DISTRO=indigo USE_DEB=false BEFORE_SCRIPT='$CI_SOURCE_PATH/.travis_before_script_released_testing.bash' ROS_REPOSITORY_PATH="http://packages.ros.org/ros/ubuntu"
- ROS_DISTRO=indigo USE_DEB=false BEFORE_SCRIPT='$CI_SOURCE_PATH/.travis_before_script_opencv3.bash' BUILD_PKGS='checkerboard_detector imagesift jsk_perception jsk_recognition_utils resized_image_transport'
- ROS_DISTRO=indigo USE_DEB=false BEFORE_SCRIPT='$CI_SOURCE_PATH/.travis_before_script_opencv3.bash' BUILD_PKGS='checkerboard_detector imagesift jsk_perception jsk_recognition_utils resized_image_transport virtual_camera'
- ROS_DISTRO=indigo USE_DEB=true BEFORE_SCRIPT='$CI_SOURCE_PATH/.travis_before_script_pcl1.8.bash' BUILD_PKGS='jsk_pcl_ros_utils jsk_pcl_ros'
- ROS_DISTRO=jade USE_DEB=false
script:
Expand Down
100 changes: 100 additions & 0 deletions virtual_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
cmake_minimum_required(VERSION 2.8.3)
project(virtual_camera)

find_package(catkin REQUIRED
COMPONENTS
camera_info_manager
cv_bridge
nodelet
pcl_conversions
roscpp
sensor_msgs
std_msgs
)

find_package(Boost REQUIRED)
find_package(OpenCV REQUIRED)
find_package(PCL REQUIRED)


###################################
## catkin specific configuration ##
###################################

catkin_package(
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS
camera_info_manager
nodelet
pcl_conversions
roscpp
sensor_msgs
std_msgs
#
DEPENDS
Boost
OpenCV
PCL
)

###########
## Build ##
###########

include_directories(
include
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)

add_library(${PROJECT_NAME} src/virtual_camera_driver.cpp)

target_link_libraries(${PROJECT_NAME}
${catkin_LIBRARIES}
${Boost_LIBRARIES}
${OpenCV_LIBRARIES}
${PCL_LIBRARIES}
)

#############
## Install ##
#############

install(PROGRAMS
scripts/driver
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(TARGETS
${PROJECT_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY
include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)

install(DIRECTORY
sample
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

install(FILES
nodelets.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

#############
## Testing ##
#############

if(CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
add_rostest(test/driver.test)
endif()
93 changes: 93 additions & 0 deletions virtual_camera/include/virtual_camera/virtual_camera_driver.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,93 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2016, Kentaro Wada
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/o2r other materials provided
* with the distribution.
* * Neither the name of the Kentaro Wada nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#ifndef VIRTUAL_CAMERA_VIRTUAL_CAMERA_DRIVER_H_
#define VIRTUAL_CAMERA_VIRTUAL_CAMERA_DRIVER_H_

#include <boost/shared_ptr.hpp>
#include <boost/thread/mutex.hpp>

#include <nodelet/nodelet.h>
#include <ros/ros.h>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/PointCloud2.h>

namespace virtual_camera
{

class VirtualCameraDriver: public nodelet::Nodelet
{
public:
VirtualCameraDriver():
publish_info_(false),
publish_image_(false),
publish_cloud_(false),
time_prev_pub_info_(ros::Time(0)),
time_prev_pub_image_(ros::Time(0)),
time_prev_pub_cloud_(ros::Time(0)) {}
protected:
virtual void onInit();
void publishCb(const ros::TimerEvent& event);

boost::mutex mutex_;

ros::NodeHandle* nh_;
ros::NodeHandle* pnh_;

ros::Timer timer_pub_;

ros::Publisher pub_info_;
ros::Publisher pub_image_;
ros::Publisher pub_cloud_;

sensor_msgs::CameraInfo info_msg_;
sensor_msgs::ImagePtr image_msg_;
sensor_msgs::PointCloud2 cloud_msg_;

bool publish_info_;
bool publish_image_;
bool publish_cloud_;
double rate_info_;
double rate_image_;
double rate_cloud_;
ros::Time time_prev_pub_info_;
ros::Time time_prev_pub_image_;
ros::Time time_prev_pub_cloud_;
private:
};

} // namespace virtual_camera

#endif // VIRTUAL_CAMERA_VIRTUAL_CAMERA_DRIVER_H_
11 changes: 11 additions & 0 deletions virtual_camera/nodelets.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<library path="lib/libvirtual_camera">

<class name="virtual_camera/driver"
type="virtual_camera::VirtualCameraDriver"
base_class_type="nodelet::Nodelet">
<description>
Virtual camera driver nodelet.
</description>
</class>

</library>
46 changes: 46 additions & 0 deletions virtual_camera/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
<?xml version="1.0"?>
<package>
<name>virtual_camera</name>
<version>0.3.25</version>
<description>A virtual ROS driver for RGB-D cameras.</description>
<maintainer email="[email protected]">Kentaro Wada</maintainer>
<license>BSD</license>
<url type="website">https://github.com/jsk-ros-pkg/jsk_recognition</url>
<author email="[email protected]">Kentaro Wada</author>

<buildtool_depend>catkin</buildtool_depend>

<!-- alphabetical order -->
<build_depend>boost</build_depend>
<build_depend>camera_info_manager</build_depend>
<build_depend>cv_bridge</build_depend>
<build_depend>libopencv-dev</build_depend>
<build_depend>libpcl-all-dev</build_depend>
<build_depend>nodelet</build_depend>
<build_depend>pcl_conversions</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<!-- alphabetical order -->

<!-- alphabetical order -->
<run_depend>boost</run_depend>
<run_depend>camera_info_manager</run_depend>
<run_depend>cv_bridge</run_depend>
<run_depend>libopencv-dev</run_depend>
<run_depend>libpcl-all-dev</run_depend>
<run_depend>nodelet</run_depend>
<run_depend>pcl_conversions</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<!-- alphabetical order -->

<!-- alphabetical order -->
<test_depend>rostest</test_depend>
<!-- alphabetical order -->

<export>
<nodelet plugin="${prefix}/nodelets.xml"/>
</export>
</package>
Loading

0 comments on commit 8ddacf4

Please sign in to comment.