Go to the documentation of this file. 1 #include <gtest/gtest.h>
5 #include <opencv2/highgui/highgui.hpp>
8 #include "dnn_detect/DetectedObject.h"
9 #include "dnn_detect/DetectedObjectArray.h"
10 #include "dnn_detect/Detect.h"
12 #include <boost/thread/thread.hpp>
14 #if CV_MAJOR_VERSION < 4
15 #define IMREAD_COLOR_MODE CV_LOAD_IMAGE_COLOR
17 #define IMREAD_COLOR_MODE cv::IMREAD_COLOR
70 for (
const auto& obj : results.objects) {
71 if (obj.class_name ==
"cat") {
81 while (nh.ok() && !got_object && !got_cat) {
82 publish_image(
"cat.jpg");
90 int main(
int argc,
char** argv)
93 testing::InitGoogleTest(&argc, argv);
95 return RUN_ALL_TESTS();
int main(int argc, char **argv)
ros::Subscriber object_sub
sensor_msgs::ImagePtr toImageMsg() const
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
image_transport::ImageTransport * it
bool getParam(const std::string &key, bool &b) const
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void spinOnce()
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Publisher image_pub
std::string image_directory
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void publish(const sensor_msgs::Image &message) const
void publish_image(std::string file)
TEST_F(DnnImagesTest, cat)
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
#define IMREAD_COLOR_MODE
void object_callback(const dnn_detect::DetectedObjectArray &results)
dnn_detect
Author(s): Jim Vaughan
autogenerated on Wed Mar 2 2022 00:13:09