mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-09 02:31:14 +00:00
Added new camera node, finished up most of UDEV with real names
This commit is contained in:
43
rover/tutorial/CMakeLists.txt
Normal file
43
rover/tutorial/CMakeLists.txt
Normal file
@@ -0,0 +1,43 @@
|
||||
cmake_minimum_required(VERSION 2.8)
|
||||
project(image_transport_tutorial)
|
||||
|
||||
find_package(catkin REQUIRED COMPONENTS cv_bridge image_transport message_generation sensor_msgs)
|
||||
|
||||
# add the resized image message
|
||||
add_message_files(DIRECTORY msg
|
||||
FILES ResizedImage.msg
|
||||
)
|
||||
generate_messages(DEPENDENCIES sensor_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(my_publisher src/my_publisher.cpp)
|
||||
add_dependencies(my_publisher ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
|
||||
target_link_libraries(my_publisher ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
|
||||
|
||||
# add the subscriber example
|
||||
#add_executable(my_subscriber src/my_subscriber.cpp)
|
||||
#add_dependencies(my_subscriber ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
|
||||
#target_link_libraries(my_subscriber ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
|
||||
|
||||
# add the plugin example
|
||||
#add_library(resized_publisher src/manifest.cpp src/resized_publisher.cpp src/resized_subscriber.cpp)
|
||||
#add_dependencies(resized_publisher ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
|
||||
#target_link_libraries(resized_publisher ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
|
||||
|
||||
|
||||
# Mark executables and/or libraries for installation
|
||||
install(TARGETS my_publisher
|
||||
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,15 @@
|
||||
#include <image_transport/simple_publisher_plugin.h>
|
||||
#include <image_transport_tutorial/ResizedImage.h>
|
||||
|
||||
class ResizedPublisher : public image_transport::SimplePublisherPlugin<image_transport_tutorial::ResizedImage>
|
||||
{
|
||||
public:
|
||||
virtual std::string getTransportName() const
|
||||
{
|
||||
return "resized";
|
||||
}
|
||||
|
||||
protected:
|
||||
virtual void publish(const sensor_msgs::Image& message,
|
||||
const PublishFn& publish_fn) const;
|
||||
};
|
||||
@@ -0,0 +1,17 @@
|
||||
#include <image_transport/simple_subscriber_plugin.h>
|
||||
#include <image_transport_tutorial/ResizedImage.h>
|
||||
|
||||
class ResizedSubscriber : public image_transport::SimpleSubscriberPlugin<image_transport_tutorial::ResizedImage>
|
||||
{
|
||||
public:
|
||||
virtual ~ResizedSubscriber() {}
|
||||
|
||||
virtual std::string getTransportName() const
|
||||
{
|
||||
return "resized";
|
||||
}
|
||||
|
||||
protected:
|
||||
virtual void internalCallback(const typename image_transport_tutorial::ResizedImage::ConstPtr& message,
|
||||
const Callback& user_cb);
|
||||
};
|
||||
3
rover/tutorial/msg/ResizedImage.msg
Normal file
3
rover/tutorial/msg/ResizedImage.msg
Normal file
@@ -0,0 +1,3 @@
|
||||
uint32 original_height
|
||||
uint32 original_width
|
||||
sensor_msgs/Image image
|
||||
26
rover/tutorial/package.xml
Normal file
26
rover/tutorial/package.xml
Normal file
@@ -0,0 +1,26 @@
|
||||
<package>
|
||||
<name>image_transport_tutorial</name>
|
||||
<version>0.0.0</version>
|
||||
<description>Tutorial for image_transport. This is useful for the tutorials at http://wiki.ros.org/image_transport/Tutorials/</description>
|
||||
<author>Vincent Rabaud</author>
|
||||
<maintainer email="vincent.rabaud@gmail.com">Vincent Rabaud</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>
|
||||
|
||||
<export>
|
||||
<image_transport plugin="${prefix}/resized_plugins.xml"/>
|
||||
</export>
|
||||
</package>
|
||||
13
rover/tutorial/resized_plugins.xml
Normal file
13
rover/tutorial/resized_plugins.xml
Normal file
@@ -0,0 +1,13 @@
|
||||
<library path="lib/libresized_image_transport">
|
||||
<class name="resized_pub" type="ResizedPublisher" base_class_type="image_transport::PublisherPlugin">
|
||||
<description>
|
||||
This plugin publishes a decimated version of the image.
|
||||
</description>
|
||||
</class>
|
||||
|
||||
<class name="resized_sub" type="ResizedSubscriber" base_class_type="image_transport::SubscriberPlugin">
|
||||
<description>
|
||||
This plugin rescales a decimated image to its original size.
|
||||
</description>
|
||||
</class>
|
||||
</library>
|
||||
7
rover/tutorial/src/manifest.cpp
Normal file
7
rover/tutorial/src/manifest.cpp
Normal file
@@ -0,0 +1,7 @@
|
||||
#include <pluginlib/class_list_macros.h>
|
||||
#include <image_transport_tutorial/resized_publisher.h>
|
||||
#include <image_transport_tutorial/resized_subscriber.h>
|
||||
|
||||
PLUGINLIB_EXPORT_CLASS(ResizedPublisher, image_transport::PublisherPlugin)
|
||||
|
||||
PLUGINLIB_EXPORT_CLASS(ResizedSubscriber, image_transport::SubscriberPlugin)
|
||||
74
rover/tutorial/src/my_publisher.cpp
Normal file
74
rover/tutorial/src/my_publisher.cpp
Normal file
@@ -0,0 +1,74 @@
|
||||
#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();
|
||||
}
|
||||
}
|
||||
|
||||
29
rover/tutorial/src/my_subscriber.cpp
Normal file
29
rover/tutorial/src/my_subscriber.cpp
Normal file
@@ -0,0 +1,29 @@
|
||||
#include <ros/ros.h>
|
||||
#include <image_transport/image_transport.h>
|
||||
#include <opencv2/highgui/highgui.hpp>
|
||||
#include <cv_bridge/cv_bridge.h>
|
||||
|
||||
void imageCallback(const sensor_msgs::ImageConstPtr& msg)
|
||||
{
|
||||
try
|
||||
{
|
||||
cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image);
|
||||
cv::waitKey(10);
|
||||
}
|
||||
catch (cv_bridge::Exception& e)
|
||||
{
|
||||
ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "image_listener");
|
||||
ros::NodeHandle nh;
|
||||
cv::namedWindow("view");
|
||||
cv::startWindowThread();
|
||||
image_transport::ImageTransport it(nh);
|
||||
image_transport::Subscriber sub = it.subscribe("camera/image", 1, imageCallback);
|
||||
ros::spin();
|
||||
cv::destroyWindow("view");
|
||||
}
|
||||
37
rover/tutorial/src/resized_publisher.cpp
Normal file
37
rover/tutorial/src/resized_publisher.cpp
Normal file
@@ -0,0 +1,37 @@
|
||||
#include <image_transport_tutorial/resized_publisher.h>
|
||||
#include <opencv2/imgproc/imgproc.hpp>
|
||||
#include <cv_bridge/cv_bridge.h>
|
||||
|
||||
void ResizedPublisher::publish(const sensor_msgs::Image& message,
|
||||
const PublishFn& publish_fn) const
|
||||
{
|
||||
cv::Mat cv_image;
|
||||
boost::shared_ptr<void const> tracked_object;
|
||||
try
|
||||
{
|
||||
cv_image = cv_bridge::toCvShare(message, tracked_object, message.encoding)->image;
|
||||
}
|
||||
catch (cv::Exception &e)
|
||||
{
|
||||
ROS_ERROR("Could not convert from '%s' to '%s'.", message.encoding.c_str(), message.encoding.c_str());
|
||||
return;
|
||||
}
|
||||
|
||||
// Retrieve subsampling factor from the parameter server
|
||||
double subsampling_factor;
|
||||
std::string param_name;
|
||||
nh().param<double>("resized_image_transport_subsampling_factor", subsampling_factor, 2.0);
|
||||
|
||||
// Rescale image
|
||||
int new_width = cv_image.cols / subsampling_factor + 0.5;
|
||||
int new_height = cv_image.rows / subsampling_factor + 0.5;
|
||||
cv::Mat buffer;
|
||||
cv::resize(cv_image, buffer, cv::Size(new_width, new_height));
|
||||
|
||||
// Set up ResizedImage and publish
|
||||
image_transport_tutorial::ResizedImage resized_image;
|
||||
resized_image.original_height = cv_image.rows;
|
||||
resized_image.original_width = cv_image.cols;
|
||||
resized_image.image = *(cv_bridge::CvImage(message.header, "bgr8", cv_image).toImageMsg());
|
||||
publish_fn(resized_image);
|
||||
}
|
||||
18
rover/tutorial/src/resized_subscriber.cpp
Normal file
18
rover/tutorial/src/resized_subscriber.cpp
Normal file
@@ -0,0 +1,18 @@
|
||||
#include <image_transport_tutorial/resized_subscriber.h>
|
||||
#include <cv_bridge/cv_bridge.h>
|
||||
#include <opencv2/imgproc/imgproc.hpp>
|
||||
|
||||
void ResizedSubscriber::internalCallback(const image_transport_tutorial::ResizedImage::ConstPtr& msg,
|
||||
const Callback& user_cb)
|
||||
{
|
||||
// This is only for optimization, not to copy the image
|
||||
boost::shared_ptr<void const> tracked_object_tmp;
|
||||
cv::Mat img_rsz = cv_bridge::toCvShare(msg->image, tracked_object_tmp)->image;
|
||||
// Resize the image to its original size
|
||||
cv::Mat img_restored;
|
||||
cv::resize(img_rsz, img_restored, cv::Size(msg->original_width, msg->original_height));
|
||||
|
||||
// Call the user callback with the restored image
|
||||
cv_bridge::CvImage cv_img(msg->image.header, msg->image.encoding, img_restored);
|
||||
user_cb(cv_img.toImageMsg());
|
||||
};
|
||||
Reference in New Issue
Block a user