00001 #include <ros/ros.h>
00002 #include <gtest/gtest.h>
00003 #include <camera_calibration_parsers/parse.h>
00004 #include <opencv/cv.h>
00005 #include <opencv/highgui.h>
00006 #include <cv_bridge/CvBridge.h>
00007 #include <image_transport/image_transport.h>
00008
00009 #include <boost/foreach.hpp>
00010
00011 class ImageProcTest : public testing::Test
00012 {
00013 protected:
00014 virtual void SetUp()
00015 {
00016 ros::NodeHandle local_nh("~");
00017
00018
00019 std::string camera_ns = nh.resolveName("camera") + "/";
00020 if (camera_ns == "/camera")
00021 throw "Must remap 'camera' to the camera namespace.";
00022 topic_raw = camera_ns + "image_raw";
00023 topic_mono = camera_ns + "image_mono";
00024 topic_rect = camera_ns + "image_rect";
00025 topic_color = camera_ns + "image_color";
00026 topic_rect_color = camera_ns + "image_rect_color";
00027
00028
00030 std::string raw_image_file, cam_info_file;
00031 if (!local_nh.getParam("raw_image_file", raw_image_file))
00032 throw "Must set parameter ~raw_image_file.";
00033 if (!local_nh.getParam("camera_info_file", cam_info_file))
00034 throw "Must set parameter ~camera_info_file.";
00035
00037 cv::Ptr<IplImage> img = cvLoadImage(raw_image_file.c_str(), 0);
00038 raw_image = sensor_msgs::CvBridge::cvToImgMsg(img, "mono8");
00039 std::string cam_name;
00040 if (!camera_calibration_parsers::readCalibration(cam_info_file, cam_name, cam_info))
00041 throw "Failed to read camera info file.";
00042
00043
00044 image_transport::ImageTransport it(nh);
00045 cam_pub = it.advertiseCamera(topic_raw, 1);
00046
00047
00048 ros::master::V_TopicInfo topics;
00049 while (true) {
00050 if (ros::master::getTopics(topics)) {
00051 BOOST_FOREACH(ros::master::TopicInfo& topic, topics) {
00052 if (topic.name == topic_rect_color)
00053 return;
00054 }
00055 }
00056 ros::Duration(0.5).sleep();
00057 }
00058 }
00059
00060 ros::NodeHandle nh;
00061 std::string topic_raw;
00062 std::string topic_mono;
00063 std::string topic_rect;
00064 std::string topic_color;
00065 std::string topic_rect_color;
00066
00067 sensor_msgs::ImagePtr raw_image;
00068 sensor_msgs::CameraInfo cam_info;
00069 image_transport::CameraPublisher cam_pub;
00070
00071 void publishRaw()
00072 {
00073 cam_pub.publish(*raw_image, cam_info);
00074 }
00075 };
00076
00077 void callback(const sensor_msgs::ImageConstPtr& msg)
00078 {
00079 ROS_FATAL("Got an image");
00080 ros::shutdown();
00081 }
00082
00083 TEST_F(ImageProcTest, monoSubscription)
00084 {
00085 ROS_INFO("In test. Subscribing.");
00086 ros::Subscriber mono_sub = nh.subscribe(topic_mono, 1, callback);
00087 ROS_INFO("Publishing.");
00088 publishRaw();
00089
00090 ROS_INFO("Spinning.");
00091 ros::spin();
00092 ROS_INFO("Done.");
00093 }
00094
00095 int main(int argc, char** argv)
00096 {
00097 ros::init(argc, argv, "imageproc_rostest");
00098 testing::InitGoogleTest(&argc, argv);
00099 return RUN_ALL_TESTS();
00100 }