mirror of
https://github.com/caperren/school_archives.git
synced 2025-11-09 21:51:15 +00:00
Added 2017-2018 mars rover repository.
This commit is contained in:
@@ -0,0 +1,46 @@
|
||||
cmake_minimum_required(VERSION 2.8)
|
||||
project(rover_camera)
|
||||
|
||||
add_compile_options(-std=c++11)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
cv_bridge
|
||||
image_transport
|
||||
message_generation
|
||||
sensor_msgs
|
||||
std_msgs
|
||||
)
|
||||
|
||||
# add the resized image message
|
||||
add_message_files(
|
||||
FILES
|
||||
CameraControlMessage.msg
|
||||
)
|
||||
|
||||
generate_messages(
|
||||
DEPENDENCIES
|
||||
std_msgs
|
||||
)
|
||||
|
||||
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}
|
||||
#)
|
||||
@@ -0,0 +1,18 @@
|
||||
<launch>
|
||||
<group ns="cameras">
|
||||
<node name="undercarriage" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 1" output="screen">
|
||||
<param name="device_path" value="/dev/rover/camera_undercarriage"/>
|
||||
</node>
|
||||
|
||||
<node name="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="chassis" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 3" output="screen" >
|
||||
<param name="device_path" value="/dev/rover/camera_chassis" />
|
||||
</node>
|
||||
|
||||
|
||||
</group>
|
||||
</launch>
|
||||
@@ -0,0 +1,3 @@
|
||||
bool enable_small_broadcast
|
||||
bool enable_medium_broadcast
|
||||
bool enable_large_broadcast
|
||||
@@ -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>
|
||||
@@ -0,0 +1,194 @@
|
||||
#include <string>
|
||||
#include <iostream>
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <ros/console.h>
|
||||
#include <image_transport/image_transport.h>
|
||||
#include <opencv2/opencv.hpp>
|
||||
|
||||
#include <cv_bridge/cv_bridge.h>
|
||||
|
||||
#include "rover_camera/CameraControlMessage.h"
|
||||
|
||||
// Useful info
|
||||
// RTSP stream is 704x480
|
||||
// 3 image channels
|
||||
// Image type 16
|
||||
|
||||
class RoverCamera{
|
||||
public:
|
||||
RoverCamera(int argc, char** argv){
|
||||
ros::init(argc, argv, "camera");
|
||||
|
||||
node_handle = new ros::NodeHandle("~");
|
||||
|
||||
node_handle->param("is_rtsp_camera", is_rtsp_camera, false);
|
||||
node_handle->param("device_path", capture_device_path, std::string("/dev/video0"));
|
||||
node_handle->param("fps", fps, 30);
|
||||
|
||||
node_handle->param("upside_down", upside_down, false);
|
||||
|
||||
node_handle->param("large_image_width", large_image_width, 1280);
|
||||
node_handle->param("large_image_height", large_image_height, 720);
|
||||
node_handle->param("medium_image_width", medium_image_width, 640);
|
||||
node_handle->param("medium_image_height", medium_image_height, 360);
|
||||
node_handle->param("small_image_width", small_image_width, 256);
|
||||
node_handle->param("small_image_height", small_image_height, 144);
|
||||
|
||||
broadcast_large_image = false;
|
||||
broadcast_medium_image = false;
|
||||
broadcast_small_image = true;
|
||||
|
||||
if(is_rtsp_camera){
|
||||
cap = new cv::VideoCapture(capture_device_path);
|
||||
ROS_INFO_STREAM("Connecting to RTSP camera with path: " << capture_device_path);
|
||||
|
||||
}else{
|
||||
cap = new cv::VideoCapture(capture_device_path);
|
||||
ROS_INFO_STREAM("Connecting to USB camera with path: " << 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);
|
||||
}
|
||||
|
||||
large_image_node_name = "image_" + std::to_string(large_image_width) + "x" + std::to_string(large_image_height);
|
||||
medium_image_node_name = "image_" + std::to_string(medium_image_width) + "x" + std::to_string(medium_image_height);
|
||||
small_image_node_name = "image_" + std::to_string(small_image_width) + "x" + std::to_string(small_image_height);
|
||||
|
||||
large_image_transport = new image_transport::ImageTransport(*node_handle);
|
||||
medium_image_transport = new image_transport::ImageTransport(*node_handle);
|
||||
small_image_transport = new image_transport::ImageTransport(*node_handle);
|
||||
|
||||
large_image_publisher = large_image_transport->advertise(large_image_node_name, 1);
|
||||
medium_image_publisher = medium_image_transport->advertise(medium_image_node_name, 1);
|
||||
small_image_publisher = small_image_transport->advertise(small_image_node_name, 1);
|
||||
|
||||
control_subscriber = node_handle->subscribe("camera_control", 1, &RoverCamera::control_callback, this);
|
||||
|
||||
if(is_rtsp_camera){
|
||||
loop_rate = new ros::Rate(fps + 10);
|
||||
}else{
|
||||
loop_rate = new ros::Rate(fps + 2);
|
||||
}
|
||||
|
||||
image_black = cv::Mat(large_image_height, large_image_width, CV_8UC3, CvScalar(0, 0, 0));
|
||||
}
|
||||
|
||||
void run(){
|
||||
if(!cap->isOpened()){
|
||||
return;
|
||||
}
|
||||
|
||||
while (ros::ok()) {
|
||||
|
||||
if(!is_rtsp_camera) {
|
||||
cap->read(image_large);
|
||||
}else{
|
||||
cap->read(image_rtsp_raw);
|
||||
image_black.copyTo(image_large);
|
||||
|
||||
float image_scalar = float(image_large.rows) / image_rtsp_raw.rows;
|
||||
|
||||
cv::resize(image_rtsp_raw, image_rtsp_scaled, CvSize(int(image_rtsp_raw.cols * image_scalar), int(image_rtsp_raw.rows * image_scalar)));
|
||||
|
||||
int x = (image_large.cols - image_rtsp_scaled.cols) / 2;
|
||||
|
||||
image_rtsp_scaled.copyTo(image_large(CvRect(x , 0, image_rtsp_scaled.cols, image_rtsp_scaled.rows)));
|
||||
}
|
||||
|
||||
if(!image_large.empty()){
|
||||
if(upside_down){
|
||||
cv::flip(image_large, image_large, -1);
|
||||
}
|
||||
|
||||
if(broadcast_large_image){
|
||||
large_image_message = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_large).toImageMsg();
|
||||
large_image_publisher.publish(large_image_message);
|
||||
}else if(broadcast_medium_image){
|
||||
cv::resize(image_large, image_medium, cv::Size(medium_image_width, medium_image_height));
|
||||
medium_image_message = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_medium).toImageMsg();
|
||||
medium_image_publisher.publish(medium_image_message);
|
||||
}else if(broadcast_small_image){
|
||||
cv::resize(image_large, image_small, cv::Size(small_image_width, small_image_height));
|
||||
small_image_message = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_small).toImageMsg();
|
||||
small_image_publisher.publish(small_image_message);
|
||||
}
|
||||
}
|
||||
|
||||
ros::spinOnce();
|
||||
loop_rate->sleep();
|
||||
}
|
||||
}
|
||||
|
||||
void control_callback(const rover_camera::CameraControlMessage::ConstPtr& msg){
|
||||
broadcast_small_image = msg->enable_small_broadcast;
|
||||
broadcast_medium_image = msg->enable_medium_broadcast;
|
||||
broadcast_large_image = msg->enable_large_broadcast;
|
||||
}
|
||||
|
||||
~RoverCamera(){
|
||||
if(cap->isOpened()){
|
||||
cap->release();
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
ros::NodeHandle *node_handle;
|
||||
|
||||
cv::VideoCapture *cap;
|
||||
|
||||
bool is_rtsp_camera;
|
||||
|
||||
std::string capture_device_path;
|
||||
int fps;
|
||||
|
||||
ros::Rate *loop_rate;
|
||||
|
||||
bool upside_down;
|
||||
|
||||
int large_image_width;
|
||||
int large_image_height;
|
||||
int medium_image_width;
|
||||
int medium_image_height;
|
||||
int small_image_width;
|
||||
int small_image_height;
|
||||
|
||||
bool broadcast_large_image;
|
||||
bool broadcast_medium_image;
|
||||
bool broadcast_small_image;
|
||||
|
||||
std::string large_image_node_name;
|
||||
std::string medium_image_node_name;
|
||||
std::string small_image_node_name;
|
||||
|
||||
image_transport::ImageTransport *large_image_transport;
|
||||
image_transport::ImageTransport *medium_image_transport;
|
||||
image_transport::ImageTransport *small_image_transport;
|
||||
|
||||
image_transport::Publisher large_image_publisher;
|
||||
image_transport::Publisher medium_image_publisher;
|
||||
image_transport::Publisher small_image_publisher;
|
||||
|
||||
ros::Subscriber control_subscriber;
|
||||
|
||||
cv::Mat image_black;
|
||||
|
||||
cv::Mat image_rtsp_raw;
|
||||
cv::Mat image_rtsp_scaled;
|
||||
cv::Mat image_large;
|
||||
cv::Mat image_medium;
|
||||
cv::Mat image_small;
|
||||
|
||||
sensor_msgs::ImagePtr large_image_message;
|
||||
sensor_msgs::ImagePtr medium_image_message;
|
||||
sensor_msgs::ImagePtr small_image_message;
|
||||
|
||||
};
|
||||
|
||||
int main(int argc, char** argv)
|
||||
{
|
||||
RoverCamera camera(argc, argv);
|
||||
camera.run();
|
||||
}
|
||||
@@ -0,0 +1,88 @@
|
||||
#include <string>
|
||||
#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 medium_image_width;
|
||||
int medium_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("medium_image_width", medium_image_width, 640);
|
||||
node_handle.param("medium_image_height", medium_image_height, 360);
|
||||
node_handle.param("small_image_width", small_image_width, 256);
|
||||
node_handle.param("small_image_height", small_image_height, 144);
|
||||
|
||||
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()){
|
||||
return -1;
|
||||
}
|
||||
|
||||
std::string large_image_node_name = "image_" + std::to_string(large_image_width) + "x" + std::to_string(large_image_height);
|
||||
std::string medium_image_node_name = "image_" + std::to_string(medium_image_width) + "x" + std::to_string(medium_image_height);
|
||||
std::string small_image_node_name = "image_" + std::to_string(small_image_width) + "x" + std::to_string(small_image_height);
|
||||
|
||||
image_transport::ImageTransport large_image_transport(node_handle);
|
||||
image_transport::ImageTransport medium_image_transport(node_handle);
|
||||
image_transport::ImageTransport small_image_transport(node_handle);
|
||||
|
||||
image_transport::Publisher large_image_publisher = large_image_transport.advertise(large_image_node_name, 1);
|
||||
image_transport::Publisher medium_image_publisher = medium_image_transport.advertise(medium_image_node_name, 1);
|
||||
image_transport::Publisher small_image_publisher = small_image_transport.advertise(small_image_node_name, 1);
|
||||
|
||||
cv::Mat image_large;
|
||||
cv::Mat image_medium;
|
||||
cv::Mat image_small;
|
||||
|
||||
ros::Rate loop_rate(fps + 2);
|
||||
|
||||
while (ros::ok()) {
|
||||
|
||||
cap.read(image_large);
|
||||
|
||||
if(!image_large.empty()){
|
||||
cv::resize(image_large, image_medium, cv::Size(medium_image_width, medium_image_height));
|
||||
cv::resize(image_medium, image_small, cv::Size(small_image_width, small_image_height));
|
||||
|
||||
sensor_msgs::ImagePtr large_image_message = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_large).toImageMsg();
|
||||
sensor_msgs::ImagePtr medium_image_message = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_medium).toImageMsg();
|
||||
sensor_msgs::ImagePtr small_image_message = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_small).toImageMsg();
|
||||
|
||||
large_image_publisher.publish(large_image_message);
|
||||
medium_image_publisher.publish(medium_image_message);
|
||||
small_image_publisher.publish(small_image_message);
|
||||
}
|
||||
|
||||
ros::spinOnce();
|
||||
loop_rate.sleep();
|
||||
}
|
||||
|
||||
cap.release();
|
||||
}
|
||||
Reference in New Issue
Block a user