Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 22 additions & 0 deletions src/image_transport_snippets.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0"?>
<example>
<title>Image Transport Snippets</title>
<description>Collection of snippets for using image transport</description>
<ros_version>kinetic</ros_version>
<tag>cv_bridge</tag>
<tag>image_transport</tag>
<tag>image_geometry</tag>
<tag>roscpp</tag>
<time_limit>2</time_limit>
<language>
<name>cpp</name>
<run_cmd>rosrun image_transport_snippets camera_subscriber_snippet</run_cmd>
<start_file>src/camera_subscriber_snippet.cpp</start_file>
</language>
<feedback>
<tab>terminal</tab>
</feedback>
<feedback>
<tab>nodes</tab>
</feedback>
</example>
32 changes: 32 additions & 0 deletions src/image_transport_snippets/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
cmake_minimum_required(VERSION 2.8.3)
project(image_transport_snippets)

add_definitions(-std=c++11)
find_package(catkin REQUIRED COMPONENTS
cv_bridge
image_transport
image_geometry
roscpp
tf2_ros
)

catkin_package(
)

include_directories(
${catkin_INCLUDE_DIRS}
)

add_executable(camera_subscriber_snippet src/camera_subscriber_snippet.cpp)
target_link_libraries(camera_subscriber_snippet ${catkin_LIBRARIES})

## Install C++ Examples
install(TARGETS camera_subscriber_snippet
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

## Install Other Resources
install(DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
20 changes: 20 additions & 0 deletions src/image_transport_snippets/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<?xml version="1.0"?>
<package format="2">
<name>image_transport_snippets</name>
<version>0.0.0</version>
<description>Code snippets for nodes using image_transport</description>

<maintainer email="st.fuchs.tr@gmail.com">Steffen Fuchs</maintainer>
<author email="st.fuchs.tr@gmail.com">Steffen Fuchs</author>
<license>BSD</license>


<buildtool_depend>catkin</buildtool_depend>

<depend>cv_bridge</depend>
<depend>image_transport</depend>
<depend>image_geometry</depend>
<depend>roscpp</depend>
<depend>tf2_ros</depend>

</package>
97 changes: 97 additions & 0 deletions src/image_transport_snippets/src/camera_subscriber_snippet.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <image_geometry/pinhole_camera_model.h>
#include <cv_bridge/cv_bridge.h>

class CameraSubscriberNode
{
public:
CameraSubscriberNode(const ros::NodeHandle& nh=ros::NodeHandle(),
const ros::NodeHandle& nh_private=ros::NodeHandle("~"))
: active_(false)
, nh_(nh)
, nh_priv_(nh_private)
{}

// We follow the design for managed nodes:
// http://design.ros2.org/articles/node_lifecycle.html
bool configure();
bool cleanup();
bool activate();
bool deactivate();

void imageCb(const sensor_msgs::ImageConstPtr& img_msg,
const sensor_msgs::CameraInfoConstPtr& info_msg);

private:
bool active_;

ros::NodeHandle nh_;
ros::NodeHandle nh_priv_;
std::unique_ptr<image_transport::ImageTransport> it_;
image_transport::CameraSubscriber sub_img_;
image_transport::Publisher pub_img_;
image_geometry::PinholeCameraModel camera_model_;
};

// Definitions

bool CameraSubscriberNode::configure()
{
it_.reset( new image_transport::ImageTransport(nh_) );
sub_img_ = it_->subscribeCamera("image_input", 5, &CameraSubscriberNode::imageCb, this);
pub_img_ = it_->advertise("image_output", 1);

return true;
}

bool CameraSubscriberNode::cleanup()
{
sub_img_.shutdown();
it_.reset();

return true;
}

bool CameraSubscriberNode::activate()
{
return active_ = true;
}

bool CameraSubscriberNode::deactivate()
{
return !(active_ = false);
}

void CameraSubscriberNode::imageCb(
const sensor_msgs::ImageConstPtr& img_msg,
const sensor_msgs::CameraInfoConstPtr& info_msg)
{
if (!active_) return;

camera_model_.fromCameraInfo(info_msg);
// do somthing read only
const cv::Mat img = cv_bridge::toCvShare(img_msg)->image;
// ..

// modifiy the image
cv::Mat img_modified;
img.copyTo(img_modified);
pub_img_.publish(
cv_bridge::CvImage(
img_msg->header,
img_msg->encoding,
img_modified).toImageMsg());
}


int main(int argc, char** argv)
{
ros::init(argc, argv, "camera_subscriber_node");
CameraSubscriberNode node;
// because there is no lifecycle manager, we need to trigger
// transitions manually
node.configure();
node.activate();
ros::spin();
}