rostest.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <gtest/gtest.h>
3 #include <camera_calibration_parsers/parse.h>
4 #include <cv_bridge/cv_bridge.h>
5 #include <opencv2/highgui/highgui.hpp>
7 
8 #include <boost/foreach.hpp>
9 
10 class ImageProcTest : public testing::Test
11 {
12 protected:
13  virtual void SetUp()
14  {
15  ros::NodeHandle local_nh("~");
16 
17  // Determine topic names
18  std::string camera_ns = nh.resolveName("camera") + "/";
19  if (camera_ns == "/camera")
20  throw "Must remap 'camera' to the camera namespace.";
21  topic_raw = camera_ns + "image_raw";
22  topic_mono = camera_ns + "image_mono";
23  topic_rect = camera_ns + "image_rect";
24  topic_color = camera_ns + "image_color";
25  topic_rect_color = camera_ns + "image_rect_color";
26 
27  // Load raw image and cam info
29  std::string raw_image_file, cam_info_file;
30  if (!local_nh.getParam("raw_image_file", raw_image_file))
31  throw "Must set parameter ~raw_image_file.";
32  if (!local_nh.getParam("camera_info_file", cam_info_file))
33  throw "Must set parameter ~camera_info_file.";
34 
36  cv::Mat img = cv::imread(raw_image_file, 0);
37  raw_image = cv_bridge::CvImage(std_msgs::Header(), "mono8", img).toImageMsg();
38  std::string cam_name;
39  if (!camera_calibration_parsers::readCalibration(cam_info_file, cam_name, cam_info))
40  throw "Failed to read camera info file.";
41 
42  // Create raw camera publisher
45 
46  // Wait for image_proc to be operational
48  while (true) {
49  if (ros::master::getTopics(topics)) {
50  BOOST_FOREACH(ros::master::TopicInfo& topic, topics) {
51  if (topic.name == topic_rect_color)
52  return;
53  }
54  }
55  ros::Duration(0.5).sleep();
56  }
57  }
58 
60  std::string topic_raw;
61  std::string topic_mono;
62  std::string topic_rect;
63  std::string topic_color;
64  std::string topic_rect_color;
65 
66  sensor_msgs::ImagePtr raw_image;
67  sensor_msgs::CameraInfo cam_info;
69 
70  void publishRaw()
71  {
73  }
74 };
75 
76 void callback(const sensor_msgs::ImageConstPtr& msg)
77 {
78  ROS_FATAL("Got an image");
79  ros::shutdown();
80 }
81 
82 TEST_F(ImageProcTest, monoSubscription)
83 {
84  ROS_INFO("In test. Subscribing.");
85  ros::Subscriber mono_sub = nh.subscribe(topic_mono, 1, callback);
86  ROS_INFO("Publishing.");
87  publishRaw();
88 
89  ROS_INFO("Spinning.");
90  ros::spin();
91  ROS_INFO("Done.");
92 }
93 
94 int main(int argc, char** argv)
95 {
96  ros::init(argc, argv, "imageproc_rostest");
97  testing::InitGoogleTest(&argc, argv);
98  return RUN_ALL_TESTS();
99 }
TEST_F
TEST_F(ImageProcTest, monoSubscription)
Definition: rostest.cpp:82
ImageProcTest::publishRaw
void publishRaw()
Definition: rostest.cpp:70
image_transport::ImageTransport
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
callback
void callback(const sensor_msgs::ImageConstPtr &msg)
Definition: rostest.cpp:76
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
ImageProcTest::nh
ros::NodeHandle nh
Definition: rostest.cpp:59
ros::shutdown
ROSCPP_DECL void shutdown()
ImageProcTest::topic_rect
std::string topic_rect
Definition: rostest.cpp:62
image_transport::CameraPublisher::publish
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
main
int main(int argc, char **argv)
Definition: rostest.cpp:94
ros::master::getTopics
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
image_transport::ImageTransport::advertiseCamera
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
ImageProcTest::SetUp
virtual void SetUp()
Definition: rostest.cpp:13
ros::master::V_TopicInfo
std::vector< TopicInfo > V_TopicInfo
ImageProcTest::topic_rect_color
std::string topic_rect_color
Definition: rostest.cpp:64
ImageProcTest::raw_image
sensor_msgs::ImagePtr raw_image
Definition: rostest.cpp:66
image_transport::CameraPublisher
ImageProcTest::topic_mono
std::string topic_mono
Definition: rostest.cpp:61
ROS_FATAL
#define ROS_FATAL(...)
image_transport.h
cv_bridge.h
cv_bridge::CvImage
ImageProcTest::topic_color
std::string topic_color
Definition: rostest.cpp:63
ros::spin
ROSCPP_DECL void spin()
ros::Duration::sleep
bool sleep() const
ImageProcTest::cam_info
sensor_msgs::CameraInfo cam_info
Definition: rostest.cpp:67
ImageProcTest::cam_pub
image_transport::CameraPublisher cam_pub
Definition: rostest.cpp:68
ROS_INFO
#define ROS_INFO(...)
ImageProcTest::topic_raw
std::string topic_raw
Definition: rostest.cpp:60
ros::master::TopicInfo
ros::Duration
ImageProcTest
Definition: rostest.cpp:10
ros::NodeHandle
ros::Subscriber
ros::master::TopicInfo::name
std::string name


image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Wed Jan 24 2024 03:57:17