Turned modified tutorial publisher into actual rover_camera node

This commit is contained in:
2017-12-27 16:26:53 -08:00
parent e2f419db4f
commit f207446293
21 changed files with 69 additions and 526 deletions

View File

@@ -0,0 +1,29 @@
cmake_minimum_required(VERSION 2.8)
project(rover_camera)
find_package(catkin REQUIRED COMPONENTS cv_bridge image_transport message_generation sensor_msgs)
# add the resized image message
catkin_package(CATKIN_DEPENDS cv_bridge image_transport message_runtime sensor_msgs)
find_package(OpenCV)
include_directories(include ${catkin_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS})
# add the publisher example
add_executable(rover_camera src/rover_camera.cpp)
add_dependencies(rover_camera ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
target_link_libraries(rover_camera ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
# Mark executables and/or libraries for installation
install(TARGETS rover_camera
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
#install(FILES resized_plugins.xml
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
#)

View File

@@ -0,0 +1,22 @@
<launch>
<group ns="cameras">
<node name="camera_name" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 1" output="screen">
<param name="device_path" value="/dev/video0"/>
</node>
<!--
<node name="main_navigation" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 2" output="screen" >
<param name="device_path" value="/dev/rover/camera_main_navigation" />
</node>
<node name="gimbal" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 3" output="screen" >
<param name="device_path" value="/dev/rover/camera_gimbal" />
</node>
-->
</group>
<node name="image_view" pkg="image_view" type="image_view" launch-prefix="taskset -c 4" output="screen">
<remap from="image" to="/cameras/camera_name/image_720p"/>
</node>
</launch>

View File

@@ -0,0 +1,23 @@
<package>
<name>rover_camera</name>
<version>0.0.0</version>
<description>This package opens a camera on linux using OpenCV and publishes multiple streams at different resolutions</description>
<author>Corwin Perren</author>
<maintainer email="caperren@gmail.com">Corwin Perren</maintainer>
<license>Apache 2.0</license>
<build_depend>cv_bridge</build_depend>
<build_depend>image_transport</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>opencv2</build_depend>
<build_depend>sensor_msgs</build_depend>
<run_depend>cv_bridge</run_depend>
<run_depend>image_transport</run_depend>
<run_depend>message_runtime</run_depend>
<run_depend>opencv2</run_depend>
<run_depend>sensor_msgs</run_depend>
<buildtool_depend>catkin</buildtool_depend>
</package>

View File

@@ -0,0 +1,73 @@
#include <string.h>
#include <iostream>
#include <ros/ros.h>
#include <ros/console.h>
#include <image_transport/image_transport.h>
#include <opencv2/opencv.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <cv_bridge/cv_bridge.h>
int main(int argc, char** argv)
{
std::string capture_device_path;
int fps;
int large_image_width;
int large_image_height;
int small_image_width;
int small_image_height;
ros::init(argc, argv, "camera");
ros::NodeHandle node_handle("~");
node_handle.param("device_path", capture_device_path, std::string("/dev/video0"));
node_handle.param("fps", fps, 30);
node_handle.param("large_image_width", large_image_width, 1280);
node_handle.param("large_image_height", large_image_height, 720);
node_handle.param("small_image_width", small_image_width, 640);
node_handle.param("small_image_height", small_image_height, 360);
cv::VideoCapture cap(capture_device_path);
cap.set(CV_CAP_PROP_FOURCC, CV_FOURCC('M', 'J', 'P', 'G'));
cap.set(CV_CAP_PROP_FRAME_WIDTH, large_image_width);
cap.set(CV_CAP_PROP_FRAME_HEIGHT, large_image_height);
cap.set(CV_CAP_PROP_FPS, fps);
if(cap.isOpened() == false){
return -1;
}
image_transport::ImageTransport full_res_image_transport(node_handle);
image_transport::ImageTransport lower_res_image_transport(node_handle);
image_transport::Publisher full_size_publisher = full_res_image_transport.advertise("image_720p", 1);
image_transport::Publisher lower_size_publisher = lower_res_image_transport.advertise("image_360p", 1);
cv::Mat image;
cv::Mat image_smaller;
ros::Rate loop_rate(fps + 5);
while (node_handle.ok()) {
cap.read(image);
if(!image.empty()){
cv::resize(image, image_smaller, cv::Size(small_image_width, small_image_height));
sensor_msgs::ImagePtr full_res_message = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
sensor_msgs::ImagePtr lower_res_message = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_smaller).toImageMsg();
full_size_publisher.publish(full_res_message);
lower_size_publisher.publish(lower_res_message);
}
ros::spinOnce();
loop_rate.sleep();
}
}