Go to the documentation of this file.
2 #include <gtest/gtest.h>
3 #include <camera_calibration_parsers/parse.h>
5 #include <opencv2/highgui/highgui.hpp>
8 #include <boost/foreach.hpp>
19 if (camera_ns ==
"/camera")
20 throw "Must remap 'camera' to the camera namespace.";
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.";
36 cv::Mat img = cv::imread(raw_image_file, 0);
39 if (!camera_calibration_parsers::readCalibration(cam_info_file, cam_name,
cam_info))
40 throw "Failed to read camera info file.";
76 void callback(
const sensor_msgs::ImageConstPtr& msg)
94 int main(
int argc,
char** argv)
96 ros::init(argc, argv,
"imageproc_rostest");
97 testing::InitGoogleTest(&argc, argv);
98 return RUN_ALL_TESTS();
TEST_F(ImageProcTest, monoSubscription)
sensor_msgs::ImagePtr toImageMsg() const
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void callback(const sensor_msgs::ImageConstPtr &msg)
bool getParam(const std::string &key, bool &b) const
ROSCPP_DECL void shutdown()
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
int main(int argc, char **argv)
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
std::string resolveName(const std::string &name, bool remap=true) const
std::vector< TopicInfo > V_TopicInfo
std::string topic_rect_color
sensor_msgs::ImagePtr raw_image
sensor_msgs::CameraInfo cam_info
image_transport::CameraPublisher cam_pub
image_proc
Author(s): Patrick Mihelich, Kurt Konolige, Jeremy Leibs
autogenerated on Wed Jan 24 2024 03:57:17