mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 18:21:15 +00:00
MAJOR refactor of software layout. Needed as ground station and rover both need access to shared packages.
This commit is contained in:
31
software/ros_packages/rover_camera/CMakeLists.txt
Normal file
31
software/ros_packages/rover_camera/CMakeLists.txt
Normal file
@@ -0,0 +1,31 @@
|
||||
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)
|
||||
|
||||
# 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}
|
||||
#)
|
||||
18
software/ros_packages/rover_camera/launch/example.launch
Normal file
18
software/ros_packages/rover_camera/launch/example.launch
Normal file
@@ -0,0 +1,18 @@
|
||||
<launch>
|
||||
<group ns="cameras">
|
||||
<node name="camera_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="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="camera_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>
|
||||
23
software/ros_packages/rover_camera/package.xml
Normal file
23
software/ros_packages/rover_camera/package.xml
Normal 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>
|
||||
88
software/ros_packages/rover_camera/src/rover_camera.cpp
Normal file
88
software/ros_packages/rover_camera/src/rover_camera.cpp
Normal file
@@ -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() == false){
|
||||
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